segway_rmp_node.cpp
Go to the documentation of this file.
1 /*
2  * The MIT License (MIT)
3  * Copyright (c) 2011 William Woodall <wjwwood@gmail.com>
4  *
5  * Permission is hereby granted, free of charge, to any person obtaining a
6  * copy of this software and associated documentation files (the "Software"),
7  * to deal in the Software without restriction, including without limitation
8  * the rights to use, copy, modify, merge, publish, distribute, sublicense,
9  * and/or sell copies of the Software, and to permit persons to whom the
10  * Software is furnished to do so, subject to the following conditions:
11  *
12  * The above copyright notice and this permission notice shall be included
13  * in all copies or substantial portions of the Software.
14  *
15  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
18  * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
20  * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
21  * DEALINGS IN THE SOFTWARE.
22  */
23 
24 #include <iostream>
25 #include <sstream>
26 #include <cmath>
27 
28 #include "ros/ros.h"
30 #include "geometry_msgs/Twist.h"
31 #include "nav_msgs/Odometry.h"
32 #include "segway_rmp/SegwayStatusStamped.h"
33 
34 #include "segwayrmp/segwayrmp.h"
35 
36 #include <boost/thread.hpp>
37 
39 
41 
42 static double radians_to_degrees = 180.0 / M_PI;
43 static double degrees_to_radians = M_PI / 180.0;
44 
45 // Message Wrappers
46 void handleDebugMessages(const std::string &msg) {ROS_DEBUG("%s",msg.c_str());}
47 void handleInfoMessages(const std::string &msg) {ROS_INFO("%s",msg.c_str());}
48 void handleErrorMessages(const std::string &msg) {ROS_ERROR("%s",msg.c_str());}
49 
51 
52 // ROS Node class
54 public:
56  n = new ros::NodeHandle("~");
57  this->segway_rmp = NULL;
58  this->first_odometry = true;
59  this->last_forward_displacement = 0.0;
60  this->last_yaw_displacement = 0.0;
61  this->odometry_x = 0.0;
62  this->odometry_y = 0.0;
63  this->odometry_w = 0.0;
64  this->linear_vel = 0.0;
65  this->angular_vel = 0.0;
66  this->target_linear_vel = 0.0;
67  this->target_angular_vel = 0.0;
72  this->count = 0;
73  }
74 
76  this->disconnect();
77  }
78 
79  void disconnect() {
80  if (this->segway_rmp != NULL)
81  delete this->segway_rmp;
82  this->segway_rmp = NULL;
83  }
84 
85  void run() {
86  if (this->getParameters()) {
87  return;
88  }
89 
90  this->setupSegwayRMP();
91 
92  this->setupROSComms();
93 
94  // Setup keep alive timer
96 
98  spinner.start();
99 
101 
102  this->connected = false;
103  while (ros::ok()) {
104  try {
105  this->segway_rmp->connect();
106  this->connected = true;
107  } catch (std::exception& e) {
108  std::string e_msg(e.what());
109  ROS_ERROR("Exception while connecting to the SegwayRMP, check your cables and power buttons.");
110  ROS_ERROR(" %s", e_msg.c_str());
111  this->connected = false;
112  }
113  if (this->spin()) { // ROS is OK, but we aren't connected, wait then try again
114  ROS_WARN("Not connected to the SegwayRMP, will retry in 5 seconds...");
115  ros::Duration(5).sleep();
116  }
117  }
118  }
119 
120  bool spin() {
121  if (ros::ok() && this->connected) {
122  ROS_INFO("Segway RMP Ready.");
123  while (ros::ok() && this->connected) {
124  ros::Duration(1.0).sleep();
125  }
126  }
127  if (ros::ok()) { // Error not shutdown
128  return true;
129  } else { // Shutdown
130  return false;
131  }
132  }
133 
139 
140  if (!this->connected || this->reset_odometry)
141  return;
142 
143  if (ros::ok()) {
144  boost::mutex::scoped_lock lock(this->m_mutex);
145 
146  // Update the linear velocity based on the linear acceleration limits
147  if (this->linear_vel < this->target_linear_vel) {
148  // Must increase linear speed
149  if (this->linear_pos_accel_limit == 0.0
150  || this->target_linear_vel - this->linear_vel < this->linear_pos_accel_limit)
151  this->linear_vel = this->target_linear_vel;
152  else
153  this->linear_vel += this->linear_pos_accel_limit;
154  } else if (this->linear_vel > this->target_linear_vel) {
155  // Must decrease linear speed
156  if (this->linear_neg_accel_limit == 0.0
157  || this->linear_vel - this->target_linear_vel < this->linear_neg_accel_limit)
158  this->linear_vel = this->target_linear_vel;
159  else
160  this->linear_vel -= this->linear_neg_accel_limit;
161  }
162 
163  // Update the angular velocity based on the angular acceleration limits
164  if (this->angular_vel < this->target_angular_vel) {
165  // Must increase angular speed
166  if (this->angular_pos_accel_limit == 0.0
167  || this->target_angular_vel - this->angular_vel < this->angular_pos_accel_limit)
168  this->angular_vel = this->target_angular_vel;
169  else
170  this->angular_vel += this->angular_pos_accel_limit;
171  } else if (this->angular_vel > this->target_angular_vel) {
172  // Must decrease angular speed
173  if (this->angular_neg_accel_limit == 0.0
174  || this->angular_vel - this->target_angular_vel < this->angular_neg_accel_limit)
175  this->angular_vel = this->target_angular_vel;
176  else
177  this->angular_vel -= this->angular_neg_accel_limit;
178  }
179 
180  ROS_DEBUG("Sending move command: linear velocity = %f, angular velocity = %f",
181  this->linear_vel, this->angular_vel);
182 
183  //if (this->linear_vel == 0 || this->angular_vel == 0) {
184  // ROS_INFO("Sending Segway Command: l=%f a=%f", this->linear_vel, this->angular_vel);
185  //}
186  try {
187  this->segway_rmp->move(this->linear_vel, this->angular_vel);
188  } catch (std::exception& e) {
189  std::string e_msg(e.what());
190  ROS_ERROR("Error commanding Segway RMP: %s", e_msg.c_str());
191  this->connected = false;
192  this->disconnect();
193  }
194  }
195  }
196 
198  if (!this->connected)
199  return;
200  // Get the time
201  ros::Time current_time = ros::Time::now();
202 
203  this->sss_msg.header.stamp = current_time;
204 
205  segwayrmp::SegwayStatus &ss = *(ss_ptr);
206 
207  // Check if an odometry reset is still required
208  if (this->reset_odometry) {
209  if ((current_time - this->odometry_reset_start_time).toSec() < 0.25) {
210  return; // discard readings for the first 0.25 seconds
211  }
212  if (fabs(ss.integrated_forward_position) < 1e-3 &&
213  fabs(ss.integrated_turn_position) < 1e-3 &&
214  fabs(ss.integrated_left_wheel_position) < 1e-3 &&
215  fabs(ss.integrated_right_wheel_position) < 1e-3) {
220  ROS_INFO("Integrators reset by Segway RMP successfully");
221  this->reset_odometry = false;
222  } else if ((current_time - this->odometry_reset_start_time).toSec() > this->odometry_reset_duration) {
227  ROS_INFO("Integrator reset by Segway RMP failed. Performing software reset");
228  this->reset_odometry = false;
229  } else {
230  return; // continue waiting for odometry to be reset
231  }
232  }
233 
234  this->sss_msg.segway.pitch_angle = ss.pitch * degrees_to_radians;
235  this->sss_msg.segway.pitch_rate = ss.pitch_rate * degrees_to_radians;
236  this->sss_msg.segway.roll_angle = ss.roll * degrees_to_radians;
237  this->sss_msg.segway.roll_rate = ss.roll_rate * degrees_to_radians;
238  this->sss_msg.segway.left_wheel_velocity = ss.left_wheel_speed;
239  this->sss_msg.segway.right_wheel_velocity = ss.right_wheel_speed;
240  this->sss_msg.segway.yaw_rate = ss.yaw_rate * degrees_to_radians;
241  this->sss_msg.segway.servo_frames = ss.servo_frames;
242  this->sss_msg.segway.left_wheel_displacement =
244  this->sss_msg.segway.right_wheel_displacement =
246  this->sss_msg.segway.forward_displacement =
248  this->sss_msg.segway.yaw_displacement =
250  this->sss_msg.segway.left_motor_torque = ss.left_motor_torque;
251  this->sss_msg.segway.right_motor_torque = ss.right_motor_torque;
252  this->sss_msg.segway.operation_mode = ss.operational_mode;
253  this->sss_msg.segway.gain_schedule = ss.controller_gain_schedule;
254  this->sss_msg.segway.ui_battery = ss.ui_battery_voltage;
255  this->sss_msg.segway.powerbase_battery = ss.powerbase_battery_voltage;
256  this->sss_msg.segway.motors_enabled = (bool)(ss.motor_status);
257 
259 
260  // TODO: possibly spin this off in another thread
261 
262  // Grab the newest Segway data
263  float forward_displacement =
265  this->linear_odom_scale;
266  float yaw_displacement =
269  float yaw_rate = ss.yaw_rate * degrees_to_radians;
270 
271  // Integrate the displacements over time
272  // If not the first odometry calculate the delta in displacements
273  float vel_x = 0.0;
274  float vel_y = 0.0;
275  if(!this->first_odometry) {
276  float delta_forward_displacement =
277  forward_displacement - this->last_forward_displacement;
278  double delta_time = (current_time-this->last_time).toSec();
279  // Update accumulated odometries and calculate the x and y components
280  // of velocity
281  this->odometry_w = yaw_displacement;
282  float delta_odometry_x =
283  delta_forward_displacement * std::cos(this->odometry_w);
284  vel_x = delta_odometry_x / delta_time;
285  this->odometry_x += delta_odometry_x;
286  float delta_odometry_y =
287  delta_forward_displacement * std::sin(this->odometry_w);
288  vel_y = delta_odometry_y / delta_time;
289  this->odometry_y += delta_odometry_y;
290  } else {
291  this->first_odometry = false;
292  }
293  // No matter what update the previouse (last) displacements
294  this->last_forward_displacement = forward_displacement;
295  this->last_yaw_displacement = yaw_displacement;
296  this->last_time = current_time;
297 
298  // Create a Quaternion from the yaw displacement
299  geometry_msgs::Quaternion quat =
300  tf::createQuaternionMsgFromYaw(yaw_displacement);
301 
302  // Publish the Transform odom->base_link
303  if (this->broadcast_tf) {
304  this->odom_trans.header.stamp = current_time;
305 
306  this->odom_trans.transform.translation.x = this->odometry_x;
307  this->odom_trans.transform.translation.y = this->odometry_y;
308  this->odom_trans.transform.translation.z = 0.0;
309  this->odom_trans.transform.rotation = quat;
310 
311  //send the transform
313  }
314 
315  // Publish Odometry
316  this->odom_msg.header.stamp = current_time;
317  this->odom_msg.pose.pose.position.x = this->odometry_x;
318  this->odom_msg.pose.pose.position.y = this->odometry_y;
319  this->odom_msg.pose.pose.position.z = 0.0;
320  this->odom_msg.pose.pose.orientation = quat;
321  this->odom_msg.pose.covariance[0] = 0.00001;
322  this->odom_msg.pose.covariance[7] = 0.00001;
323  this->odom_msg.pose.covariance[14] = 1000000000000.0;
324  this->odom_msg.pose.covariance[21] = 1000000000000.0;
325  this->odom_msg.pose.covariance[28] = 1000000000000.0;
326  this->odom_msg.pose.covariance[35] = 0.001;
327 
328  this->odom_msg.twist.twist.linear.x = vel_x;
329  this->odom_msg.twist.twist.linear.y = vel_y;
330  this->odom_msg.twist.twist.angular.z = yaw_rate;
331 
332  this->odom_pub.publish(this->odom_msg);
333  }
334 
341  boost::mutex::scoped_lock lock(m_mutex);
342  //ROS_INFO("Motor command timeout! Setting target linear and angular velocities to be zero.");
343  this->target_linear_vel = 0.0;
344  this->target_angular_vel = 0.0;
345  }
346 
350  void cmd_velCallback(const geometry_msgs::Twist::ConstPtr& msg) {
351  if (!this->connected)
352  return;
353  boost::mutex::scoped_lock lock(m_mutex);
354  double x = msg->linear.x, z = msg->angular.z;
355  if (this->invert_x) {
356  x *= -1;
357  }
358  if (this->invert_z) {
359  z *= -1;
360  }
361  if (this->max_linear_vel != 0.0) {
362  if (abs(x) > this->max_linear_vel) {
363  x = (x > 0) ? this->max_linear_vel : -this->max_linear_vel;
364  }
365  }
366  if (this->max_angular_vel != 0.0) {
367  if (abs(z) > this->max_angular_vel) {
368  z = (z > 0) ? this->max_angular_vel : -this->max_angular_vel;
369  }
370  }
371  this->target_linear_vel = x;
372  this->target_angular_vel = z * radians_to_degrees; // Convert to degrees
373 
374  //ROS_INFO("Received motor command linear vel = %f, angular vel = %f.",
375  // this->target_linear_vel, this->target_angular_vel);
376 
377  this->motor_timeout_timer =
378  this->n->createTimer(
381  this,
382  true);
383  }
384 private:
385  // Functions
386  void setupROSComms() {
387  // Subscribe to command velocities
388  this->cmd_velSubscriber = n->subscribe("cmd_vel", 1000, &SegwayRMPNode::cmd_velCallback, this);
389  // Advertise the SegwayStatusStamped
390  this->segway_status_pub = n->advertise<segway_rmp::SegwayStatusStamped>("segway_status", 1000);
391  // Advertise the Odometry Msg
392  this->odom_pub = n->advertise<nav_msgs::Odometry>("odom", 50);
393  }
394 
395  void setupSegwayRMP() {
396  std::stringstream ss;
397  ss << "Connecting to Segway RMP via ";
399  if (this->interface_type_str == "serial") {
400  ss << "serial on serial port: " << this->serial_port;
401  this->segway_rmp->configureSerial(this->serial_port);
402  } else if (this->interface_type_str == "usb") {
403  ss << "usb ";
404  if (this->usb_selector == "serial_number") {
405  ss << "identified by the device serial number: " << this->serial_number;
406  this->segway_rmp->configureUSBBySerial(this->serial_number);
407  }
408  if (this->usb_selector == "description") {
409  ss << "identified by the device description: " << this->usb_description;
410  this->segway_rmp->configureUSBByDescription(this->usb_description);
411  }
412  if (this->usb_selector == "index") {
413  ss << "identified by the device index: " << this->usb_index;
414  this->segway_rmp->configureUSBByIndex(this->usb_index);
415  }
416  }
417  ROS_INFO("%s", ss.str().c_str());
418 
419  // Set the instance variable
420  segwayrmp_node_instance = this;
421 
422  // Set callbacks for segway data and messages
427  }
428 
430  // Get Interface Type
431  n->param("interface_type", this->interface_type_str, std::string("serial"));
432  // Get Configurations based on Interface Type
433  if (this->interface_type_str == "serial") {
435  n->param("serial_port", this->serial_port, std::string("/dev/ttyUSB0"));
436  } else if (this->interface_type_str == "usb") {
438  n->param("usb_selector", this->usb_selector, std::string("index"));
439  if (this->usb_selector == "index") {
440  n->param("usb_index", this->usb_index, 0);
441  } else if (this->usb_selector == "serial_number") {
442  n->param("usb_serial_number", this->serial_number, std::string("00000000"));
443  if (this->serial_number == std::string("00000000")) {
444  ROS_WARN("The serial_number parameter is set to the default 00000000, which shouldn't work.");
445  }
446  } else if (this->usb_selector == "description") {
447  n->param("usb_description", this->serial_number, std::string("Robotic Mobile Platform"));
448  } else {
449  ROS_ERROR(
450  "Invalid USB selector: %s, valid types are 'index', 'serial_number', and 'description'.",
451  this->usb_selector.c_str());
452  return 1;
453  }
454  } else {
455  ROS_ERROR(
456  "Invalid interface type: %s, valid interface types are 'serial' and 'usb'.",
457  this->interface_type_str.c_str());
458  return 1;
459  }
460  // Get Setup Motor Timeout
461  n->param("motor_timeout", this->segway_motor_timeout, 0.5);
462  // Get frame id parameter
463  n->param("frame_id", frame_id, std::string("base_link"));
464  n->param("odom_frame_id", odom_frame_id, std::string("odom"));
465  this->sss_msg.header.frame_id = this->frame_id;
466  this->odom_trans.header.frame_id = this->odom_frame_id;
467  this->odom_trans.child_frame_id = this->frame_id;
468  this->odom_msg.header.frame_id = this->odom_frame_id;
469  this->odom_msg.child_frame_id = this->frame_id;
470  // Get cmd_vel inversion parameters
471  n->param("invert_linear_vel_cmds", invert_x, false);
472  n->param("invert_angular_vel_cmds", invert_z, false);
473  // Get option for enable/disable tf broadcasting
474  n->param("broadcast_tf", this->broadcast_tf, true);
475  // Get the segway rmp type
476  std::string segway_rmp_type_str;
477  n->param("rmp_type", segway_rmp_type_str, std::string("200/400"));
478  if (segway_rmp_type_str == "200/400") {
480  } else if (segway_rmp_type_str == "50/100") {
482  } else {
483  ROS_ERROR(
484  "Invalid rmp type: %s, valid rmp types are '200/400' and '50/100'.",
485  segway_rmp_type_str.c_str());
486  return 1;
487  }
488 
489  // Get the linear acceleration limits in m/s^2. Zero means infinite.
490  n->param("linear_pos_accel_limit", this->linear_pos_accel_limit, 0.0);
491  n->param("linear_neg_accel_limit", this->linear_neg_accel_limit, 0.0);
492 
493  // Get the angular acceleration limits in deg/s^2. Zero means infinite.
494  n->param("angular_pos_accel_limit", this->angular_pos_accel_limit, 0.0);
495  n->param("angular_neg_accel_limit", this->angular_neg_accel_limit, 0.0);
496 
497  // Check for valid acceleration limits
498  if (this->linear_pos_accel_limit < 0) {
499  ROS_ERROR("Invalid linear positive acceleration limit of %f (must be non-negative).",
500  this->linear_pos_accel_limit);
501  return 1;
502  }
503  if (this->linear_neg_accel_limit < 0) {
504  ROS_ERROR("Invalid linear negative acceleration limit of %f (must be non-negative).",
505  this->linear_neg_accel_limit);
506  return 1;
507  }
508  if (this->angular_pos_accel_limit < 0) {
509  ROS_ERROR("Invalid angular positive acceleration limit of %f (must be non-negative).",
511  return 1;
512  }
513  if (this->angular_neg_accel_limit < 0) {
514  ROS_ERROR("Invalid angular negative acceleration limit of %f (must be non-negative).",
516  return 1;
517  }
518 
519  ROS_INFO("Accel limits: linear: pos = %f, neg = %f, angular: pos = %f, neg = %f.",
522 
523  // Get velocity limits. Zero means no limit
524  n->param("max_linear_vel", this->max_linear_vel, 0.0);
525  n->param("max_angular_vel", this->max_angular_vel, 0.0);
526 
527  if (this->max_linear_vel < 0) {
528  ROS_ERROR("Invalid max linear velocity limit of %f (must be non-negative).",
529  this->max_linear_vel);
530  return 1;
531  }
532 
533  if (this->max_angular_vel < 0) {
534  ROS_ERROR("Invalid max angular velocity limit of %f (must be non-negative).",
535  this->max_angular_vel);
536  return 1;
537  }
538 
539  ROS_INFO("Velocity limits: linear: %f, angular: %f.",
540  this->max_linear_vel, this->max_angular_vel);
541 
542  // Convert the linear acceleration limits to have units of (m/s^2)/20 since
543  // the movement commands are sent to the Segway at 20Hz.
544  this->linear_pos_accel_limit /= 20;
545  this->linear_neg_accel_limit /= 20;
546 
547  // Convert the angular acceleration limits to have units of (deg/s^2)/20 since
548  // the movement commands are sent to the Segway at 20Hz.
549  this->angular_pos_accel_limit /= 20;
550  this->angular_neg_accel_limit /= 20;
551 
552  // Get the scale correction parameters for odometry
553  n->param("linear_odom_scale", this->linear_odom_scale, 1.0);
554  n->param("angular_odom_scale", this->angular_odom_scale, 1.0);
555 
556  // Check if a software odometry reset is required
557  n->param("reset_odometry", this->reset_odometry, false);
558  n->param("odometry_reset_duration", this->odometry_reset_duration, 1.0);
559 
560  return 0;
561  }
562 
563  // Variables
565 
567 
572 
574 
575  std::string interface_type_str;
578  std::string serial_port;
579  std::string usb_selector;
580  std::string serial_number;
581  std::string usb_description;
583 
586 
587  std::string frame_id;
588  std::string odom_frame_id;
591 
592  double linear_vel;
593  double angular_vel; // The angular velocity in deg/s
594 
595  double target_linear_vel; // The ideal linear velocity in m/s
596  double target_angular_vel; // The ideal angular velocity in deg/s
597 
598  double linear_pos_accel_limit; // The max linear acceleration in (m/s^2)/20
599  double linear_neg_accel_limit; // The max linear deceleration in (m/s^2)/20
600  double angular_pos_accel_limit; // The max angular acceleration in (deg/s^2)/20
601  double angular_neg_accel_limit; // The max angular deceleration in (deg/s^2)/20
602 
603  double linear_odom_scale; // linear odometry scale correction
604  double angular_odom_scale; // angular odometry scale correction
605 
606  double max_linear_vel; // maximum allowed magnitude of velocity
608 
609  bool connected;
610 
611  segway_rmp::SegwayStatusStamped sss_msg;
612  geometry_msgs::TransformStamped odom_trans;
613  nav_msgs::Odometry odom_msg;
614 
615  int count;
616 
620  float odometry_x;
621  float odometry_y;
622  float odometry_w;
624 
625  boost::mutex m_mutex;
626 
627  // Hardware reset of integrators can sometimes fail.
628  // These help in performing a software reset.
636 
637 };
638 
639 // Callback wrapper
641  segwayrmp_node_instance->handleStatus(ss);
642 }
643 
644 int main(int argc, char **argv) {
645  ros::init(argc, argv, "segway_rmp_node");
646 
647  SegwayRMPNode segwayrmp_node;
648 
649  segwayrmp_node.run();
650 
651  return 0;
652 }
tf::TransformBroadcaster odom_broadcaster
double segway_motor_timeout
void configureUSBByIndex(int device_index, int baudrate=460800)
ros::NodeHandle * n
std::string serial_number
void setLogMsgCallback(std::string log_level, LogMsgCallback callback)
void publish(const boost::shared_ptr< M > &message) const
void handleStatus(segwayrmp::SegwayStatus::Ptr &ss_ptr)
ros::Publisher odom_pub
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
double angular_pos_accel_limit
void connect(bool reset_integrators=true)
segwayrmp::SegwayRMP * segway_rmp
segway_rmp::SegwayStatusStamped sss_msg
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher segway_status_pub
double linear_neg_accel_limit
nav_msgs::Odometry odom_msg
ros::Timer keep_alive_timer
boost::mutex m_mutex
#define ROS_WARN(...)
void handleDebugMessages(const std::string &msg)
double linear_pos_accel_limit
std::string interface_type_str
void spinner()
void setStatusCallback(SegwayStatusCallback callback)
ControllerGainSchedule controller_gain_schedule
ros::Subscriber cmd_velSubscriber
double initial_integrated_right_wheel_position
void configureSerial(std::string port, int baudrate=460800)
geometry_msgs::TransformStamped odom_trans
std::string odom_frame_id
void move(float linear_velocity, float angular_velocity)
#define ROS_INFO(...)
void handleErrorMessages(const std::string &msg)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
void sendTransform(const StampedTransform &transform)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
void handleInfoMessages(const std::string &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double angular_neg_accel_limit
static SegwayRMPNode * segwayrmp_node_instance
void configureUSBByDescription(std::string description, int baudrate=460800)
segwayrmp::SegwayRMPType segway_rmp_type
double initial_integrated_forward_position
void configureUSBBySerial(std::string serial_number, int baudrate=460800)
std::string usb_description
std::string frame_id
TFSIMD_FORCE_INLINE const tfScalar & z() const
double initial_integrated_turn_position
static double degrees_to_radians
float last_forward_displacement
std::string usb_selector
void cmd_velCallback(const geometry_msgs::Twist::ConstPtr &msg)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
ros::Timer motor_timeout_timer
double initial_integrated_left_wheel_position
segwayrmp::InterfaceType interface_type
ros::Time odometry_reset_start_time
double odometry_reset_duration
OperationalMode operational_mode
static Time now()
std::string serial_port
static double radians_to_degrees
#define ROS_ERROR(...)
void motor_timeoutCallback(const ros::TimerEvent &e)
void keepAliveCallback(const ros::TimerEvent &e)
void handleStatusWrapper(segwayrmp::SegwayStatus::Ptr &ss)
#define ROS_DEBUG(...)


segway_rmp
Author(s): William Woodall
autogenerated on Mon Jun 10 2019 15:04:58