Only released in EOL distros:  

segwayrmp: rmp_base | rmp_description | rmp_msgs | rmp_teleop

Package Summary

The rmp_base package provides a ros interface to control a Segway Robotics Mobility Platform. In addition, navigation and status data are also published such as odometry, imu, mottor and battery status, ...

Overview

The rmp_base package provides a ros interface to control a Segway Robotics Mobility Platform (http://rmp.segway.com/). It supports USB and UDP interfaces.

Please refer to the RMP documentation for a description of the sensors' coordinate system.

This package has only been tested on the RMP 440LE (http://rmp.segway.com/about-segway-robotics/segway-rmp440-le-and-se/).

Quick Start

$ roslaunch rmp_base rmp440le.launch

Node

rmp_440le_node

ros interface to control a Segway RMP 440LE.

Subscribed Topics

/rmp440le/base/vel_cmd (geometry_msgs/TwistStamped)
  • velocity command
/rmp440le/deadman (rmp_msgs/BoolStamped)
  • deadman, needs to be pressed (true) for velocity commands to be processed.
/rmp440le/audio_cmd (rmp_msgs/AudioCommand)
  • audio command

Published Topics

/rmp440le/odom (nav_msgs/Odometry)
  • odometry
/rmp440le/joint_states (sensor_msgs/JointState)
  • joint states
/rmp440le/inertial (sensor_msgs/Imu)
  • inertial measurements
/rmp440le/pse (sensor_msgs/Imu)
  • pitch state estimate
/rmp440le/motor_status (rmp_msgs/MotorStatus)
  • motor status (current, power, ...)
/rmp440le/battery (rmp_msgs/Battery)
  • battery status (charge level, temperature, ...)
/rmp440le/fault_status (rmp_msgs/FaultStatus)
  • report faults

Parameters

transport_type (string, default: udp)
  • specify transport type: udb, usb
ip_address (string, default: 192.168.0.40)
  • specify the ip address of the rmp. This parameter is only used when transport_type is set to udp.
port_number (int, default: 8080)
  • specify the port number of the rmp. This parameter is only used when transport_type is set to udp.
device_port (string, default: /dev/ttyACM0)
  • specify a serial device. This parameter is only used when transport_type is set to usb.
update_frequency (double, default: 50.0)
  • specify the node process rate, [0.5, 100.0][Hz]
odometry_topic (string, default: /rmp440le/odom)
  • odometry topic
joint_states_topic (string, default: /rmp440le/joint_states)
  • joint states topic
inertial_topic (string, default: /rmp440le/inertial)
  • inertial topic
pse_topic (string, default: /rmp440le/pse)
  • pse topic
motor_status_topic (string, default: /rmp440le/motor_status)
  • motor status topic
battery_topic (string, default: /rmp440le/battery)
  • battery topic
velocity_command_topic (string, default: /rmp440le/base/vel_cmd)
  • velocity command topic
deadman_topic (string, default: /rmp440le/deadman)
  • deadman topic
audio_command_topic (string, default: /rmp440le/audio_cmd)
  • audio command topic
fault_status_topic (string, default: /rmp440le/fault_status)
  • fault status topic
max_translational_velocity (double, default: 8.0)
  • maximum translational velocity [0.0, 8.047][m/s]
max_turn_rate (string, default: 4.4)
  • maximum turn rate [0.0, 4.5][rad/s]

Wiki: rmp_base (last edited 2014-08-13 22:59:53 by ThomasDecandia)