motion_stack.ros2.default_node package

Default ROS2 nodes provided by the motion stack.

Created using ros2.base_node as the API. Once you understand the API, feel free to overwrite methods of these default nodes in your own class. With this you can change or add behaviors.

Submodules

motion_stack.ros2.default_node.lvl1 module

class motion_stack.ros2.default_node.lvl1.DefaultLvl1[source]

Bases: Lvl1Node

Default implementation of the Joint node of lvl1.

Refer to ros2.base_node.lvl1 for documentation on linking ros2 and python core of lvl1. This only makes use of this base to create the default implementation and give an example.

Publishers:

Topic

Type

Note

joint_commands

JointState

sent to motors (lvl0)

joint_read

JointState

sent to IK (lvl2)

Subscribers:

Topic

Type

Note

joint_states

JointState

coming from sensors (lvl0)

joint_set

JointState

coming from IK (lvl2)

Service server:

Topic

Type

Note

advertise_joints

ReturnJointState

JointState with the name of all joints

Timers:
  • Sends to lvl2, freq.= ROS2_PARAMETER[mvmt_update_rate].

Startup:
  • Sends empty message to lvl0 with only joint names.

alive_srv = (<class 'std_srvs.srv._empty.Empty'>, 'joint_alive')

Type:    Interf

subscribe_to_lvl2(lvl2_input)[source]
Parameters:

lvl2_input (Callable[[List[JState]], Any])

subscribe_to_lvl0(lvl0_input)[source]
Parameters:

lvl0_input (Callable[[List[JState]], Any])

publish_to_lvl0(states)[source]
Parameters:

states (List[JState])

publish_to_lvl2(states)[source]
Parameters:

states (List[JState])

frequently_send_to_lvl2(send_function)[source]
Parameters:

send_function (Callable[[], None])

startup_action(core)[source]
Parameters:

core (JointCore)

motion_stack.ros2.default_node.lvl1.create_advertise_service(node, lvl1)[source]

Creates the advertise_joints service and its callback.

Callback returns a ReturnJointState.Response wich is a JointState with the name of all joints managed by the node. Other field of JointState are not meant to be used, but are filled with the latest data.

Parameters:
  • node (Node) – spinning node

  • lvl1 (JointCore) – lvl1 core

motion_stack.ros2.default_node.lvl1.main(*args, **kwargs)[source]

motion_stack.ros2.default_node.lvl2 module

class motion_stack.ros2.default_node.lvl2.DefaultLvl2[source]

Bases: Lvl2Node

Default implementation of the Joint node of lvl2.

Refer to ros2.base_node.lvl2.Lvl2Node for documentation on linking ros2 and python core of lvl1. This only makes use of this base to create the default implementation and give an example.

alive_srv = (<class 'std_srvs.srv._empty.Empty'>, 'ik_alive')

Type:    Interf

subscribe_to_lvl1(lvl1_input)[source]
Parameters:

lvl1_input (Callable[[List[JState]], Any])

subscribe_to_lvl3(lvl3_input)[source]
Parameters:

lvl3_input (Callable[[Pose], Any])

publish_to_lvl1(states)[source]
Parameters:

states (List[JState])

publish_to_lvl3(pose)[source]
Parameters:

pose (Pose)

startup_action(lvl2)[source]
Parameters:

lvl2 (IKCore)

motion_stack.ros2.default_node.lvl2.main(*args, **kwargs)[source]

motion_stack.ros2.default_node.trial module

class motion_stack.ros2.default_node.trial.TestNode[source]

Bases: Node

async joints_ready()[source]
async ik_ready()[source]
json_step(n)[source]
Parameters:

n (int)

async execute_json()[source]
async zero()[source]
async ik_square()[source]
async ik_circle(samples=20)[source]
Parameters:

samples (int)

async api_demo()[source]
main()[source]
startup()[source]
loop()[source]
motion_stack.ros2.default_node.trial.main(*args)[source]