motion_stack.api package
Subpackages
Submodules
motion_stack.api.ik_syncer module
Python API to sync the movement of several end_effectors. This requires ik lvl2 to be running.
Note
The ros2 implementation is available in ros2.ik_api
.
This high level API alows for multi-end-effector control and syncronization (over several legs). This is the base class where, receiving and sending data to motion stack lvl2 is left to be implemented.
- motion_stack.api.ik_syncer.FutureType
placeholder type for a Future (ROS2 Future, asyncio or concurrent)
Alias of
Awaitable
- motion_stack.api.ik_syncer.LimbNumber
A type alias representing the limb number (end effector index).
- motion_stack.api.ik_syncer.MultiPose
A dictionary mapping limb numbers to their corresponding poses.
Alias of
Dict
[int
,Pose
]
- class motion_stack.api.ik_syncer.IkSyncer(interpolation_delta=XyzQuat(xyz=40, quat=0.06981317007977318), on_target_delta=XyzQuat(xyz=40, quat=0.06981317007977318))[source]
Bases:
ABC
One instance controls and syncronises several limbs end-effectors, safely executing trajectory to targets.
Note
This class is an abstract base class, the ros2 implementation is available in
ros2.joint_api.IkSyncerRos
. Hence, parts of this class are left to be implmented by the interface/runtime:IkSyncer.FutureT()
,IkSyncer.sensor()
,IkSyncer.send_to_lvl2()
.Important
IkSyncer.execute()
must be called to compute, update and send the command.One object instance can only execute one target at a time. However, the limbs or targets can change between calls of the same instance, before the previous task is done.
The trajectory interpolates between two points:
The last position (if None: uses sensor, else: last sub-target). This is handled automatically, however
clear
resets the last position to None.The input target.
Several interpolation strategies are available:
LERP:
IkSyncer.lerp()
ASAP:
IkSyncer.asap()
Unsafe:
IkSyncer.unsafe()
- Parameters:
- last_future
Type:
Awaitable
Future of the latest task/trajectory that was run.
- clear()[source]
Resets the trajectory starting point onto the current sensor positions.
Important
- Use when:
The trajectory is stuck unable to interpolate.
External motion happened, thus the last position used by the syncer is no longer valid.
Caution
At task creation, if the syncer applies clear() automatically, SensorSyncWarning is issued. Raise the warning as an error to interupt operation if needed.
- lerp(target)[source]
Starts executing a lerp trajectory toward the target.
LERP: all joints reach the target at the same time.
- Returns:
Future of the task. Done when sensors are on target.
- Return type:
Awaitable
- Parameters:
target (Dict[int, Pose])
- asap(target)[source]
Starts executing a asap trajectory toward the target.
ASAP: (Not Implemented) joints will reach their tagets indepently, as fast as possible.
- Returns:
Future of the task. Done when sensors are on target.
- Return type:
Awaitable
- Parameters:
target (Dict[int, Pose])
- unsafe(target)[source]
Starts executing a unsafe trajectory toward the target.
Unsafe: Similar to ASAP except the final target is sent directly to the IK, so the movement will not stop in case of crash, errors, network issue AND you cannot cancel it.
- Returns:
Future of the task. Done when sensors are on target.
- Return type:
Awaitable
- Parameters:
target (Dict[int, Pose])
- speed_safe(target, delta_time)[source]
A Cartesian speed‐safe trajectory that interprets angular velocity as a rotation vector (axis * rad/s) instead of a quaternion.
- Parameters:
target (Dict[int, VelPose]) – Mapping limb → VelPose, where • VelPose.lin is linear speed (mm/s) • VelPose.rvec is rotational speed vector (axis * rad/s)
delta_time (float | Callable[[], float]) – Either a fixed Δt (s) or a zero‐arg callable returning Δt.
- Returns:
A Future that continuously steps the motion until cancelled.
- Return type:
Awaitable
- abs_from_rel(offset)[source]
Absolute position of the MultiPose that corresponds to the given relative offset.
Example
joint_1 is at 45 deg, offset is 20 deg. Return will be 65 deg.
- abstract send_to_lvl2(ee_targets)[source]
Sends ik command to lvl2.
Important
This method must be implemented by the runtime/interface.
Note
Default ROS2 implementation:
ros2.ik_api.IkSyncerRos.send_to_lvl2()
- Parameters:
states – Ik target to be sent to lvl1
ee_targets (Dict[int, Pose])
- abstract property FutureT
ROS2 Future, asyncio or concurrent.
Important
This method must be implemented by the runtime/interface.
- Default ROS2 implementation::
return rclpy.task.Future
- Returns:
The Future class (not an instance).
- Return type:
Type
[Awaitable
]- Type:
Class of Future to use
- abstract property sensor
Is called when sensor data is need.
Important
This method must be implemented by the runtime/interface.
Note
Default ROS2 implementation:
ros2.joint_api.JointSyncerRos.sensor()
Returns:
- Return type:
Dict
[int
,Pose
]
motion_stack.api.joint_syncer module
Python API to sync the movement of several joints.
Note
The ros2 implementation is available in ros2.joint_api
.
This high level API alows for multi-joint control and syncronization (over several legs). This is the base class where, receiving and sending data to motion stack lvl1 is left to be implemented.
- motion_stack.api.joint_syncer.FutureType
placeholder type for a Future (ROS2 Future, asyncio or concurrent)
Alias of
Awaitable
- class motion_stack.api.joint_syncer.JointSyncer(interpolation_delta=0.08726646259971647, on_target_delta=0.06981317007977318)[source]
Bases:
ABC
One instance controls and syncronises several joints, safely executing trajectory to targets.
Note
This class is an abstract base class, the ros2 implementation is available in
ros2.joint_api.JointSyncerRos
. Hence, parts of this class are left to be implmented by the interface/runtime:JointSyncer.FutureT()
,JointSyncer.sensor()
,JointSyncer.send_to_lvl2()
.Important
JointSyncer.execute()
must be called to compute, update and send the command.One object instance can only execute one target at a time. However, the limbs or targets can change between calls of the same instance, before the previous task is done.
The trajectory interpolates between two points:
The last position (if None: uses sensor, else: last sub-target). This is handled automatically, however
clear
resets the last position to None.The input target.
Several interpolation strategies to reach the target are available:
LERP:
JointSyncer.lerp()
ASAP:
JointSyncer.asap()
Unsafe:
JointSyncer.unsafe()
Speed:
JointSyncer.speed()
- Parameters:
interpolation_delta (float) – (rad) During movement, how much error is allowed from the path. if exceeded, movement slows down.
on_target_delta (float) – (rad) Delta at which the trajectory/task is considered finished and the Future is switched to
done
.
- last_future
Future of the latest task/trajectory that was run.
- clear()[source]
Resets the trajectory starting point onto the current sensor positions.
Important
- Use when:
The trajectory is stuck unable to interpolate.
External motion happened, thus the last position used by the syncer is no longer valid.
Caution
At task creation, if the syncer applies clear() automatically, SensorSyncWarning is issued. Raise the warning as an error to interupt operation if needed.
- lerp(target)[source]
Starts executing a lerp trajectory toward the target.
LERP: all joints reach the target at the same time.
- Parameters:
target (Dict[str, float]) –
key
= joint name ;value
= joint angle- Returns:
Future of the task. Done when sensors are on target.
- Return type:
Awaitable
- asap(target)[source]
Starts executing a asap trajectory toward the target.
ASAP: joints will reach their tagets indepently, as fast as possible
- Parameters:
target (Dict[str, float]) –
key
= joint name ;value
= joint angle- Returns:
Future of the task. Done when sensorare on target.
- Return type:
Awaitable
- unsafe(target)[source]
Starts executing a unsafe trajectory toward the target.
Unsafe: Similar to ASAP except the final target is sent directly to the motor, so the movement will not stop in case of crash, errors, network issue AND you cannot cancel it.
- Parameters:
target (Dict[str, float]) –
key
= joint name ;value
= joint angle- Returns:
Future of the task. Done when sensorare on target.
- Return type:
Awaitable
- speed_safe(target, delta_time)[source]
Starts executing a speed safe trajectory at the target speeds.
Speed Safe: Moves the joints at a given set speed and keeps them in sync positon-wise.
Warning
This method is in early developpement and hasn’t been thouroughly tested.
Note
This sends position commands and not speed commands. This is to avoid dangerous joint runaway if issue arises.
- Parameters:
target (Dict[str, float]) – key = joint name ; value = joint speed
delta_time (float | Callable[[], float]) – Function giving the elapsed time in seconds (float) since the last time it was called. A constant float value can also be used but it is not recommanded.
- Returns:
Future of the task. This future will never be done unless when canceled.
- Return type:
Awaitable
- ready(joints)[source]
Returns wether a movement using those joints is possible or not.
- Parameters:
joints (Set | Dict) – Joints that one wants to use for a movement
- Returns:
True if movement is possible
Missing joints
- Return type:
Tuple
[bool
,Set
]
- abs_from_rel(offset)[source]
Absolute position of the joints that correspond to the given relative offset.
Example
joint_1 is at 45 deg, offset is 20 deg. Return will be 65 deg.
- Parameters:
offset (Dict[str, float]) – Relative positions.
- Returns:
Absolute position.
- Return type:
Dict
[str
,float
]
- abstract send_to_lvl1(states)[source]
Sends motor command data to lvl1.
Important
This method must be implemented by the runtime/interface.
Note
Default ROS2 implementation:
ros2.joint_api.JointSyncerRos.send_to_lvl1()
- Parameters:
states (List[JState]) – Joint state data to be sent to lvl1
- abstract property FutureT
ROS2 Future, asyncio or concurrent.
Important
This method must be implemented by the runtime/interface.
- Default ROS2 implementation::
return rclpy.task.Future
- Returns:
The Future class (not an instance).
- Return type:
Type
[Awaitable
]- Type:
Class of Future to use
- abstract property sensor
Is called when sensor data is need.
Important
This method must be implemented by the runtime/interface.
Note
Default ROS2 implementation:
ros2.joint_api.JointSyncerRos.sensor()
Returns:
- Return type:
Dict
[str
,JState
]
- unsafe_toward(target)[source]
Executes one single unsafe step.
- Parameters:
target (Dict[str, float]) – key = joint name ; value = joint angle
- Returns:
True if trajectory finished
- Return type:
bool