Wiki

Only released in EOL distros:  

Package Summary

ROS Wrapper for the Segway RMP Ethernet Python Driver

Package Summary

ROS Wrapper for the Segway RMP Ethernet Python Driver

About

The ros_ethernet_rmp package is used to bridge ROS and a Segway RMP. It will convert cmd_vel topic messages to the RMPCommand format and then publish the feedback from the RMP. There is also a joint state publisher to read in the feedback and publish the changing joint states as necessary.

Nodes

ethernet_rmp.py

ethernet_rmp.py interfaces ROS with the RMP drivers.

Subscribed Topics

cmd_vel ('geometry_msgs/Twist') rmp_command ('rmp_msgs/RMPCommand')

Published Topics

rmp_feedback ('rmp_msgs/RMPFeedback')

Parameters

~update_delay_sec (double, default: 0.05) ~log_data (bool, default: False) ~current_rmp_ip_addr (string, default: DEFAULT_IP_ADDRESS) ~current_rmp_port_num (int, default: DEFAULT_PORT_NUMBER) ~is_omni (bool, default: False) ~my_velocity_limit_mps (double, default: DEFAULT_MAXIMUM_VELOCITY_MPS) ~my_accel_limit_mps2 (double, default: DEFAULT_MAXIMUM_ACCELERATION_MPS2) ~my_decel_limit_mps2 (double, default: DEFAULT_MAXIMUM_DECELERATION_MPS2) ~my_dtz_rate_mps2 (double, default: DEFAULT_MAXIMUM_DTZ_DECEL_RATE_MPS2) ~my_coastdown_accel_mps2 (double, default: DEFAULT_COASTDOWN_ACCEL_MPS2) ~my_yaw_rate_limit_rps (double, default: DEFAULT_MAXIMUM_YAW_RATE_RPS) ~my_yaw_accel_limit_rps2 (double, default: DEFAULT_MAX_YAW_ACCEL_RPS2) ~my_tire_diameter_m (double, default: DEFAULT_TIRE_DIAMETER_M) ~my_wheel_base_length_m (double, default: DEFAULT_WHEEL_BASE_LENGTH_M) ~my_wheel_track_width_m (double, default: DEFAULT_WHEEL_TRACK_WIDTH_M) ~my_gear_ratio (double, default: DEFAULT_TRANSMISSION_RATIO) ~my_config_bitmap (int, default: DEFAULT_CONFIG_BITMAP) ~my_ip_address (string, default: DEFAULT_IP_ADDRESS) ~my_port_num (int, default: DEFAULT_PORT_NUMBER) ~my_subnet_mask (string, default: DEFAULT_SUBNET_MASK) ~my_gateway (string, default: DEFAULT_GATEWAY) ~my_user_defined_feedback_bitmap_1 (double, default: DEFAULT_USER_FB_1_BITMAP) ~my_user_defined_feedback_bitmap_2 (double, default: DEFAULT_USER_FB_2_BITMAP) ~my_user_defined_feedback_bitmap_3 (double, default: DEFAULT_USER_FB_3_BITMAP) ~my_user_defined_feedback_bitmap_4 (double, default: DEFAULT_USER_FB_4_BITMAP)

rmp_pose_updater.py

rmp_pose_updater.py publishes odom information based on the feedback from the RMP

Subscribed Topics

rmp_feedback ('rmp_msgs/RMPFeedback')

Published Topics

odom ('nav_msgs/Odometry')

Parameters

~publish_tf (bool, default: True)

Transforms

rmp_pose_updater broadcasts the robot frame ('/base_footprint') with respect to the odometry frame (/odom).

rmp_joint_state.py

rmp_joint_state.py publishes joint state information based on the feedback from the RMP

Subscribed Topics

rmp_feedback ('rmp_msgs/RMPFeedback')

Published Topics

rmp_joint_states ('sensor_msgs/JointState')

Parameters

~has_two_wheels (bool, default: True) ~link_left_front (string, default: base_link_left_wheel_joint) ~link_right_front (string, default: base_link_left_wheel_joint) ~link_left_rear (string, default: base_link_left_rear_wheel_joint) ~link_right_rear (string, default: base_link_right_rear_wheel_joint)

Installation

To install the ros_ethernet_rmp package, you can choose to either install from source, or from the Ubuntu package:

Source

To install from source, execute the following:

Ubuntu Package

To install the Ubuntu package, execute the following:

Startup

The ros_ethernet_rmp package contains a ros_ethernet_rmp.launch file. This file launches an instance of the ethernet_rmp.py, 'rmp_pose_updater.py' and rmp_joint_states.py nodes. 'battery_monitor_rmp.launch' from 'battery_monitor_rmp' will also be launched if the argument, include_batt_monitor, is true. It is defaulted to true. To launch these nodes, with the battery monitor the following command can be used:

roslaunch ros_ethernet_rmp ros_ethernet_rmp.launch 

To launch these nodes without the battery monitor, the following command can be used:

roslaunch ros_etehrnet_rmp ros_ethernet_rmp.launch include_batt_monitor:=false

Support

Please send bug reports to the GitHub Issue Tracker. Feel free to contact me at any point with questions and comments.

Wiki: ros_ethernet_rmp (last edited 2014-12-12 16:35:33 by davidkent)