Contents


Component IDs


right_j0, right_j1, right_j2, right_j3, right_j4, right_j5right_j6


Arm Joint States


/robot/joint_states (sensor_msgs-JointState)

  • name[i]: '<component_id>' of i-th joint in message value arrays.
  • position[i]: position of joint i rad
  • velocity[i]: velocity of joint i in rad/s
  • effort[i]: effort applied in joint i in Nm

Joint states are published by the robot_state_publisher and are updated with information from the sensors for every cycle.

Set Joint State Publishing Rate
/robot/joint_state_publish_rate (std_msgs-UInt16)

  • The rate at which the joints are published can be controlled by publishing a frequency on this topic.
  • Default rate is 100Hz; Maximum is 800Hz.

Arm Joint Control


There are currently four modes for controlling the arms: Joint Position Mode, Joint Velocity Mode, and Joint Torque Mode, and Joint Trajectory Mode.

For Joint Trajectory Mode, a joint trajectory action server has been created in support of timestamped joint position trajectories using the ROS standard joint trajectory action.


Joint Control Mode


Each arm can be in independent control modes by publishing the desired control mode to the topic for the appropriate arm.


Position Mode


The first is Position Mode, in which users publish target joint angles for given joints and the internal controller drives the arm to the published angles.


Velocity Mode


In Velocity Control Mode, users publish velocities for given joints and the joints will move at the specified velocity.


Torque Mode


'Warning:' Advanced Control Mode.
In Torque Control Mode, users publish torques for given joints and the joints will move at the specified torque.


Trajectory Mode


'Warning:' Advanced Control Mode. In Trajectory Control Mode, users publish desired joint positions. Where these commands would typically be modified in traditional 'Position Mode', these commands are passed directly to the Joint Controller Boards (JCBs). The only limitation placed on Trajectory commands is it requires a user-computed Position, Velocity, and Acceleration at each timestamp.


Switching Modes


/robot/limb/right/joint_command (intera_core_msgs/JointCommand)

  • Mode is set implicitly by specifying the mode in the command message. Publish a JointCommand message to the joint_command topic for a given arm to set the arm into the desired control mode.
  • Constants for each mode are defined in the JointCommand message type.

Joint Trajectory Action


The Joint Trajectory Action provides an ROS action interface for tracking trajectory execution.

The joint trajectory action server provides an action interface for execution of trajectories requested by the client, known as a Goal* request. The joint trajectory action server then executes the request trajectory communicating the *Result response.

The actionlib (action server/client interface) package differs from ROS services, simple request/response interface, in that actions allow mid-execution cancellation, they can also provide feedback during execution as to the progress of the Goal request.

Joint Trajectory Action Server
/robot/limb/right/follow_joint_trajectory/cancel
/robot/limb/right/follow_joint_trajectory/feedback
/robot/limb/right/follow_joint_trajectory/goal
/robot/limb/right/follow_joint_trajectory/result
 
/robot/limb/right/follow_joint_trajectory/status


Usage

    # Verify that the robot is enabled:
    $ rosrun intera_interface enable_robot.py
    # Start the joint trajectory action server:
    $ rosrun intera_interface joint_trajectory_action_server.py

Please see the joint trajectory playback example for examples of creating a client of this action server and requesting a joint trajectory.


Parameters


The joint trajectory action server provides a number of parameters which describe it's behavior during the trajectory execution. These were largely designed to follow these standards.


Note: All of these parameters will be initialized on startup of the trajectory_controller.py if they were not previously specified.


  • /rethink_rsdk_joint_trajectory_controller/<joint_name>__kp

The proportional gain with which the joint trajectory controller will track the commanded trajectory for the specified joint.

  • /rethink_rsdk_joint_trajectory_controller/<joint_name>__kd

The derivative gain with which the joint trajectory controller will track the commanded trajectory for the specified joint.

  • /rethink_rsdk_joint_trajectory_controller/<joint_name>__ki

The integral gain with which the joint trajectory controller will track the commanded trajectory for the specified joint.

  • /rethink_rsdk_joint_trajectory_controller/goal_time (double, default: 0.0)

The amount of time (in seconds) that the controller is permitted to be late to the goal. If goal_time has passed and the controller still has not reached the final position (within the parameters described by /rethink_rsdk_joint_trajectory_controller/<joint_name>_goal, then the goal is aborted.

  • /rethink_rsdk_joint_trajectory_controller/<joint>_goal (double, default: -1.0)

The maximum final error for <joint> for the trajectory goal to be considered successful. Negative numbers indicate that there is no constraint. Given in units of joint position (radians). If this constraint is violated, the goal is aborted.

  • /rethink_rsdk_joint_trajectory_controller/trajectory (double, default: -1.0)

The maximum error for <joint> at any point during execution for the trajectory goal to be considered successful. Negative numbers indicate that there is no constraint. Given in units of joint position (radians). If this constraint is violated, the goal is aborted.

Dynamic Reconfigure GUI is suggest for use with ROS Distributions >=Indigo for setting these parameters.

  

   # Start the dynamic reconfigure GUI:
   $ rosrun rqt_reconfigure rqt_reconfigure

  

Expand the joint trajectory controller's parameters by choosing rethink_rsdk_joint_trajectory_controller from the left menu. Use the sliders/input fields to specify these parameters dynamically.

Alternatively, these parameters can be set via a YAML file, command line, or programmatically (rospy, roscpp).


Collision Avoidance


Warning: RETHINK ROBOTICS DISCLAIMS COMPLIANCE BY THE PRODUCTS WITH ANSI, ISO OR OTHER INDUSTRIAL ROBOT SAFETY STANDARDS. RETHINK’S PRODUCTS INCLUDE CERTAIN SAFETY AND/OR COLLISION DETECTION TECHNOLOGY TO PREVENT POSSIBLE INJURY FROM USE OF THE PRODUCTS. THE USER ACKNOWLEDGES THAT HE/SHE HAS THE ABILITY TO DISABLE CERTAIN SAFETY MECHANISMS INCLUDED IN THE PRODUCTS, AND IF DISABLED BY USER, USER ASSUMES ALL RESPONSIBILITY FOR DAMAGE AND/OR HARM CAUSED BY THE PRODUCTS AND AGREES TO INDEMNIFY RETHINK ROBOTICS FROM ALL LIABILITY RELATING TO SUCH DAMAGE OR HARM.


In certain situations, collision avoidance (forces applied to the joints to avoid self collision) are undesirable.


Torso Collision Avoidance
/robot/limb/right/suppress_collision_avoidance (std_msgs-Empty)

To disable torso self collision avoidance, a std_msgs/Empty message must be published at a rate greater than 5 Hz.

For additional information on joint control, see the Joint Position Example, Head Movement Example, and MoveIt! Tutorial.