No version for distro humble. Known supported distros are highlighted in the buttons above.
No version for distro jazzy. Known supported distros are highlighted in the buttons above.
No version for distro rolling. Known supported distros are highlighted in the buttons above.

interbotix_xs_sdk package from ros2-essentials repo

interbotix_footswitch_driver interbotix_footswitch_msgs interbotix_ros_slate interbotix_slate_driver interbotix_slate_msgs dynamixel_workbench_toolbox interbotix_ros_xseries interbotix_xs_driver interbotix_xs_msgs interbotix_xs_sdk interbotix_ros_xsarms_examples interbotix_xsarm_diagnostic_tool interbotix_xsarm_dual interbotix_xsarm_dual_joy interbotix_xsarm_joy interbotix_xsarm_moveit_interface interbotix_xsarm_pid interbotix_xsarm_puppet interbotix_ros_xsarms interbotix_xsarm_control interbotix_xsarm_descriptions interbotix_xsarm_moveit interbotix_xsarm_perception interbotix_xsarm_ros_control interbotix_xsarm_sim interbotix_common_modules interbotix_common_sim interbotix_common_toolbox interbotix_landmark_modules interbotix_moveit_interface interbotix_moveit_interface_msgs interbotix_tf_tools interbotix_io_modules interbotix_io_toolbox interbotix_perception_modules interbotix_perception_msgs interbotix_perception_pipelines interbotix_perception_toolbox interbotix_rpi_modules interbotix_rpi_msgs interbotix_rpi_toolbox interbotix_xs_modules interbotix_xs_ros_control interbotix_xs_rviz interbotix_xs_toolbox moveit_visual_tools cartographer_demo multi_lidar_desp multi_lidar_gazebo aws_robomaker_hospital_world aws_robomaker_small_house_world aws_robomaker_small_warehouse_world citysim clearpath_playpen gazebo_launch turtlebot3_gazebo lms1xx husky_base husky_bringup husky_control husky_description husky_desktop husky_gazebo husky_msgs husky_navigation husky_robot husky_simulator husky_viz cmd_vel_mux ecl_command_line ecl_concepts ecl_containers ecl_converters ecl_core ecl_core_apps ecl_devices ecl_eigen ecl_exceptions ecl_filesystem ecl_formatters ecl_geometry ecl_ipc ecl_linear_algebra ecl_manipulators ecl_math ecl_mobile_robot ecl_mpl ecl_sigslots ecl_statistics ecl_streams ecl_threads ecl_time ecl_type_traits ecl_utilities ecl_config ecl_console ecl_converters_lite ecl_errors ecl_io ecl_lite ecl_sigslots_lite ecl_time_lite kobuki_core kobuki_keyop kobuki_node kobuki_ros kobuki_ros_interfaces sophus kobuki_control kobuki_description kobuki_gazebo kobuki_launch kobuki_navigation kobuki_rviz velodyne_description velodyne_gazebo_plugins velodyne_simulator rtabmap_sim minimal_pkg turtlebot3 turtlebot3_bringup turtlebot3_cartographer turtlebot3_description turtlebot3_example turtlebot3_navigation2 turtlebot3_node turtlebot3_teleop turtlebot3_cartographer_ex turtlebot3_fake_node turtlebot3_simulations vlp_cartographer

Package Summary

Tags No category tags.
Version 0.0.0
License BSD
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description A repo containing essential ROS2 Humble features for controlling Autonomous Mobile Robots (AMRs) and robotic arm manipulators.
Checkout URI https://github.com/j3soon/ros2-essentials.git
VCS Type git
VCS Version main
Last Updated 2025-02-20
Dev Status UNKNOWN
CI status No Continuous Integration
Released UNRELEASED
Tags docker robotics docker-compose ros isaac slam nvidia-docker ros2 isaacsim isaac-sim nav2 omniverse ros2-humble
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

The interbotix_xs_sdk package

Additional Links

No additional links.

Maintainers

  • Luke Schmitt

Authors

  • Solomon Wiznitzer

Interbotix X-Series SDK ROS Package

xs_sdk_banner

Overview

This package contains two driver nodes responsible for controlling the many Interbotix X-Series platforms sold by Trossen Robotics. Descriptions for both of them are below.

The xs_sdk node is a ROS wrapper for the Interbotix X-Series Driver. This allows robots based on the X-Series servos to be controlled through higher-level ROS commands. The X-Series driver is loosely based on the dynamixel_workbench_controllers.cpp file created by ROBOTIS. Feel free to take a look at their API to get a better understanding of how their functions work. Also, take a look at the interbotix_xs_sdk’s header file here which contains the fully documented ROS features like publishers, subscribers, timers, and services.

The xs_sdk_sim node is meant to simulate control of DYNAMIXEL servos which can then be visualized RViz. It contains the same ROS interfaces as the actual driver and can be used to ‘test-out’ code before working with the physical motors. All higher level code or ROS packages can stay exactly the same (no code needs to be changed to make them compatible with the simulator). It is written in Python, and the documented code can be found here. It does have some limitations which are described in the ‘Structure’ section below.

Structure

The interbotix_xs_sdk package contains the actual driver node called xs_sdk and a simulation node called xs_sdk_sim. As mentioned previously, these nodes are responsible for controlling the robot. Please look below for a description of the ROS topics, services, actions, and parameters available to the user. Note that the ‘mode’ and ‘motor’ config files referenced in some of the descriptions can be found in the ‘config’ directory of the interbotix_XXXXX_control package in any interbotix_ros_XXXXX repository. Templates, including parameter descriptions, can be found in the ‘config’ directory located here. Finally, if there is any difference between how the two nodes behave, that will be outlined below too.

Publishers
  • /<robot_name>/joint_states - publishes ROS JointState messages at a user-desired frequency; note that in general, positions are given in radians, velocities are given in radians per second, and effort is given in milliamps. If the robot has a two-finger gripper, the positions for the ‘right_finger’ and ‘left_finger’ joints are given in meters relative to a virtual ‘fingers_link’ placed dead center (launch a robot model in RViz to get familiar with the link and joint names/positions).

    Simulation: publishes ROS JointState messages at 20 Hz. Only the ‘name’ and ‘position’ fields in the messages are populated. Otherwise, it operates the same as the physical driver.

Subscribers
  • /<robot_name>/commands/joint_group - subscribes to JointGroupCommand messages; this topic is used to control a specified group of joints synchronously (which is more efficient than sending commands to individual joints consecutively). Refer to the message description for implementation details. Any number of joint groups can be defined in the motor config file.
  • /<robot_name>/commands/joint_single - subscribes to JointSingleCommand messages; this topic is used to control a single joint. Refer to the message description for implementation details.
  • /<robot_name>/commands/joint_trajectory - subscribes to ROS JointTrajectoryCommand messages; this topic is used to send desired trajectories to a specified joint or joint group. Refer to the message description for implementation details.

    Simulation: All Subscription topics behave identically to the physical driver ones.

Services
  • /<robot_name>/torque_enable - service to torque on/off the specified motor or motors; refer to the TorqueEnable service description for implementation details.

    Simulation: messages are displayed showing that the desired motors were torqued on/off, but nothing actually happens.

  • /<robot_name>/reboot_motors - service to reboot the specified motor or motors; refer to the Reboot service description for implementation details.

    Simulation: messages are displayed showing that the desired motors were rebooted, but nothing actually happens.

  • /<robot_name>/get_robot_info - service to get robot information like joint limits, joint names, and joint ‘sleep’ positions; refer to the RobotInfo service description for implementation details.
  • /<robot_name>/set_operating_modes - service to set a motor’s or multiple motors’ operating modes (like position, velocity, current, etc…); refer to the OperatingModes service description for implementation details. Note that the motors will torque off for a moment when changing operating modes so make sure that the robot is in its ‘sleep’ pose (defined in the motor config file) or otherwise secured before calling this service.

    Simulation: behaves exactly the same except setting the operating mode just changes how the desired motors will be simulated; of course, nothing is torqued off either. Note that ‘current_based_position’, ‘ext_position’, and ‘position’ are all treated equivalently. Similarly, ‘pwm’ and ‘current’ modes are also treated the same, and masses/inertias of links are NOT considered. Additionally, when in a ‘position-type’ mode, motors should be using the ‘Time-based Profile’ Drive Mode as the ‘Profile_Velocity’ register is used to determine how long a motion should take (‘Profile Acceleration’ is ignored).

  • /<robot_name>/set_motor_pid_gains - service to set a motor’s or multiple motors’ internal PID gains for position/velocity control; refer to the MotorGains service description for implementation details.

    Simulation: doesn’t affect anything; no messages are even displayed.

  • /<robot_name>/set_motor_registers - service to set a motor’s or multiple motors’ register values at once for a user-provided register name; refer to the RegisterValues service description for implementation details.

    Simulation: only works the same if setting the ‘Profile_Velocity’ or ‘Profile_Acceleration’ registers; otherwise, nothing happens.

  • /<robot_name>/get_motor_registers - service to get a motor’s or multiple motors’ register values at once for a user-provided register name; refer to the RegisterValues service description for implementation details.

    Simulation: only works the same if getting the ‘Profile_Velocity’ or ‘Profile_Acceleration’ registers; otherwise, an empty service message is returned.

Parameters
  • motor_configs - the file path to the ‘motor config’ YAML file; refer to the Motor Config Template file for details.
  • mode_configs - the file path to the ‘mode config’ YAML file; refer to the Mode Config Template file for details.
  • load_configs - a boolean that specifies whether or not the initial register values (under the ‘motors’ heading) in a motor config file should be written to the motors; as the values being written are stored in each motor’s EEPROM (which means the values are retained even after a power cycle), this can be set to ‘false’ after the first time using the robot. Setting to ‘false’ also shortens the node startup time by a few seconds and preserves the life of the EEPROM.
  • xs_driver_logging_level - a string value of DEBUG, INFO, WARN, ERROR, or FATAL that sets the logging level of the X-Series Driver.

    Simulation: the load_configs and xs_driver_logging_level parameters are unused.

Usage

To comply with the IRROS standard, this package contains no launch or config files (to keep it robot agnostic). Either node within it is meant to be included in the launch file located in any interbotix_XXXXX_control package (and passed the robot-specific motor and mode config files). For optimal usability, a URDF should also be loaded to the parameter server so that the get_robot_info ROS service can get joint position and velocity limits.

Notes

Please note that the nodes do NOT check joint limits. It is up to the user to make sure that joint limits are not violated (such as by using the limits defined in the URDF) and that motors do not collide with any obstacles.

CHANGELOG
No CHANGELOG found.

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged interbotix_xs_sdk at Robotics Stack Exchange

No version for distro noetic. Known supported distros are highlighted in the buttons above.
No version for distro ardent. Known supported distros are highlighted in the buttons above.
No version for distro bouncy. Known supported distros are highlighted in the buttons above.
No version for distro crystal. Known supported distros are highlighted in the buttons above.
No version for distro eloquent. Known supported distros are highlighted in the buttons above.
No version for distro dashing. Known supported distros are highlighted in the buttons above.
No version for distro galactic. Known supported distros are highlighted in the buttons above.
No version for distro foxy. Known supported distros are highlighted in the buttons above.
No version for distro iron. Known supported distros are highlighted in the buttons above.
No version for distro lunar. Known supported distros are highlighted in the buttons above.
No version for distro jade. Known supported distros are highlighted in the buttons above.
No version for distro indigo. Known supported distros are highlighted in the buttons above.
No version for distro hydro. Known supported distros are highlighted in the buttons above.
No version for distro kinetic. Known supported distros are highlighted in the buttons above.
No version for distro melodic. Known supported distros are highlighted in the buttons above.