easy_robot_control.launch package

Public and customizable launch API for the motion stack

Submodules

easy_robot_control.launch.builder module

API to generate launch files

easy_robot_control.launch.builder.T = TypeVar(T)

Type:    TypeVar

Invariant TypeVar.

class easy_robot_control.launch.builder.LevelBuilder(robot_name, leg_dict, params_overwrite={})[source]

Bases: object

Builds a launcher for the motion stack generating your nodes

Note

This class is meant to be overloaded and changed for your robot. Refere to Launch API

Parameters:
  • robot_name (str) – Name of your robot URDF

  • leg_dict (Mapping[int, str | int]) – Dictionary linking leg number to end effector name. This informs the API of the number of legs and nodes to launch.

  • params_overwrite (Dict[str, Any]) – Will overwrite the default parameters

Example:

from easy_robot_control.launch.builder import LevelBuilder
ROBOT_NAME = "moonbot_7"  # name of the xacro to load
LEGS_DIC = {
    1: "end1",
    2: "end2",
    3: "end3",
    4: "end4",
}
lvl_builder = LevelBuilder(robot_name=ROBOT_NAME, leg_dict=LEGS_DIC)
def generate_launch_description():
    return lvl_builder.make_description()
make_description(levels=None)[source]

Return the launch description for ros2

Example:

def generate_launch_description():
    return lvl_builder.make_description()
Parameters:

levels (List[List[Node]] | None) – list of levels, levels being a list of nodes to be launched

Returns:

launch description to launch all the nodes

Return type:

LaunchDescription

process_CLI_args()[source]
lvl_to_launch()[source]
Returns:

List of int corresponding to the motion stack levels to start

Return type:

List[int]

get_xacro_path()[source]
Returns:

Path to the robot’s xacro file

Return type:

str

generate_global_params()[source]

Generates parameters shared by all nodes. Based on the default params and overwrites.

make_leg_param(leg_index, ee_name)[source]

Based on the leg index/number (and end-effector), returns the parameters corresponding to the leg

Parameters:
  • leg_index (int) – leg number to create the params for

  • ee_name (None | str | int) – (Optional) end effector name or number

Raises:

Exception – Exception(f”{leg_index} not in self.legs_dic”)

Returns:

Dictionary of ROS2 parameters

Return type:

Dict

lvl1_params()[source]

Returns parameters for all lvl1 nodes to be launched

Returns:

List of ros2 parameter dictionary, one per node.

Return type:

List[Dict]

lvl2_params()[source]

Returns parameters for all lvl2 nodes to be launched

Returns:

List of ros2 parameter dictionary, one per node.

Return type:

List[Dict]

lvl3_params()[source]

Returns parameters for all lvl3 nodes to be launched

Returns:

List of ros2 parameter dictionary, one per node.

Return type:

List[Dict]

lvl4_params()[source]

Returns parameters for all lvl4 nodes to be launched

Returns:

List of ros2 parameter dictionary, one per node.

Return type:

List[Dict]

lvl5_params()[source]

Returns parameters for all lvl5 nodes to be launched

Returns:

List of ros2 parameter dictionary, one per node.

Return type:

List[Dict]

state_publisher_lvl1()[source]

Prepares all nodes meant to publish the state of the robot to external tools.

Along each lvl1 node, it creates:
  • One (customized) joint_state_publisher continuously publishing joint angles

  • One robot_state_publisher continuously publishing robot TF and description.

Returns:

List of Nodes to be launched (empty if lvl1 is not to be launched)

Return type:

List[Node]

get_node_lvl1(params)[source]
Return type:

Node

Parameters:

params (Dict[str, Any])

get_node_lvl2(params)[source]
Return type:

Node

Parameters:

params (Dict[str, Any])

get_node_lvl3(params)[source]
Return type:

Node

Parameters:

params (Dict[str, Any])

get_node_lvl4(params)[source]
Return type:

Node

Parameters:

params (Dict[str, Any])

get_node_lvl5(params)[source]
Return type:

Node

Parameters:

params (Dict[str, Any])

lvl1()[source]
Return type:

List[Node]

lvl2()[source]
Return type:

List[Node]

lvl3()[source]
Return type:

List[Node]

lvl4()[source]
Return type:

List[Node]

lvl5()[source]
Return type:

List[Node]

make_levels()[source]
Return type:

List[List[Node]]

easy_robot_control.launch.builder.get_cli_argument(arg_name, default)[source]

Returns the CLI argument as a string, or default is none inputed. Can be much better optimised, I don’t care.

Return type:

Union[~T, str]

Parameters:
  • arg_name (str)

  • default (T)

easy_robot_control.launch.default_params module

Provides and explains all parameters to launch the motion stack

easy_robot_control.launch.default_params.default_params = {'WAIT_FOR_LOWER_LEVEL': True, 'add_joints': [''], 'always_write_position': False, 'control_rate': 30.0, 'end_effector_name': 0, 'ignore_limits': False, 'leg_list': [0], 'leg_number': 0, 'limit_margin': 0.0, 'mirror_angle': False, 'mvmt_update_rate': 10.0, 'number_of_legs': None, 'pure_topic_remap': False, 'robot_name': None, 'services_to_wait': [''], 'speed_mode': False, 'start_coord': [0.0, 0.0, 0.0], 'start_effector_name': '', 'std_movement_time': 2, 'urdf_path': None, 'wheel_size_mm': 230}

Type:    Dict[str, Any]

the default parameters of the motion stack

 1 default_params: Dict[str, Any] = {  # does this work
 2     # you must set these in your own launcher
 3     #        #
 4     #        #
 5     "robot_name": None,  #: (str) Name of the robot, not critical
 6     "urdf_path": None,  # path to the xacro or urdf to load
 7     "number_of_legs": None,  # number of legs in your robot (not used by lvl 1-2-3)
 8     "leg_number": 0,  # number associated with a leg,
 9     # if serveral lvl 1-2-3 are running, it is recommanded to use different numbers
10     "end_effector_name": 0,  # end effector associated with a leg, (the most important)
11     # the kinematic chain used for IK will go
12     # from the root link of the URDF (usually base_link)
13     # to the end effector link (specified in this parameter).
14     # the URDF will be parsed to find this link name. Make sure it exists.
15     # you can also provide a number (as a string) instead of a link_name. If you do this
16     # the Nth longest kinematic path (sequence of link where each link is connected to
17     # exactly one other link) from the root of the URDF will be used for IK
18     # Basically, if you use only one limb, set this as "0", and it will pick the right ee.
19     "leg_list": [0],  # list of leg numbers
20     #        #
21     #        #
22     "std_movement_time": 2,  # time lvl3 takes to execute a trajectory
23     "mvmt_update_rate": 10.0,  # update rate used through out the stack
24     "control_rate": 30.0,  # update rate for speed control PID only
25     "start_coord": [0 / 1000, 0 / 1000, 0 / 1000],  # starting position
26     # (only affects rviz for now).
27     # if set to [np.nan,np.nan,np.nan], world->base_link publishing is disabled.
28     # lvl1 is publishing this TF, so if you have several lvl1,
29     # only one should have this opition enabled
30     "add_joints": [""],  # manually adds joints for lvl1 if they are not in the urdf
31     "mirror_angle": False,  # lvl1 assumes position sensor data is the last sent command
32     "always_write_position": False,  # deprecated ?
33     "start_effector_name": "",  # setting this manually, works with the motion stack,
34     # but not for Rviz and ros2's tf, so be carefull.
35     # In ros, the baselink must be the root of the tf tree, it cannot have a parent
36     # and there can only be one baselink.
37     # Leaving this empty and properly setting your URDF baselink is recommended.
38     "wheel_size_mm": 230,  # deprecated ?
39     "pure_topic_remap": False,  # activates the pure_remap.py remapping
40     "speed_mode": False,  # lvl1 will send speed commands to the motors, using angle readings as feedback for a PID.
41     "services_to_wait": [""],  # List of services to wait for before initializing
42     "WAIT_FOR_LOWER_LEVEL": True,  # waits for services of lower level before initializing
43     "ignore_limits": False,  # joint limits set in the URDF will be ignored
44     "limit_margin": 0.0,  # adds a additional margin to the limits of the URDF (in rad)
easy_robot_control.launch.default_params.get_xacro_path(robot_name)[source]

retieves the .urdf/.xacro path in the install share folder

Parameters:

robot_name (str) – corresponds to <robot_name>.xacro

Returns:

easy_robot_control.launch.default_params.enforce_params_type(parameters)[source]

enforces types to dic in place

Parameters:

parameters (Dict[str, Any]) – ros2 parameters dictinary

Return type:

None