Doc for the python bindings of ros2 control.
- Builder: Internal documentation for the executable that parses C++ and outputs pybind11 bindings
- controller_interface
- controller_manager
- hardware_interface
- joint_limits
- ros2_control_test_assets
- transmission_interface
- parse_control_resources_from_urdf
- StateInterface / CommandInterface (see FloatRef and FloatRefProp)
- Actuator / Sensor / System
- ActuatorInterface / SensorInterface / SystemInterface
- ResourceManager
Because rclpy and rclcpp are bindings over rclc and the fact that ros2 control is written over rclcpp and not rclc,
We need to provide some bindings over rclcpp and rclcpp_lifecycle for this to work.
- init / shutdown / ok
- Time / Duration
- State
- LifecycleNodeInterface / CallbackReturn
- Node / NodeBase / NodeBaseInterface
- Executor / StaticSingleThreadedExecutor
- FloatRef / FloatRefProp
- VectorString / VectorDouble (see StlBindings)
FloatRef is an owning reference to a
double
that behaves as a float-like object in Python.In C++ it decays into a
double
or a double*
for interfaces that require it.It's purpose is to be used with StateInterface / CommandInterface.
- Warning:
- Although you can use assignment operators like +=,you cannot assign to a FloatRef with =.To do that see FloatRefProp of use @ / @= / set_value.
Usage:
from ros2_control_py.hardware_interface import CommandInterface, HW_IF_VELOCITY
from ros2_control_py.rclcpp import FloatRef
fr = FloatRef(5)
assert fr == 5
fr += 3
assert fr == 8
fr.set_value(5 / 2)
assert fr == 2.5
fr @ 8
assert fr == 8
fr @= 7
assert fr == 7
ci = CommandInterface("name", HW_IF_VELOCITY, fr)
assert ci.get_value() == 7
fr @= 4
assert ci.get_value() == 4
ci.set_value(5)
assert fr == 5
FloatRefProp is a property
like descriptor that handles instance wide FloatRef so that you can assign to them like normal floats.
Usage:
from ros2_control_py.hardware_interface import CommandInterface, HW_IF_VELOCITY
from ros2_control_py.rclcpp import FloatRefProp
class Dummy:
fr = FloatRefProp(5)
def __init__(self):
self.ci = CommandInterface("name", HW_IF_VELOCITY, self.fr)
d = Dummy()
assert d.fr == 5
assert d.ci.get_value() == 5
d.fr += 3
assert d.fr == 8
d.fr = 5 / 2
assert d.fr == 2.5
d.fr = 4
assert d.ci.get_value() == 4
d.ci.set_value(5)
assert d.fr == 5
When using stl containers (
std::vector
, std::map
, std::set
, etc...) in the python interface,we need to use a specialized binding for changes to go both ways.
This is only needed for some cases, mainly containers of string/double,
In other cases use a simple list but beware: it will be copied/moved out when passes to a C++ interface
(For these types you cannot have a reference to the container but merely a copy).
All these bindings are located in the rclcpp module in PascaleCase.
(ex:
std::vector<std::string>
=> VectorString
).