Video explanation of its implemntation and how to use can be found here.
If you not familiar with ros2_control.xacro
check the section at the end.
In this files we define the hardware components like the servo, linear actuator and proximity sensor. You can see there which component (plugin) is used and how the component is configured.
Let's make an example: If we want to use the ModbusHardwareInterface
in our project we can create a my_example_hw.ros2_control.xacro
. In this file we define the used implementation with the <plugin>...</plugin>
tag:
Besides this the most important part of this files are that we define the provided Command-/StateInterfaces of the hardware component.
To define a command or state interface you have to supply following parameters for modbus:
CommandInterface:
<command_interface name="name_of_interface">
<param name="register">number_of_register*2</param>
<param name="bits_to_read"number of bits to write/register size</param>
<param name="conversion_fn">how to convert from double to modbus int</param>
<param name="write_function">what modbus type</param>
<param name="factor">for converting to modbus</param>
<param name="offset">for converting to modbus</param>
</command_interface>
StateInterface:
<state_interface name="position">
<param name="register">umber_of_register*2</param>
<param name="bits_to_read">number of bits to read/register size</param>
<param name="conversion_fn">how to convert from modbus int to double</param>
<param name="read_function">what modbus type</param>
<param name="factor">for converting from modbus</param>
<param name="offset">or converting from modbus</param>
</state_interface>
The ModbusHardwareInterface
supports the following parameters to configure how a StateInterface acquires its value from modbus or how a CommandInterface writes its value to modbus.
Register number. Defines which register is requester for reading or writing. Check data sheet of your hardware for reference.
How many bits we read/write when accessing this modbus register. For registers this needs to be the register size and a multiple of sizeof(uint_16t)
. If the register is not a multiple of 16, which is the underlying modbus int size, this could be problematic. For bit it says how many bits are read/written in one call.
For reading: This maps to a function which is used to convert from uint_16t (register) or uint_8t (bits) used in modbus to double used in ros2_control. You can check the modbus library to see which functions are available and the implementations in modbus_client.hpp. If you need some special conversion you have to implement.
For writing: This maps to a function which is used to convert from double to uint_16t (register) or uint_8t (bits).
read_function is for StatateIntefaces only, write_functions for CommandInterfaces only.
We distinguish between reading a register or single bits. This is done by setting the read_function/write_function:
- register -> read/write register
- input_register -> used for read only registers
- bits -> read/write bits
- input_bits -> read only bits
Used for converting from the special modbus datatype to double. This is different then a conversion from uint_8t/uint_16 to double. With the conversion_fn we just convert from uint_8tuint_16 to double. For example the consider the position StateInterface is given in ticks but we want to provide a position in m in our StateInterface. Therefore we have to convert the double we receive by simply converting from modbus to double further. Therefore we supply the options of giving a factor and offset-> factor*converted_uint_16+offset.
The same is for the conversion from ros2_control double -> modbus uint_16 true.
If you need a custom HardwareInterface you first have to inherit from the ModbusHardwareInterface
:
class MyServo : public modbus_hardware_interface::ModbusHardwareInterface
then override the functions you need some custom actions. Important! Don't forget to call the ModbusHardwareInterface
functions in your implementations e.g. for: on_init
, read
, write
like this
hardware_interface::CallbackReturn ServoHardwareInterface::on_init(
const hardware_interface::HardwareInfo & info)
{
if (modbus_hardware_interface::ModbusHardwareInterface::on_init(info) != CallbackReturn::SUCCESS)
{
return CallbackReturn::ERROR;
}
...
}
hardware_interface::return_type ServoHardwareInterface::read(
const rclcpp::Time & time, const rclcpp::Duration & period)
{
auto ret = modbus_hardware_interface::ModbusHardwareInterface::read(time, period);
if (ret != hardware_interface::return_type::OK)
{
return ret;
}
.....
}
If you do not call those the modbus specific parameters in ros2_control.xacro
will not be parsed and the StateInterfaces will not be read or CommandInterfaces be written.
URDF, Unified Robot Description Format is an XML format for representing a robot model. URDF is commonly used in Robot Operating System (ROS) tools such as rviz (Ros Visualization tool) and Gazebo simulator. The model consists of links and joints motion.
Xacro is an XML macro language and preprocessor that is typically used to simplify the generation of URDF files. However, it can be applied to any XML. Using parameterizable macros, re-occurring XML blocks can be created with a few commands only.
Check the control docs