.. _using_the_hardware_interface: Using the Hardware Interface ============================ The ``robco_hardware`` package supplies a ros2_control hardware interface, allowing ros2_control controllers to interface with RobCo robots. The following command interfaces are supported: * ``effort``: robot accepts torque commands * ``position``, ``velocity`` and ``acceleration``: all three of these command interfaces must be active at the same time, used for trajectory streaming Configuring the Hardware Interface ---------------------------------- .. note:: Using the hardware interface requires a URDF file to describe the robot. Refer to :ref:`creating_a_urdf_file` for instructions on how to create one, then update the launch file mentioned below to load the correct file for your particular robot configuration. .. attention:: The launch files and configurations provided as part of the ``robco_bringup`` package are for an exemplary robot configuration and should be used as a basis for creating files for your specific robot configuration. Due to the modular nature of RobCo robots, a generic configuration applying to all configurations cannot be provided. An example launch file (``robco_controller.launch.py``) is provided in the ``robco_bringup`` package. For the hardware interface to operate correctly, ensure that: * the launch file refers to the correct URDF file * the URDF file matches the robot configuration and contains the ``ros2_control`` configuration * the configuration in ``robco_bringup/config/controllers.yaml`` is correct To make the launch file load a different URDF file, it can be modified or copied into a separate package. For adapting the URDF file to a specific robot configuration and configuring it for ``ros2_control``, see :ref:`creating_a_urdf_file`. The ``controllers.yaml`` file is passed to the ``ros2_control`` controller manager to configure all controllers being started. The following is an example configuration: .. code-block:: yaml controller_manager: ros__parameters: update_rate: 1000 joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster robco_controller: type: joint_trajectory_controller/JointTrajectoryController robco_controller: ros__parameters: joints: - joint0_joint - joint1_joint - joint2_joint - joint3_joint - joint4_joint - joint5_joint command_interfaces: - position - velocity - acceleration state_interfaces: - position - velocity #interpolation_method: 'none' gains: joint0_joint: { p: 100.0, d: 0.0, i: 1.0 } joint1_joint: { p: 100.0, d: 0.0, i: 1.0 } joint2_joint: { p: 100.0, d: 0.0, i: 1.0 } joint3_joint: { p: 100.0, d: 0.0, i: 1.0 } joint4_joint: { p: 100.0, d: 0.0, i: 1.0 } joint5_joint: { p: 100.0, d: 0.0, i: 1.0 } To adapt this configuration to a new robot, ensure that the joint names match those from the URDF file. **Note that the joint macros append** ``_joint`` **to the names of drive modules** to form the names of the actual URDF joint elements! Thus, if the drive module has ``name="joint2"``, the name of the joint is ``joint2_joint``. Also, adjust the ``command_interfaces`` parameter for the set of command interfaces which should be used. See :ref:`provided_command_interfaces` for supported combinations. Finally, there might be further controller parameters that need adjusting. For example, in the configuration above for the ``JointTrajectoryController``, there are gain settings for each joint. Starting the Hardware Interface ------------------------------- .. code-block:: bash ros2 launch robco_bringup robco_controller.launch.py This launch file starts the following nodes: * ``controller_manager``: The central node in the ros2_control framework * ``robot_state_publisher``: Reads the joint states and, based on the kinematics defined in the URDF file, outputs transforms to ``tf`` * ``controller_manager`` spawner to start a ``joint_state_broadcaster`` controller to publish joint states received from the robot * ``controller_manager`` spawner to start a ``joint_trajectory_controller`` (named ``robco_controller`` in the config) to execute trajectories on the robot using its command interfaces It can act as a starting point for more complex setups. Enabling the ROS Streaming Mode on the Robot -------------------------------------------- RobCo robots with the ROS 2 interface enabled will publish joint states as soon as the internal controller on the control unit has started successfully. However, write access (sending commands) is disabled by default. To enable ROS joint commands, the robot must be put into streaming mode. This feature is not exposed in the RobFlow UI yet, but it can be activated by sending a HTTP PUT request to the ``/ros-control`` endpoint of the RobFlow API with the following JSON body: .. code-block:: json true This can be done using ``curl`` as follows, assuming the robot control unit is reachable as ``192.168.3.1``: .. code-block:: bash curl -X PUT -H 'Content-Type: application/json' -d 'true' http://192.168.3.1/api/v3.0/ros-control Alternatively, this can be accomplished from a browser by navigating to `http://192.168.3.1/docs `_, finding the ``/ros-control`` endpoint, clicking "Try it out", then clicking "Execute". .. figure:: /_static/robflow_apidocs.png :align: center Sending the ``ros-control`` request from the RobFlow API Docs page. The status area in the top right corner of the RobFlow UI should now show that the robot is in streaming mode: .. figure:: /_static/robflow_ros_state.png :align: center RobFlow showing ROS streaming state .. note:: Once the streaming mode is enabled, the internal controller starts observing incoming messages. **If no message is received for 50 milliseconds, the streaming mode is automatically stopped and the robot decelerates to stop any movement**. Thus, the hardware interface and ROS2 controllers should be started before the robot is put into streaming mode. Using the Hardware Interface ---------------------------- The ros2_control hardware interface provided by ``robco_ros2`` can be used in a variety of ways. Please consult the `official ros2_control documentation `_ for more information. To get started with the provided launch files, `rqt_joint_trajectory_controller `_ can be used to command simple joint movements.