#include <Rmp440LE.h>
This class setup a ros interface to the Segway RMP 440LE.
Definition at line 98 of file Rmp440LE.h.
Constructor
Definition at line 70 of file Rmp440LE.cpp.
Destructor
Definition at line 76 of file Rmp440LE.cpp.
void Rmp440LE::Initialize | ( | ) |
Initialize the communication.
Definition at line 81 of file Rmp440LE.cpp.
void Rmp440LE::InitializeMessages | ( | ) | [private] |
Initialize ros messages
Definition at line 219 of file Rmp440LE.cpp.
bool Rmp440LE::IsDeadmanValid | ( | ) | [private] |
Check wether the deadman command is valid It has to be true and has to be "recent".
Definition at line 482 of file Rmp440LE.cpp.
void Rmp440LE::ProcessAudioCommand | ( | const rmp_msgs::AudioCommand::ConstPtr & | rpAudioCommand | ) | [private] |
Process audio commands The different audio commands are defined in the rmp user manual (p.51) and in the rmp_msg package.
rpAudioCommand | audio command |
Definition at line 307 of file Rmp440LE.cpp.
void Rmp440LE::ProcessDeadman | ( | const rmp_msgs::BoolStamped::ConstPtr & | rpDeadmanMsg | ) | [private] |
Process deadman messages. The deadman needs to be pressed (true) for the velocity commands to be processed.
rpDeadmanMsg | deadman message |
Definition at line 302 of file Rmp440LE.cpp.
void Rmp440LE::ProcessVelocityCommand | ( | const geometry_msgs::TwistStamped::ConstPtr & | rpVelocityCommand | ) | [private] |
Process velocity commands. Velocity commands are defined by a linear and angular vector. Translational velocity is defined in the x field of the linear vector in [m/s] with the positive axis pointing forward. Turn rate is defined in the z field of the angular vector in [rad/s] with the positive axis pointing upward. The rmp has to be in tractor mode for the command to be effective. The command should not be outside the predefined range. Please refer to the rmp user manual for more information.
rpVelocityCommand | velocity command |
std::logic_error | if the velocity command is out of range |
Definition at line 263 of file Rmp440LE.cpp.
void Rmp440LE::UpdateBattery | ( | ) | [private] |
Publish battery data
Definition at line 416 of file Rmp440LE.cpp.
void Rmp440LE::UpdateFaultStatus | ( | ) | [private] |
Publish fault status An empty messages means no fault
Definition at line 473 of file Rmp440LE.cpp.
void Rmp440LE::UpdateImu | ( | ) | [private] |
Publish Pse (Pitch State Estimate) and inertial data The coordinate systems are defined in the rmp user manual (p.12).
Definition at line 330 of file Rmp440LE.cpp.
void Rmp440LE::UpdateMotorStatus | ( | ) | [private] |
Publish motor status
Definition at line 442 of file Rmp440LE.cpp.
void Rmp440LE::UpdateOdometry | ( | ) | [private] |
Publish odometry
Definition at line 360 of file Rmp440LE.cpp.
void Rmp440LE::UpdateStatus | ( | ) | [private] |
Publish rmp status related information such as imu, odometry, battery, motor and fault(s).
Definition at line 321 of file Rmp440LE.cpp.
Audio command subscriber
Definition at line 243 of file Rmp440LE.h.
ros::Publisher Rmp440LE::m_BatteryPublisher [private] |
Battery data publisher
Definition at line 223 of file Rmp440LE.h.
rmp_msgs::BoolStamped Rmp440LE::m_DeadmanMsg [private] |
Most recent deadman message
Definition at line 268 of file Rmp440LE.h.
ros::Subscriber Rmp440LE::m_DeadmanSubscriber [private] |
Deadman command subscriber
Definition at line 238 of file Rmp440LE.h.
Fault status publisher
Definition at line 228 of file Rmp440LE.h.
sensor_msgs::Imu Rmp440LE::m_InertialMsg [private] |
Inertial data message
Definition at line 258 of file Rmp440LE.h.
ros::Publisher Rmp440LE::m_InertialPublisher [private] |
Inertial data publisher
Definition at line 208 of file Rmp440LE.h.
sensor_msgs::JointState Rmp440LE::m_JointStateMsg [private] |
Joint state message
Definition at line 253 of file Rmp440LE.h.
Joint states publisher
Definition at line 203 of file Rmp440LE.h.
Motor status publisher
Definition at line 218 of file Rmp440LE.h.
ros::NodeHandle Rmp440LE::m_NodeHandle [private] |
Ros interface
Definition at line 193 of file Rmp440LE.h.
bool Rmp440LE::m_OdometryInitialized [private] |
Wether the odometry has been initialized
Definition at line 278 of file Rmp440LE.h.
nav_msgs::Odometry Rmp440LE::m_OdometryMsg [private] |
Odometry message
Definition at line 248 of file Rmp440LE.h.
ros::Publisher Rmp440LE::m_OdometryPublisher [private] |
Odometry publisher
Definition at line 198 of file Rmp440LE.h.
sensor_msgs::Imu Rmp440LE::m_PseMsg [private] |
Pse (Pitch State Estimate) message
Definition at line 263 of file Rmp440LE.h.
ros::Publisher Rmp440LE::m_PsePublisher [private] |
Pse (Pitch State Estimate) publisher
Definition at line 213 of file Rmp440LE.h.
Rmp 440LE interface
Definition at line 188 of file Rmp440LE.h.
Velocity command subscriber
Definition at line 233 of file Rmp440LE.h.
Last updated wheel displacement
Definition at line 273 of file Rmp440LE.h.