Skip to content

Introduction

The dnb_remote_robot_control ROS package, also known as control panel, is a ROS node responsible for managing motion commands when moving the robot through drag&bot GUI smoothly. The control panel has its own interface for moving the robot. This page describes the ROS interface used for this purpose. This information is only relevant if you are planing to implement a drag&bot robot driver and replace the existing control panel node.

Interface

This section describes how motion commands are triggered from drag&bot GUI.

Heartbeat

After a move is started, a heartbeat must regularly called in order to keep the motion active. If it is not called within a given time interval, the motion will stop. Calling the service is only necessary after a motion is triggered.

Heartbeat ROS service

A call of the /dnb_remote_robot_control/heartbeat ROS service of type std_srvs/Trigger resets the internal timer.

Heartbeat ROS topic

Alternatively, a ROS topic called /heartbeat of type std_msgs/Bool produces the same effect as calling the Heartbeat service. As topics can be queued or delayed through a ROS Bridge connection, its use is not recommended. It is just kept due to backwards compatibility.

Heartbeat timeout

The timeout is defined as a ROS parameter called heartbeat_timeout. Its default value is 0.2 seconds. This value can be changed by adding the parameter in the corresponding module_config/robot/robot.yaml file inside the driver component. Alternatively there is a ROS service called dnb_remote_robot_control/set_heartbeat_timeout of type robot_movement_interface/SetFloat which allows changing live the timeout value.

Start a joint move

The service /remotecontrol_start_move_joints of type dnb_remote_robot_control/StartMoveJoints triggers a joint motion which can be absolute (goal) or incremental (also known as delta move or relative move, but this last term may be confussing specially in cartesian moves). When absolute, the target joints must be sent. When incremental, a direction is sent.

The service definition is:

# Service to start rotating one Joint
Joints joints
float32 speed
---
bool success

Speed is a real value (0,1] representing an override of the motion speed. This speed is defined as the joints_delta_velocity and joints_goal_velocity ROS parameters.

Joints message is defined as:

# If true, robot will move in delta position (incrementally)
bool move_delta

# Final or delta joint values
float32[] joint_values

In this case move_delta indicates if the move is a incremental move or an absolute move, which changes the semantic value of joint_values.

Incremental / Delta move

In an incremental move, a normalization is carried on the joints vector. This vector represent therefore a n-dimensional direction. The resulting module of the vector after the normalization will be step_joints ROS parameter value. Normally only one joint is active (1 or -1) and the rest are 0, but his is not compulsory. E.g. [0,0,-1,0,0,0] for a six axis robot moving joint 3 in a negative direction. The move_delta flag must therefore true. The motion will be carried out until timeout expiration or until stop service call.

Absolute / Goal position

In an absolute move, the values provided in joint_values are taken as the final position to arrive. The move_delta flag must therefore false. The motion will be carried out until position is reached, until timeout expiration or until stop service call.

Start a cartesian move

The service /remotecontrol_start_move_cartesian of type dnb_remote_robot_control/StartMoveCartesian starts a cartesian move which can be incremental (delta) or absolute (goal). The given position can use as origin a ROS frame and a provided frame.

# Service to Move either to a specific position or to start moving in one direction
Pose pose

# Optional
robot_movement_interface/EulerFrame pose_reference_frame

float32 speed
---
bool success

Pose message is defined as:

# If null, then world coordinates will be used
string pose_reference

# If true, robot will move in delta position (incrementally)
bool move_delta

# Position: X, Y, Z
Position position

# Orientation: Alpha, Beta, Gamma
Orientation orientation

Position message:

float32 x
float32 y
float32 z

Orientation message:

float32 rz
float32 ry
float32 rx

# Documentation:
# --------------
# This message follows the Euler Intrinsic ZYX convention:
# x,y,z in meters
# - First alpha rads are rotated in Z axis
# - Then beta rads are rotated in the new Y axis
# - Finally gamma rads are rotated in the new X axis
# float32 x
# float32 y
# float32 z
# float32 alpha
# float32 beta
# float32 gamma

Incremental / Delta move

In this case move_delta flag is true. Then the values of the position and the values of the orientation are normalized as two vectors, one for position and one for orientation. Position will increment step_translation module on each iteration. Orientation will increment step_rotation module on each iteration. This increment can be relative to a provided frame as it is described below.

Absolute / Goal Position

In this case move_delta flag is false. Position and orientation values are taken as a target position. This position can be relative to other frames as it is described below.

Relative moves

In both incremental and absolute, the cartesian motion origin can be defined by two methods: a ROS frame and a given full-frame. The incremental or absolute position defined is relative to the pose reference frame provided in the message (pose_reference_frame field), which can be null. This pose reference frame has as base the ROS TF frame defined through pose_reference string name (e.g. world). For example, if we have an absolute position of (x,y,z,rz,ry,rx) = (0,0,0.01,0,0,0) applied to a frame of (-2,0,2,0,0,0) which is based on a TF frame called A whose transformation from robot base (to A) is (1,0,0,0,0,0) then, the target position on robot base sent to the controller will be (-1,0,2.01,0,0,0).

It is important to note some special cases for incremental moves: if the name of pose_reference is world (or the one defined through the parameter ~robot_data/world_frame) or is the same name of the robot base base_link (again can be modified through the parameter ~robot_data/fixed_frame) is provided as the ROS frame, the increment is done by placing the cartesian origin at the tool but keeping the original orientation.

Additional implementation notes

The final move command sent to the robot may be a command with absolute position or a relative command to the end-effector. This happens both in case of joints or cartesian moves. The implementation of the control panel needs to decide which method is using. The standard control panel accept both of them and it is configurable through ROS parameters. If cartesian_delta_command_type parameter is set to REL, RELW or RELT, then is the increment between the calculated goal position and the current end-effector position is sent to the robot. Anything else is taken as absolute positioning (e.g. LIN, PTP).

One of the main complexities of the control panel is that needs to transform live from relative poses to a final robot pose in the active robot coordinate system.

Stop a move

/remotecontrol_start_move_joints service of type std_srvs/Trigger stops immediately the motion. It has the same effect as a timeout expiration.

ROS configuration parameters

The following parameters are recognized by the standard control panel. Normally they are included in a yaml file under module_config/robot directory of the driver.

Logic

Indicates the best effort looping rate for sending commands to the robot. Target positions are recalculated and sent to the robot controller following this rate.

  • update_rate: 20

Heartbeat

Defines the heartbeat interval after robot stops.

  • heartbeat_timeout: 0.2

Step parameters

Represent the distance (in the corresponding units) to increment on each iteration up from the current position.

  • step_translation: 0.01
  • step_rotation: 0.2
  • step_joints: 0.2

Step distance is dynamically recalculated according to the current robot global speed override. This parameter is actively used for reaching the limit of robot working areas by making smaller the robot moving step. These two optional parameters allow to manually deactivate this feature if necessary:

  • step_scale_joints: false
  • step_scale_cartesian: false

Additionally, factors may be defined to recalculate target position only when the tool is less than this percent near the next position. E.g. if 0.5 is set, the control panel only calculates the next target position when the tool has already traveled 50% of the move to the target.

  • step_translation_factor: 1.0
  • step_rotation_factor: 1.0

Joint incremental / delta move

Including descriptions. It fills a RMI trajectory command.

  • joints_delta_replace: true → Indicates if the command list replace flag is active or not.
  • joints_delta_command_type: 'PTPCP' → Command which is sent to the robot
  • joints_delta_velocity_type: 'PERCENT' → Speed units
  • joints_delta_acceleration_type: 'PERCENT' → Acceleration units.
  • joints_delta_blending_type: 'M' → Blending units.
  • joints_delta_velocity: 5.0 → Speed in the corresponding units.
  • joints_delta_acceleration: 100.0 → Acceleration in the corresponding units.
  • joints_delta_blending: 0.01 → Blending in the corresponding units.

Joints absolute move

Parameters have a similar description as joint incremental.

  • joints_goal_replace: false
  • joints_goal_command_type: 'PTP'
  • joints_goal_velocity_type: 'PERCENT'
  • joints_goal_acceleration_type: 'PERCENT'
  • joints_goal_blending_type: 'M'
  • joints_goal_velocity: 5.0
  • joints_goal_acceleration: 100.0
  • joints_goal_blending: 0.01

Cartesian delta

Parameters have a similar description as joint incremental.

  • cartesian_delta_replace: true
  • cartesian_delta_command_type: 'PTP'
  • cartesian_delta_velocity_type: 'PERCENT'
  • cartesian_delta_acceleration_type: 'PERCENT'
  • cartesian_delta_blending_type: 'M'
  • cartesian_delta_velocity: 5.0
  • cartesian_delta_acceleration: 100.0
  • cartesian_delta_blending: 0.01

Additionally acceleration and blending can be defined differently for rotation-only moves:

  • cartesian_delta_blending_rot: 0.01
  • cartesian_delta_acceleration_rot: 50.0

Cartesian goal

Parameters have a similar description as joint incremental. The control panel allows to differentiate the behavior if the command is only rotation or translation.

  • cartesian_goal_replace: false
  • cartesian_goal_command_type_rotational_movement: 'PTP' → Rotation-only moves
  • cartesian_goal_command_type_translational_movement: 'PTP' → Includes translation moves.
  • cartesian_goal_velocity_type: 'PERCENT'
  • cartesian_goal_acceleration_type: 'PERCENT'
  • cartesian_blending_type: 'M'
  • cartesian_goal_velocity: 5.0
  • cartesian_goal_acceleration: 100.0
  • cartesian_blending: 0.0

Further its possible to differentiate between normal goal movement (which is usually performed as PTP) and LIN goal movement. LIN goal movements are only provided to the user, if specified for the robot:

  • cartesian_goal_command_type_rotational_movement_lin: 'LIN' → Rotation-only moves
  • cartesian_goal_command_type_translational_movement_lin: 'LIN' → Includes translation moves.
  • cartesian_goal_velocity_type_lin: 'M/S'
  • cartesian_goal_acceleration_type_lin: 'PERCENT'
  • cartesian_goal_velocity_lin: 0.1
  • cartesian_goal_acceleration_lin: 100.0

Frames

Name of the robot base frame and the tool frame. Also the name of the corresponding urdf of the robot. Usually world is omitted.

  • robot_data:
    • fixed_frame: 'manufacturer_base'
    • flange_frame: 'robot_state_tcp'
    • urdf_param: 'robot_description'
    • world_frame: 'world'

Joint limits

The list of joint ranges necessary for drag&bot GUI to know limits and intervals. Assumed degrees except if unit m is defined (for cartesian links).

joint_limits:
  - min: -42
    max:  222
  -
    min: -141
    max:  141
  -
    min:  -0.15
    max:  0.0
    unit: 'm'
    step: 0.005
  -
    min: -360
    max:  360

Launch file for replacing standard control panel

Additionally to the control panel, different nodes must be also configured and started together. If only the control panel is replaced, then it is still necessary to start the additional as follows in the launch file. This launch file called start_config_only.launch is included together with start_v3.launch in d&b releases up from April 2020.

<?xml version="1.0"?>
<!-- Select the robot type which is used for remote control -->
<launch>

    <arg name="package" />
    <arg name="robot" />
    <arg name="sim" default="false"/>
    <arg name="tool_frame" default="tool0"/>

    <!-- basic: load configuration as general for all robots-->
    <rosparam file="$(find dnb_remote_robot_control)/config/general.yaml" ns="/dnb_remote_robot_control/" command="load" />

    <!-- robot: load configuration specific for a robot -->
    <rosparam file="$(eval find(arg('package'))+'/module_config/robot/'+(arg('robot'))+'.yaml')" ns="/dnb_remote_robot_control/" command="load" />

    <!-- sim: when using sim, the default config of a robot
        will be override by the settings in the *_sim.yaml file -->
    <rosparam if="$(arg sim)" file="$(eval find(arg('package'))+'/module_config/robot/'+(arg('robot'))+'_sim.yaml')" ns="/dnb_remote_robot_control/" command="load" />

    <node name="dnb_remote_robot_control_interactive_marker" pkg="dnb_remote_robot_control" type="interactive_marker.py" />

    <!-- interactive_marker_proxy to provide the marker data to frontend -->
    <node name="interactive_marker_proxy_tool" pkg="interactive_marker_proxy" type="proxy" output="screen">
        <remap from="topic_ns" to="/remotecontrol_markers_tool" />
        <remap from="target_frame" to="$(arg tool_frame)" />
    </node>

    <node name="interactive_marker_proxy_base" pkg="interactive_marker_proxy" type="proxy" output="screen">
        <remap from="topic_ns" to="/remotecontrol_markers_base" />
        <remap from="target_frame" to="$(arg tool_frame)" />
    </node>

    <node name="interactive_marker_proxy_world" pkg="interactive_marker_proxy" type="proxy" output="screen">
        <remap from="topic_ns" to="/remotecontrol_markers_world" />
        <remap from="target_frame" to="$(arg tool_frame)" />
    </node>

</launch>