This module exposes APIs that use the ros2 interface (as opposed to pure python API that may lack interface).
ROS2 API to send/receive end-effector IK command / FK state to lvl2 and syncronise multiple limbs.
Bases: object
ROS2 API to send/receive end-effector command/state to lvl2.
One instance is limited to a single limb.
To safely execute ik movement to a target, do not directly use this class, but use IkSyncerRos.
- Parameters:
- node (Node) – Spinning node.
- limb_number (int) – Limb number on which to interface with the ik.
Type: int
Limb number
Type: List[Callable[[‘IkHandler’]]]
Callback executed when the end-effector sensor updates. Argument is this object instance.
Type: Future
Future becoming done when sensor data is available for the end-effector.
End effector pose
- Return type:
Pose
self.ready will be canceled and re-created.
- Returns: Future done the next time end effector pose is received
- Return type:
Future
Sends ik target command to lvl2.
- Parameters: target_pose (Pose)
class motion_stack.api.ros2.ik_api.IkSyncerRos(ik_handlers, interpolation_delta=XyzQuat(xyz=40, quat=0.06981317007977318), on_target_delta=XyzQuat(xyz=40, quat=0.06981317007977318))
Bases: IkSyncer
Controls and syncronises several end-effector, safely executing trajectory to a target.
This class is a ROS2 implementation of the base class: api.ik_syncer.JointSyncer. Refere to it for documentation.
- Parameters:
Executes one step of the task/trajectory.
This must be called frequently in a ros Timer or something else of your liking.
This class is a ROS2 implementation of the base class: api.ik_syncer.JointSyncer. Refere to it for documentation.
- Return type:
Dict[int,Pose]
This class is a ROS2 implementation of the base class: api.ik_syncer.JointSyncer. Refere to it for documentation.
- Parameters: ee_targets (Dict *[*int , Pose ])
This class is a ROS2 implementation of the base class: api.ik_syncer.JointSyncer. Refere to it for documentation.
- Return type:
Type[Future]
ROS2 API to send/receive joint command/state to lvl1 and syncronise multiple joints.
Bases: object
ROS2 API to send/receive joint command/state to lvl1.
One instance is limited to a single limb.
To safely execute joint movement to a target, do not directly use this class, but use JointSyncerRos.
- Parameters:
- node (Node) – Spinning node.
- limb_number (int) – Limb number on which to interface with the joints.
Type: Set[str]
Joint available on the limb
Type: int
Limb number
Type: List[Callable[[‘JointHandler’]]]
Callback executed when the state sensor updates. Argument is this object instance.
Type: Future
Future becoming done when sensor data is available on all tracked joints
Accumulated joint state (sensor).
- Return type:
List[JState]
Starts timer looking for available joints and their data.
- Parameters: tracked (Set *[*str ] | None) – Joints required to be considered ready.
- Returns:
- [0] Future done when all available joints have data.
- [1] Future done when the leg replies with the names of the available joints
- Return type:
Tuple[Future,Future]
Sends joint command to lvl1.
- Parameters: states (List [JState ])
class motion_stack.api.ros2.joint_api.JointSyncerRos(joint_handlers, interpolation_delta=0.08726646259971647, on_target_delta=0.06981317007977318)
Bases: JointSyncer
Controls and syncronises several joints, safely executing trajectory to a target.
This class is a ROS2 implementation of the base class: api.joint_syncer.JointSyncer. Refere to it for documentation.
- Parameters:
- joint_handlers (List [JointHandler ]) – ROS2 objects handling joint communications of several limbs.
- interpolation_delta (float)
- on_target_delta (float)
Executes one step of the task/trajectory.
This must be called frequently in a ros Timer or something else of your liking.
This class is a ROS2 implementation of the base class: api.joint_syncer.JointSyncer. Refere to it for documentation.
- Return type:
Dict[str,JState]
This class is a ROS2 implementation of the base class: api.joint_syncer.JointSyncer. Refere to it for documentation.
- Parameters: states (List [JState ])
Overloaded to automatically create the delta_time function.
This class is a ROS2 implementation of the base class: api.joint_syncer.JointSyncer. Refere to it for documentation.
- Return type:
Future - Parameters:
- target (Dict *[*str , float ])
- delta_time (float | Callable [ [ ] , float ] | None)
This class is a ROS2 implementation of the base class: api.joint_syncer.JointSyncer. Refere to it for documentation.
- Return type:
Type[Future]
motion_stack.api.ros2.offsetter.setup_lvl0_offsetter(node, angle_recovery_path=None, offset_path=None)
- Return type:
Tuple[Timer,Service] - Parameters:
- node (Lvl1Node)
- angle_recovery_path (str | None)
- offset_path (str | None)
Provides StatesToTopics, to be injected in a Node. see the class docstring for details
Return the topic name associated with an attribute and joint.
This is the default implementation. You might want to make your own.
- Parameters:
- attribute (str) – position, velocity or effort
- joint_name (str) – name of the joint
- Returns: name of the associated topic
- Return type:
str
class motion_stack.api.ros2.state_to_topic.StatesToTopic(ros_node, joint_to_topic_name=<function 'default_joint_to_topic_name'>)
Bases: object
Publishes joint states onto individual topics.
Features: : - Publishes a list of JState or a JointStates onto individual Float64 topics
- Provide joint_to_topic_name with the the naming convention you need
- Lazily creates the topics as they are published
: - topics will not be created at startup, but the first time they are used
- publish a state with np.nan instead of None to force the creation.
- Parameters:
- ros_node (Node) – ROS2 node
- joint_to_topic_name (Callable [ *[*str , str ] , str ]) – Function, Args: [attribute, joint_name] Return: [topic_name]. default function:
state_to_topic.default_joint_to_topic_name()
classmethod setup_lvl0_command(lvl1_ros_node, joint_to_topic_name=<function 'default_joint_to_topic_name'>)
All joints will have their own individual float topic.
Applies state_to_topic.StatesToTopic to outgoing motor commands of lvl1.
- Parameters:
- lvl1_ros_node (Lvl1Node) – ROS2 node running lvl1
- joint_to_topic_name (Callable [ *[*str , str ] , str ]) – Function returning the topic name associated with an attribute and joint.
- Return type:
StatesToTopic
publishes a list of JState over float topics (lazily created).
- Parameters: states (Iterable [JState ] | JointState)