cordyceps package
Class
Robot Class
- class cordyceps.Robot.Robot(x, y, theta, name, node: rclpy.node.Node)[source]
Bases:
object
- calculate_carrot(projected_point_index: int, route: list)[source]
given the projected position of a bot in its route, returns the goal (aka lookahead point)
- Parameters:
projected_point_index (int) – index of the projected point
route (list) – list of points
- Returns:
the new goal point
- get_deltas_to_point(goal: numpy.array.T) tuple[float, float, float] [source]
given a goal point, returns the deltas to the goal point
- Parameters:
goal (np.array([[float,float,float]]).T) – goal point
- Returns:
delta s, delta_s_wheelbase, delta theta
- odom_callback(msg: nav_msgs.msg.Odometry)[source]
updates the pose of the robot. Transforms from quaternion to euler angles
- Parameters:
msg (Odometry) – Odometry message
- project_pose(route: list)[source]
given a route, returns the index of the closest point to the robot
- Parameters:
route (list) – list of points
- Returns:
index of the closest point
- publish_velocity(lin_vel: float, ang_vel: float)[source]
publishes the velocity of the robot
- Parameters:
lin_vel (float) – linear velocity
ang_vel (float) – angular velocity
Node
path_planner Node
vs_assembler Node
vs_controller Node
- class cordyceps.vs_controller.ControllerService(*args: Any, **kwargs: Any)[source]
Bases:
Node
- calc_velocities(distances: list[float], thetas: list[float], max_distance: float) list[list[float]] [source]
Calculates the velocities for each robot
- Parameters:
distances (list[float]) – List of distances from the robots to their goals.
thetas (list[float]) – List of angles from the robots to their goals.
max_distance (float) – largest distance a robot travels.
- Returns:
List of velocities for each robot.
- check_thread_state_callback(request, response)[source]
Checks if the thread is still running
- Parameters:
request (Request) – Request message for the service.
response (Response) – Response message for the service.
- Returns:
True if the thread is still running, False otherwise.
vs_manager Node
- class cordyceps.vs_manager.VsManager(*args: Any, **kwargs: Any)[source]
Bases:
Node
- controll_vs(routes: cordyceps_interfaces.msg.RobotRoutes)[source]
Calls the controller service to start the path following.
- Parameters:
paths (RobotPaths) – The paths for each robot.
- request_routes(task: cordyceps_interfaces.msg.Task, vs_ref_pose: list)[source]
Requests the routes from the path planner service.
- Parameters:
task (Task) – The task for which the routes are requested.
vs_ref_pose (list) – The reference poses for each robot.
- Returns:
The routes for each robot.
- request_transformed_bot_poses(task)[source]
Requests the reference poses for each robot from the assembler service.
- Parameters:
task (Task) – The task for which the reference poses are requested.
- Returns:
The reference poses for each robot.