interbotix_xs_msgs

View Package on GitHub

Overview

The interbotix_xs_msgs package defines and builds the common messages, services, and actions used by the Interbotix X-Series platforms. This guide details those interfaces relevant to the X-Series Arms.

Usage

Simply build this package and include any generated message in your own custom node or script. For example, if you wanted to reboot a servo in an X-Series manipulator, you would include the Reboot service in your program’s header.

  • C++

    #include "interbotix_xs_msgs/Reboot.h"
    
  • Python

    from interbotix_xs_msgs.srv import Reboot
    

Structure

Messages

JointGroupCommand

Command the joints in the specified joint group. Note that the commands are processed differently based on the group’s operating mode. For example, if a group’s operating mode is set to ‘position’, the commands are interpreted as positions in radians

string name            # Name of joint group
float32[] cmd          # List of joint commands; order is dictated by the index of each joint name for the given group in the 'groups' section of a 'motor_config' yaml file

JointSingleCommand

Command a desired joint. Note that the command is processed differently based on the joint’s operating mode. For example, if a joint’s operating mode is set to ‘position’, the command is interpreted as a position in radians

string name          # Name of joint
float32 cmd          # Joint command

JointTrajectoryCommand

Command a joint trajectory to the desired joint(s). Note that the commands are processed differently based on the currently set operating mode. For example, if the operating mode is set to ‘position’, the commands are interpreted as positions in radians. This message wraps the trajectory_msgs/JointTrajectory message.

string cmd_type                               # set to 'single' for a single joint or 'group' for a group of joints
string name                                   # joint group name if 'cmd_type' is set to 'group' or joint name if 'cmd_type' is set to 'single'
trajectory_msgs/JointTrajectory traj          # ROS trajectory message

Services

TorqueEnable

Torque a joint or group of joints on/off.

string cmd_type          # set to 'group' if commanding a joint group or 'single' if commanding a single joint
string name              # name of the group if commanding a joint group or joint if commanding a single joint
bool enable              # set to 'true' to torque on or 'false' to torque off
---

Warning

The specified motors will torque off and the robot may collapse when this service is called. Make sure the robot is in its sleep pose or in a safe configuration before calling it.

Reboot

Reboot a joint or group of joints.

Warning

If a dual-joint is selected, both motors will be rebooted.

Warning

The specified motors will torque off and the robot may collapse when this service is called. Make sure the robot is in its sleep pose or in a safe configuration before calling it.

Warning

Only EEPROM registers will retain their values, but RAM registers will not. See details on the RAM and EEPROM Control Tables for your specific motors, for example, the XM430-W350.

string cmd_type          # set to 'group' if commanding a joint group or 'single' if commanding a single joint
string name              # name of the group if commanding a joint group or joint if commanding a single joint
bool enable              # whether to torque the selected joints on after reboot
bool smart_reboot        # set to true to only reboot motors in a specified group that are in an error state
                         # (as opposed to a blanket reboot of all motors in said group)
---

RobotInfo

Get information about a joint, group of joints, or all joints on the robot.

Note

If a ‘gripper’ joint is specified, all information will be specified in terms of the ‘left_finger’ joint

string cmd_type                          # set to 'group' if requesting info about a joint group or 'single' if requesting info about a single joint
string name                              # the group name if requesting info about a group or the joint name if requesting info about a single joint
---
string mode                              # the operating mode for the specified joint group or joint
string profile_type                      # the profile type for the specified joint group or joint
string[] joint_names                     # the name of each joint in a group or just the specified joint
int16[] joint_ids                        # the Dynamixel ID for each joint in a group or for the specified joint
float32[] joint_lower_limits             # the lower limit [radians] for each joint in a group or for the specified joint (taken from URDF)
float32[] joint_upper_limits             # the upper limit [radians] for each joint in a group or for the specified joint (taken from URDF)
float32[] joint_velocity_limits          # the velocity limit [rad/s] for each joint in a group or for the specified joint (taken from URDF)
float32[] joint_sleep_positions          # the sleep position [rad] for each joint in a group or for the specified joint
int16[] joint_state_indices              # index for each joint in a group or for the specified joint in the published JointState message
int16 num_joints                         # the number of joints in a group or 1
string[] name                            # the name of the group or joint requested; if group was 'all', returns the names of all groups

OperatingModes

Used to set Operating Modes on a joint or group of joints.

To get familiar with the various operating modes, go to the DYNAMIXEL Workbench E-Manual page, click on a motor model, and scroll down to the ‘Operating Mode’ section.

There are 6 valid operating modes:

  • “position” - allows up to 1 complete joint revolution (perfect for arm joints); units are in radians
  • “ext_position” - allows up to 512 joint revolutions; units are in radians
  • “velocity” - allows infinite number of rotations (perfect for wheeled robots); units are in rad/s
  • “current” - allows infinite number of rotations (perfect for grippers); units are in milliamps
  • “current_based_position” - allows up to 512 joint revolutions; units are in radians
  • “pwm” - allows infinite number of rotations (perfect for grippers); units are in PWM

Note that the interbotix_xs_sdk offers one other ‘pseudo’ operating mode that can be useful in controlling Interbotix Grippers - called “linear_position”. Behind the scenes, it uses the “position” operating mode mentioned above. The main difference is that with this mode, a desired linear distance [m] between the two gripper fingers can be commanded. In the “position” mode though, only the angular position of the motor can be commanded.

There are 2 valid profile types - either ‘time’ or ‘velocity’. Depending on which is chosen, the following parameters behave differently.

  • profile_velocity: acts as a pass-through to the Profile_Velocity register and operates in one of two ways. If ‘profile_type’ is set to ‘velocity’, this parameter describes the max velocity limit for the specified joint(s); for example, if doing ‘position’ control, setting this to ‘131’ would be equivalent to a limit of 3.14 rad/s; if ‘profile_type’ is set to ‘time’, this parameter sets the time span (in milliseconds) that it should take for the specified joint(s) to move; to have an ‘infinite’ max limit, set to ‘0’.
  • profile_acceleration: acts as a pass-through to the Profile_Acceleration register and operates in one of two ways. If ‘profile_type’ is set to ‘velocity’, this parameter describes the max acceleration limit for the specified joint(s); for example, if doing ‘position’ or ‘velocity’ control, setting this to ‘15’ would be equivalent to a limit of 5.6 rad/s^2; if ‘profile_type’ is set to ‘time’, this parameter sets the time span (in milliseconds) that it should take for the specified joint(s) to accelerate; to have an ‘infinite’ max limit, set to ‘0’.
string cmd_type                     # set to 'group' if commanding a joint group or 'single' if commanding a single joint
string name                         # name of the group if commanding a joint group or joint if commanding a single joint
string mode                         # desired operating mode as described above
string profile_type                 # desired 'profile' type - either 'time' or 'velocity' as described above
int32 profile_velocity              # desired velocity profile as explained above - only used in 'position' or the 'ext_position' control modes
int32 profile_acceleration          # desired acceleration profile as explained above - used in all modes except for 'current' and 'pwm' control
---

MotorGains

Used to set PID gains on a joint or group of joints.

To get familiar with the various PID gains, go to the DYNAMIXEL Workbench E-Manual page, click on a motor model, and scroll down to the ‘PID’ section.

string cmd_type          # set to 'group' if commanding a joint group or 'single' if commanding a single joint
string name              # name of the group if commanding a joint group or joint if commanding a single joint
int32 kp_pos             # acts as a pass-through to the Position_P_Gain register
int32 ki_pos             # acts as a pass-through to the Position_I_Gain register
int32 kd_pos             # acts as a pass-through to the Position_D_Gain register
int32 k1                 # acts as a pass-through to the Feedforward_1st_Gain register
int32 k2                 # acts as a pass-through to the Feedforward_2nd_Gain register
int32 kp_vel             # acts as a pass-through to the Velocity_P_Gain register
int32 ki_vel             # acts as a pass-through to the Velocity_I_Gain register
---

RegisterValues

Used to set or get the register(s) value(s) from a joint or group of joints.

To get familiar with the register values, go to the DYNAMIXEL Workbench E-Manual page, click on a motor model, and scroll down to the ‘Control Table of RAM Area’ section.

string cmd_type          # set to 'group' if commanding a joint group or 'single' if commanding a single joint
string name              # name of the group if commanding a joint group or joint if commanding a single joint
string reg               # register name (like Profile_Velocity, Profile_Acceleration, etc...)
int32 value              # desired register value (only set if 'setting' a register)
---
int32[] values           # current register values (only filled if 'getting' a register)