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

get_pose()[source]

returns the pose of the robot

Returns:

pose of the robot

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

set_prev_point_index(index: int)[source]

sets the index of the previous point in the route

Parameters:

index (int) – index of the previous point

transform_pt_to_bot_frame(point: numpy.array.T)[source]

given a point, returns the point in the robot frame

Parameters:

point (np.array([[float,float,float]]).T) – point to be converted

Returns:

point in the robot frame

Node

path_planner Node

class cordyceps.path_planner.PathPlanner(*args: Any, **kwargs: Any)[source]

Bases: Node

get_path_from_csv(start_pose: geometry_msgs.msg.Pose, filename: str) numpy.array[source]

Generates a path for the virtual structure to follow.

get_routes_callback(request, response)[source]

Generates a path for a robot to follow in order to reach a goal pose.

Parameters:

request (Request) – The request containing the starting pose of the robot.

Returns:

The path that the robot should follow.

cordyceps.path_planner.main(args=None)[source]

vs_assembler Node

class cordyceps.vs_assembler.Assembler(*args: Any, **kwargs: Any)[source]

Bases: Node

add_robot(number_of_robots, robot_number)[source]
get_robot_vs_ref_pose_callback(request, response)[source]

Callback function for the assembler service.

Parameters:
  • request – Request message for the service.

  • response – Response message for the service.

Returns:

The response message with the reference poses for each robot.

cordyceps.vs_assembler.main(args=None)[source]

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.

follow_routes(routes: list[list[tuple[float, float]]])[source]

Publishes the velocities so that the robots follow their routes

Parameters:

routes (list[list[tuple[float, float]]]) – List of routes for each robot.

start_thread_callback(request, response)[source]

Recieves each bot’s path and sends the velocities to follow them

Parameters:
  • request (Request) – Request message for the service.

  • response (Response) – Response message for the service.

cordyceps.vs_controller.main(args=None)[source]

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.

get_parameters()[source]
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.

task_callback(msg: cordyceps_interfaces.msg.Task)[source]

Callback function for the task subscriber. Adds the task to the task queue.

Parameters:

msg (Task) – The task message that is received from the task topic.

task_executor()[source]

Executes the tasks in the task queue.

cordyceps.vs_manager.main(args=None)[source]