easy_robot_control.injection package
Provides objects adding functionalities to nodes through dependency injection.
Submodules
easy_robot_control.injection.offsetter module
- class easy_robot_control.injection.offsetter.OffsetterLvl0(parent, angle_path=None, offset_path=None)[source]
Bases:
object
Position offseter for lvl0, to be injected into a JointNode. Usefull if your URDF and robot are not aligned.
- Features
Inject this into any JointNode
Apply an angle offset to any joint of the lvl0 input/output.
Use a service to apply the offset at runtime
(Optional) Load offsets from a csv on disk.
(Optional) Save current angles multiplied by -1 every 3s in a csv on disk.This saved angle can tell you the last shutdown position of the robot, if you need to recover the offsets from it.
Note
You should inject this object into a JointNode at the end of initialization.
You do not need to call any of those function, just inject this object.
- Parameters:
parent (JointNode)
angle_path (str | None) – if None, does not save the current angles on disk
offset_path (str | None) – if None, does not save or load offsets from disk
Examples
Injecting in a JointNode:
class Example(JointNode): def __init__(self): super().__init__() self.offsetter = OffsetterLvl0( self, angle_path=ANGLE_PATH, offset_path=OFFSET_PATH )
Service call:
ros2 service call /leg1/set_offset motion_stack_msgs/srv/SendJointState "{js: {name: [joint1-2], position: [1], velocity: [], effort: []}}"
- update_mapper(mapper_in=None, mapper_out=None)[source]
Applies the offsets to a StateRemapper.
- Parameters:
mapper_in (StateRemapper | None) – original map to which offset should be added
mapper_out (StateRemapper | None) – affected subshaper of this map will change
- Return type:
None
- update_and_save_offset(js_offset)[source]
Held offset values will be updated then saved on disk.
Note
Preferably use this to not lose the offset in case of restart
- Parameters:
js_offset (List[JState]) – list of offsets
- Returns:
True if all offsets have a joint to be applied to String for user debugging
- Return type:
Tuple
[bool
,str
]
- save_angle_as_offset(handlers=None)[source]
Saves current position as the offset to recover to incase of powerloss.
Note
Saved in self.angle_path
To use those saves as offsets, replace the file <self.offset_path> with <self.angle_path>
- Parameters:
handlers (Dict[str, JointHandler] | None)
easy_robot_control.injection.topic_pub module
Provides StatesToTopics, to be injected in a Node. see the class docstring for details
- class easy_robot_control.injection.topic_pub.StatesToTopic(joint_node)[source]
Bases:
object
Publishes joint states onto individual topics, to be injected in a Node.
- Features:
Publishes a list of JState or a JointStates onto individual Float64 topics
Overload make_topic_name with the the naming convention you need
- Lazily creates the topics as they are publishedtopics
topics will not be created at startup, but the first time they are used
publish np.nan and/or overload _pub_attribute to change this
====================== Injection sample code ==================== from easy_robot_control.injection.topic_pub import StatesToTopic from rclpy.node import Node
- class MyStatesToTopic(StatesToTopic):
- def make_topic_name(self, attribute: str, joint_name: str) -> str:
topic_name = f”canopen_motor/{joint_name}_joint_{attribute}_controller/command” return topic_name
- class Example(Node):
- def __init__(self):
super().__init__() self.topic_pub = StatesToTopic(self)
- def send_to_lvl0(self, states):
self.topic_pub.publish(states)
- Parameters:
joint_node (Node)
- make_topic_name(attribute, joint_name)[source]
Return the topic name to create. Overload this with the topic naming style you need, for example
return f”canopen_motor/{joint_name}_joint_{attribute}_controller/command”
the output will be sanitize by __make_topic_name.
- Parameters:
attribute (str) – position, velocity or effort
joint_name (str) – name of the joint
- Returns:
name of the associated topic
- Return type:
str