robco_hardware
The robco_hardware
package provides a ros2_control
hardware interface for RobCo robots.
Note
The ROS 2 interface is currently not shipped by default on RobCo robots. If you are interested in using the ROS 2 interface on your RobCo robot, please get in touch with RobCo support.
RobCo ros2_control interface overview
Using the hardware interface
The ROS interface is disabled when the robot control unit starts up and has to be enabled using the RobFlow API before using the hardware interface. This can be done in a browser and is described in Using the hardware interface.
By default, the hardware interface expects to communicate with the ROS bridge running on the controller via topics robco_joint_states
and robco_joint_commands
. These topic names can be configured via the optional parameters joint_states_topic
and joint_commands_topic
to the <hardware>
XML tag of the URDF, as demonstrated in Assembling the URDF file.
Provided command interfaces
The hardware interface exposes the following types of command interfaces:
position
+velocity
+acceleration
(must all be active at the same time)effort
(joint torque)
Note
At any given point in time, the same set of command interfaces must be active on all robot joints. In other words, one joint cannot use a different set of command interfaces than another.
Joint position/velocity/acceleration interface
When the position
, velocity
and acceleration
interfaces are active, the internal
controller operates in trajectory streaming mode. The internal desired values for joint position,
velocity and acceleration are immediately updated from the values coming from ros2_control
.
Joint effort (torque) interface
When only the effort
interface is activated, the internal controller operates in
torque streaming mode. In this mode, the controller compensates gravity (\(\tau_g\)) and
coriolis forces (\(\tau_{coriolis}\)) only. The effort
command (\(\tau_{ROS}\)) is then
added to form the final torque vector commanded to the motors: