I have a 5 DoF manipulator, driven by K-tech CAN motors (controlled with raw CAN frames, by one CAN bus). Each of these motors has a built-in gear, an absolute single-loop encoder and an embedded controller allowing the motor's control by CAN and reading of the motor's single-loop and multi-loop angles (the multi-loop angle memory is volatile - it's lost once the robot's power is turned off.
FYI: The second and third joint's full range of motion consists of 11 motor revolutions (loops) - this in pair with the motor controllers' volatility of the multi-loop angle memory, creates the need for a homing mechanism or another set of absolute encoders, directly on the joints, after the gears.
I chose the second option - absolute encoders mounted directly on the joints. Those are controlled with a single RS485 bus.
So I would like to control the movement of the joints using the CAN bus, and read the joints' angles using the RS485 absolute encoders.
This sums up to the following question:
Can I have one ros2_control hardware interface responsible for providing the joints' states interfaces (data gotten from the RS485 encoders) and another ros2_control hardware interface for handling the joints' command interfaces (controlling the CAN motors' speeds)?
In xacro this would have looked like this I suppose:
<xacro:macro name="can_motor" params="name">
<joint name="${name}">
<command_interface name="position">
<param name="min">0</param>
<param name="max">${1 * PI}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<command_interface name="effort">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="velocity" />
<state_interface name="effort" />
</joint>
</xacro:macro>
<xacro:macro name="cui_rs485_encoder" params="name">
<joint name="${name}">
<state_interface name="position" />
</joint>
</xacro:macro>
<ros2_control name="ManipulatorMotorsSystem" type="system">
<hardware>
<plugin>hardware_interfaces/ManipulatorsCanSystem</plugin>
<param name="can_interface">${can_interface}</param>
</hardware>
<xacro:can_motor name="shoulder_pan_joint"/>
<xacro:can_motor name="shoulder_lift_joint"/>
<xacro:can_motor name="elbow_joint"/>
<xacro:can_motor name="wrist_1_joint"/>
<xacro:can_motor name="wrist_2_joint"/>
<xacro:can_motor name="wrist_3_joint"/>
</ros2_control>
<ros2_control name="ManipulatorEncodersSystem" type="system">
<hardware>
<plugin>hardware_interfaces/ManipulatorEncodersSystem</plugin>
<param name="serial_port">${serial_port}</param>
<param name="baud_rate">115200</param>
<param name="loop_rate">30</param>
<param name="timeout_ms">1000</param>
</hardware>
<xacro:cui_rs485_encoder name="shoulder_pan_joint"/>
<xacro:cui_rs485_encoder name="shoulder_lift_joint"/>
<xacro:cui_rs485_encoder name="elbow_joint"/>
<xacro:cui_rs485_encoder name="wrist_1_joint"/>
<xacro:cui_rs485_encoder name="wrist_2_joint"/>
<xacro:cui_rs485_encoder name="wrist_3_joint"/>
</ros2_control>