Swarm Manager¶
Module to move the swarm and use TrajectoryPlanner
and FormationManager
packages.
SwarmController
class¶
-
class
swarm_controller.
SwarmController
[source]¶ Main class
-
update_swarm_param
(param, value)[source]¶ Update parameter of all swarm
Parameters: - param (str) – Name of parameter
- value (int64) – Parameter value
-
check_collisions
()[source]¶ To check that the minimal distance between each CF is okay.
If actual distance between CF is too small, calls emergency service.
-
update_formation
(formation_goal=None)[source]¶ To change formation of the swarm.
Formation center will be formation_goal if is specified. If not, it will be stay at the same place
Parameters: formation_goal (list, optional) – New formation goal: [x, y, z, yaw]. Defaults to None.
-
go_to_goal
(target_goals=None, land_swarm=False)[source]¶ Controls swarm to move each CF to it’s desired goal while avoiding collisions.
If some CFs are in extra (in formation) will land them.
Handles extra CF landing.
Parameters: - land_swarm (bool, optional) – If true, land swarm to initial pos. Defaults to False.
- goals (dict, optional) – To specify target goals. Used when not in formation mode. Defaults to None.
-
CrazyfliePy
class¶
-
class
swarm_controller.
CrazyfliePy
(cf_id)[source]¶ Link between the swarm manager and a crazyflie.
Controls one robot.
-
call_srv
(srv_name, args=None, kwargs=None)[source]¶ Call a CF service
Parameters: - srv_name (str) – Name of srv to call
- args (list, optional) – Service args. Defaults to None.
- kwargs (dict, optional) – Service kwargs. Defaults to None.
-
update_goal
(goal_name='')[source]¶ Update current goal to one of other CF goal (trajectory, formation or current goal)
Notes: “” or “goal”: Set to current goal “traj” or “trajectory”: Set to goal to trajectory goal “formation: Set goal to formation goal
Parameters: goal_name (str, optional) – To specify goal to set. Defaults to “”.
-