Skip to content

Latest commit

 

History

History
121 lines (82 loc) · 2.94 KB

swarm_controller_ros.rst

File metadata and controls

121 lines (82 loc) · 2.94 KB

swarm_controller

To control flight of the swarm. By using a state machine, this node will determine each crazyflie goal and control it's desired position by publishing to cf-goal.

The goal will change depending of the services called by SwarmAPI.

Note

See /glossary for definition of Swarm and Formation

ROS Features

Subscribed Topics

cf-formation-goal (crazyflie_driver/Position)

Position of the CF in formation

trajectory-goal (crazyflie_driver/Position)

Position of the CF on the trajectory, at each time step

cf-state (std_msgs/String)

Current state of CF

cf-pose (geometry_msgs/PoseStamped)

Current pose of CF

joy-swarm-vel (geometry_msgs/Twist)

Swarm velocity

Published Topics

cf-goal (crazyflie_driver/Position)

Target position of CF

formation-goal-vel (geometry_msgs/Twist)

Formation center goal variation

Services

/take_off_swarm(std_srvs/Empty)

Take off all CFs

/stop_swarm(std_srvs/Empty)

Stop all CFs

/swarm_emergency(std_srvs/Empty)

Emgergency stop of all CFs

/land_swarm(std_srvs/Empty)

Land all CF to their starting position

/get_positions(swarm_manager/GetPositions)

Get current position of CFs

/go_to(swarm_manager/SetGoals)

Move CFs or formation to specified positions

/set_mode(swarm_manger/SetMode)

Set control of swarm_controller

/set_swarm_formation(formation_manager/SetFormation)

Set swarm to a formation

/inc_swarm_scale(std_srvs/Empty)

Increase scale of formation

/dec_swarm_scale(std_srvs/Empty)

Decrease scale of formation

/next_swarm_formation(std_srvs/Empty)

Go to next formation

/prev_swarm_formation(std_srvs/Empty)

Go to previous formation

/traj_found(std_srvs/SetBool)

To call once the trajectory planner is done

/traj_done(std_srvs/Empty)

To call once the trajectory is done

Services Called

/set_formation(formation_manager/SetFormation)

From /ros_architecture/formation_manager

/get_formations_list(formation_manager/GetFormationList)

From /ros_architecture/formation_manager

/formation_inc_scale(std_srvs/Empty)

From /ros_architecture/formation_manager

/formation_dec_scale(std_srvs/Empty)

From /ros_architecture/formation_manager

/set_planner_positions(trajectory_planner/SetPositions)

From /ros_architecture/trajectory_planner

/plan_trajectories(std_srvs/Empty)

From /ros_architecture/trajectory_planner

/pub_trajectories(std_srvs/Empty)

From /ros_architecture/trajectory_planner

Parameters

~n_cf(int)

~take_off_height(float)

~gnd_height(float)

~min_dist(float)

~min_goal_dist(float)