create_driver.cpp
Go to the documentation of this file.
1 
29 
31 
32 #include <string>
33 
35  : model_(create::RobotModel::CREATE_2),
36  nh_(nh),
37  priv_nh_("~"),
38  diagnostics_(),
39  is_running_slowly_(false)
40 {
41  std::string robot_model_name;
42  priv_nh_.param<std::string>("dev", dev_, "/dev/ttyUSB0");
43  priv_nh_.param<std::string>("robot_model", robot_model_name, "CREATE_2");
44  priv_nh_.param<std::string>("base_frame", base_frame_, "base_footprint");
45  priv_nh_.param<std::string>("odom_frame", odom_frame_, "odom");
46  priv_nh_.param<double>("latch_cmd_duration", latch_duration_, 0.2);
47  priv_nh_.param<double>("loop_hz", loop_hz_, 10.0);
48  priv_nh_.param<bool>("publish_tf", publish_tf_, true);
49 
50  if (robot_model_name == "ROOMBA_400")
51  {
53  }
54  else if (robot_model_name == "CREATE_1")
55  {
57  }
58  else if (robot_model_name == "CREATE_2")
59  {
61  }
62  else
63  {
64  ROS_FATAL_STREAM("[CREATE] Robot model \"" + robot_model_name + "\" is not known.");
65  ros::shutdown();
66  return;
67  }
68 
69  ROS_INFO_STREAM("[CREATE] \"" << robot_model_name << "\" selected");
70 
71  priv_nh_.param<int>("baud", baud_, model_.getBaud());
72 
74 
75  if (!robot_->connect(dev_, baud_))
76  {
77  ROS_FATAL("[CREATE] Failed to establish serial connection with Create.");
78  ros::shutdown();
79  }
80 
81  ROS_INFO("[CREATE] Connection established.");
82 
83  // Start in full control mode
84  robot_->setMode(create::MODE_FULL);
85 
86  // Show robot's battery level
87  ROS_INFO("[CREATE] Battery level %.2f %%", (robot_->getBatteryCharge() / robot_->getBatteryCapacity()) * 100.0);
88 
89  // Set frame_id's
90  mode_msg_.header.frame_id = base_frame_;
91  bumper_msg_.header.frame_id = base_frame_;
92  charging_state_msg_.header.frame_id = base_frame_;
93  tf_odom_.header.frame_id = odom_frame_;
94  tf_odom_.child_frame_id = base_frame_;
95  odom_msg_.header.frame_id = odom_frame_;
96  odom_msg_.child_frame_id = base_frame_;
97  joint_state_msg_.name.resize(2);
98  joint_state_msg_.position.resize(2);
99  joint_state_msg_.velocity.resize(2);
100  joint_state_msg_.effort.resize(2);
101  joint_state_msg_.name[0] = "left_wheel_joint";
102  joint_state_msg_.name[1] = "right_wheel_joint";
103 
104  // Populate intial covariances
105  for (int i = 0; i < 36; i++)
106  {
107  odom_msg_.pose.covariance[i] = COVARIANCE[i];
108  odom_msg_.twist.covariance[i] = COVARIANCE[i];
109  }
110 
111  // Setup subscribers
112  cmd_vel_sub_ = nh.subscribe("cmd_vel", 1, &CreateDriver::cmdVelCallback, this);
113  debris_led_sub_ = nh.subscribe("debris_led", 10, &CreateDriver::debrisLEDCallback, this);
114  spot_led_sub_ = nh.subscribe("spot_led", 10, &CreateDriver::spotLEDCallback, this);
115  dock_led_sub_ = nh.subscribe("dock_led", 10, &CreateDriver::dockLEDCallback, this);
116  check_led_sub_ = nh.subscribe("check_led", 10, &CreateDriver::checkLEDCallback, this);
117  power_led_sub_ = nh.subscribe("power_led", 10, &CreateDriver::powerLEDCallback, this);
118  set_ascii_sub_ = nh.subscribe("set_ascii", 10, &CreateDriver::setASCIICallback, this);
119  dock_sub_ = nh.subscribe("dock", 10, &CreateDriver::dockCallback, this);
120  undock_sub_ = nh.subscribe("undock", 10, &CreateDriver::undockCallback, this);
121  define_song_sub_ = nh.subscribe("define_song", 10, &CreateDriver::defineSongCallback, this);
122  play_song_sub_ = nh.subscribe("play_song", 10, &CreateDriver::playSongCallback, this);
123  side_brush_motor_sub_ = nh.subscribe("side_brush_motor", 10, &CreateDriver::sideBrushMotor, this);
124  main_brush_motor_sub_ = nh.subscribe("main_brush_motor", 10, &CreateDriver::mainBrushMotor, this);
125  vacuum_motor_sub_ = nh.subscribe("vacuum_motor", 10, &CreateDriver::vacuumBrushMotor, this);
126 
127  // Setup publishers
128  odom_pub_ = nh.advertise<nav_msgs::Odometry>("odom", 30);
129  clean_btn_pub_ = nh.advertise<std_msgs::Empty>("clean_button", 30);
130  day_btn_pub_ = nh.advertise<std_msgs::Empty>("day_button", 30);
131  hour_btn_pub_ = nh.advertise<std_msgs::Empty>("hour_button", 30);
132  min_btn_pub_ = nh.advertise<std_msgs::Empty>("minute_button", 30);
133  dock_btn_pub_ = nh.advertise<std_msgs::Empty>("dock_button", 30);
134  spot_btn_pub_ = nh.advertise<std_msgs::Empty>("spot_button", 30);
135  voltage_pub_ = nh.advertise<std_msgs::Float32>("battery/voltage", 30);
136  current_pub_ = nh.advertise<std_msgs::Float32>("battery/current", 30);
137  charge_pub_ = nh.advertise<std_msgs::Float32>("battery/charge", 30);
138  charge_ratio_pub_ = nh.advertise<std_msgs::Float32>("battery/charge_ratio", 30);
139  capacity_pub_ = nh.advertise<std_msgs::Float32>("battery/capacity", 30);
140  temperature_pub_ = nh.advertise<std_msgs::Int16>("battery/temperature", 30);
141  charging_state_pub_ = nh.advertise<create_msgs::ChargingState>("battery/charging_state", 30);
142  omni_char_pub_ = nh.advertise<std_msgs::UInt16>("ir_omni", 30);
143  mode_pub_ = nh.advertise<create_msgs::Mode>("mode", 30);
144  bumper_pub_ = nh.advertise<create_msgs::Bumper>("bumper", 30);
145  wheeldrop_pub_ = nh.advertise<std_msgs::Empty>("wheeldrop", 30);
146  wheel_joint_pub_ = nh.advertise<sensor_msgs::JointState>("joint_states", 10);
147 
148  // Setup diagnostics
149  diagnostics_.add("Battery Status", this, &CreateDriver::updateBatteryDiagnostics);
150  diagnostics_.add("Safety Status", this, &CreateDriver::updateSafetyDiagnostics);
151  diagnostics_.add("Serial Status", this, &CreateDriver::updateSerialDiagnostics);
153  diagnostics_.add("Driver Status", this, &CreateDriver::updateDriverDiagnostics);
154 
155  diagnostics_.setHardwareID(robot_model_name);
156 
157  ROS_INFO("[CREATE] Ready.");
158 }
159 
161 {
162  ROS_INFO("[CREATE] Destruct sequence initiated.");
163  robot_->disconnect();
164  delete robot_;
165 }
166 
167 void CreateDriver::cmdVelCallback(const geometry_msgs::TwistConstPtr& msg)
168 {
169  robot_->drive(msg->linear.x, msg->angular.z);
171 }
172 
173 void CreateDriver::debrisLEDCallback(const std_msgs::BoolConstPtr& msg)
174 {
175  robot_->enableDebrisLED(msg->data);
176 }
177 
178 void CreateDriver::spotLEDCallback(const std_msgs::BoolConstPtr& msg)
179 {
180  robot_->enableSpotLED(msg->data);
181 }
182 
183 void CreateDriver::dockLEDCallback(const std_msgs::BoolConstPtr& msg)
184 {
185  robot_->enableDockLED(msg->data);
186 }
187 
188 void CreateDriver::checkLEDCallback(const std_msgs::BoolConstPtr& msg)
189 {
190  robot_->enableCheckRobotLED(msg->data);
191 }
192 
193 void CreateDriver::powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr& msg)
194 {
195  if (msg->data.size() < 1)
196  {
197  ROS_ERROR("[CREATE] No values provided to set power LED");
198  }
199  else
200  {
201  if (msg->data.size() < 2)
202  {
203  robot_->setPowerLED(msg->data[0]);
204  }
205  else
206  {
207  robot_->setPowerLED(msg->data[0], msg->data[1]);
208  }
209  }
210 }
211 
212 void CreateDriver::setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr& msg)
213 {
214  bool result;
215  if (msg->data.size() < 1)
216  {
217  ROS_ERROR("[CREATE] No ASCII digits provided");
218  }
219  else if (msg->data.size() < 2)
220  {
221  result = robot_->setDigitsASCII(msg->data[0], ' ', ' ', ' ');
222  }
223  else if (msg->data.size() < 3)
224  {
225  result = robot_->setDigitsASCII(msg->data[0], msg->data[1], ' ', ' ');
226  }
227  else if (msg->data.size() < 4)
228  {
229  result = robot_->setDigitsASCII(msg->data[0], msg->data[1], msg->data[2], ' ');
230  }
231  else
232  {
233  result = robot_->setDigitsASCII(msg->data[0], msg->data[1], msg->data[2], msg->data[3]);
234  }
235 
236  if (!result)
237  {
238  ROS_ERROR("[CREATE] ASCII character out of range [32, 126]");
239  }
240 }
241 
242 void CreateDriver::dockCallback(const std_msgs::EmptyConstPtr& msg)
243 {
244  (void) msg;
245 
247 
248  if (model_.getVersion() <= create::V_2)
249  usleep(1000000); // Create 1 requires a delay (1 sec)
250 
251  // Call docking behaviour
252  robot_->dock();
253 }
254 
255 void CreateDriver::undockCallback(const std_msgs::EmptyConstPtr& msg)
256 {
257  (void) msg;
258 
259  // Switch robot back to FULL mode
261 }
262 
263 void CreateDriver::defineSongCallback(const create_msgs::DefineSongConstPtr& msg)
264 {
265  if (!robot_->defineSong(msg->song, msg->length, &(msg->notes.front()), &(msg->durations.front())))
266  {
267  ROS_ERROR_STREAM("[CREATE] Failed to define song " << msg->song << " of length " << msg->length);
268  }
269 }
270 
271 void CreateDriver::playSongCallback(const create_msgs::PlaySongConstPtr& msg)
272 {
273  if (!robot_->playSong(msg->song))
274  {
275  ROS_ERROR_STREAM("[CREATE] Failed to play song " << msg->song);
276  }
277 }
278 
279 void CreateDriver::sideBrushMotor(const create_msgs::MotorSetpointConstPtr& msg)
280 {
281  if (!robot_->setSideMotor(msg->duty_cycle))
282  {
283  ROS_ERROR_STREAM("[CREATE] Failed to set duty cycle " << msg->duty_cycle << " for side brush motor");
284  }
285 }
286 void CreateDriver::mainBrushMotor(const create_msgs::MotorSetpointConstPtr& msg)
287 {
288  if (!robot_->setMainMotor(msg->duty_cycle))
289  {
290  ROS_ERROR_STREAM("[CREATE] Failed to set duty cycle " << msg->duty_cycle << " for main motor");
291  }
292 }
293 void CreateDriver::vacuumBrushMotor(const create_msgs::MotorSetpointConstPtr& msg)
294 {
295  if (!robot_->setVacuumMotor(msg->duty_cycle))
296  {
297  ROS_ERROR_STREAM("[CREATE] Failed to set duty cycle " << msg->duty_cycle << " for vacuum motor");
298  }
299 }
300 
302 {
303  publishOdom();
307  publishOmniChar();
308  publishMode();
311 
312  // If last velocity command was sent longer than latch duration, stop robot
314  {
315  robot_->drive(0, 0);
316  }
317 
318  return true;
319 }
320 
322 {
323  const float charge = robot_->getBatteryCharge();
324  const float capacity = robot_->getBatteryCapacity();
325  const create::ChargingState charging_state = robot_->getChargingState();
326  const float charge_ratio = charge / capacity;
327 
328  if (charging_state == create::CHARGE_FAULT)
329  {
330  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Charging fault reported by base");
331  }
332  else if (charge_ratio == 0)
333  {
334  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Battery reports no charge");
335  }
336  else if (charge_ratio < 0.1)
337  {
338  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Battery reports less than 10% charge");
339  }
340  else
341  {
342  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Battery is OK");
343  }
344 
345  stat.add("Charge (Ah)", charge);
346  stat.add("Capacity (Ah)", capacity);
347  stat.add("Temperature (Celsius)", robot_->getTemperature());
348  stat.add("Current (A)", robot_->getCurrent());
349  stat.add("Voltage (V)", robot_->getVoltage());
350 
351  switch (charging_state)
352  {
353  case create::CHARGE_NONE:
354  stat.add("Charging state", "Not charging");
355  break;
357  stat.add("Charging state", "Reconditioning");
358  break;
359  case create::CHARGE_FULL:
360  stat.add("Charging state", "Full charge");
361  break;
363  stat.add("Charging state", "Trickle charging");
364  break;
366  stat.add("Charging state", "Waiting");
367  break;
369  stat.add("Charging state", "Fault");
370  break;
371  }
372 }
373 
375 {
376  const bool is_wheeldrop = robot_->isWheeldrop();
377  const bool is_cliff = robot_->isCliff();
378  if (is_wheeldrop)
379  {
380  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Wheeldrop detected");
381  }
382  else if (is_cliff)
383  {
384  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Cliff detected");
385  }
386  else
387  {
388  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No safety issues detected");
389  }
390 
391  stat.add("Wheeldrop", is_wheeldrop);
392  stat.add("Cliff", is_cliff);
393 }
394 
396 {
397  const bool is_connected = robot_->connected();
398  const uint64_t corrupt_packets = robot_->getNumCorruptPackets();
399  const uint64_t total_packets = robot_->getTotalPackets();
400 
401  if (!is_connected)
402  {
403  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Serial port to base not open");
404  }
405  else if (corrupt_packets)
406  {
407  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN,
408  "Corrupt packets detected. If the number of corrupt packets is increasing, data may be unreliable");
409  }
410  else
411  {
412  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Serial connection is good");
413  }
414 
415  stat.add("Corrupt packets", corrupt_packets);
416  stat.add("Total packets", total_packets);
417 }
418 
420 {
421  const create::CreateMode mode = robot_->getMode();
422  switch (mode)
423  {
425  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Unknown mode of operation");
426  break;
427  case create::MODE_OFF:
428  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Mode is set to OFF");
429  break;
431  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Mode is set to PASSIVE");
432  break;
433  case create::MODE_SAFE:
434  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Mode is set to SAFE");
435  break;
436  case create::MODE_FULL:
437  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Mode is set to FULL");
438  break;
439  }
440 }
441 
443 {
444  if (is_running_slowly_)
445  {
446  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Internal loop running slowly");
447  }
448  else
449  {
450  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Maintaining loop frequency");
451  }
452 }
453 
455 {
456  create::Pose pose = robot_->getPose();
457  create::Vel vel = robot_->getVel();
458 
459  // Populate position info
460  tf2::Quaternion tf_quat;
461  tf_quat.setRPY(0.0, 0.0, pose.yaw);
462  geometry_msgs::Quaternion quat = tf2::toMsg(tf_quat);
463  odom_msg_.header.stamp = ros::Time::now();
464  odom_msg_.pose.pose.position.x = pose.x;
465  odom_msg_.pose.pose.position.y = pose.y;
466  odom_msg_.pose.pose.orientation = quat;
467 
468  // Populate velocity info
469  odom_msg_.twist.twist.linear.x = vel.x;
470  odom_msg_.twist.twist.linear.y = vel.y;
471  odom_msg_.twist.twist.angular.z = vel.yaw;
472 
473  // Update covariances
474  odom_msg_.pose.covariance[0] = static_cast<double>(pose.covariance[0]);
475  odom_msg_.pose.covariance[1] = pose.covariance[1];
476  odom_msg_.pose.covariance[5] = pose.covariance[2];
477  odom_msg_.pose.covariance[6] = pose.covariance[3];
478  odom_msg_.pose.covariance[7] = pose.covariance[4];
479  odom_msg_.pose.covariance[11] = pose.covariance[5];
480  odom_msg_.pose.covariance[30] = pose.covariance[6];
481  odom_msg_.pose.covariance[31] = pose.covariance[7];
482  odom_msg_.pose.covariance[35] = pose.covariance[8];
483  odom_msg_.twist.covariance[0] = vel.covariance[0];
484  odom_msg_.twist.covariance[1] = vel.covariance[1];
485  odom_msg_.twist.covariance[5] = vel.covariance[2];
486  odom_msg_.twist.covariance[6] = vel.covariance[3];
487  odom_msg_.twist.covariance[7] = vel.covariance[4];
488  odom_msg_.twist.covariance[11] = vel.covariance[5];
489  odom_msg_.twist.covariance[30] = vel.covariance[6];
490  odom_msg_.twist.covariance[31] = vel.covariance[7];
491  odom_msg_.twist.covariance[35] = vel.covariance[8];
492 
493  if (publish_tf_)
494  {
495  tf_odom_.header.stamp = ros::Time::now();
496  tf_odom_.transform.translation.x = pose.x;
497  tf_odom_.transform.translation.y = pose.y;
498  tf_odom_.transform.rotation = quat;
500  }
501 
503 }
504 
506 {
507  // Publish joint states
508  float wheelRadius = model_.getWheelDiameter() / 2.0;
509 
510  joint_state_msg_.header.stamp = ros::Time::now();
511  joint_state_msg_.position[0] = robot_->getLeftWheelDistance() / wheelRadius;
512  joint_state_msg_.position[1] = robot_->getRightWheelDistance() / wheelRadius;
513  joint_state_msg_.velocity[0] = robot_->getRequestedLeftWheelVel() / wheelRadius;
514  joint_state_msg_.velocity[1] = robot_->getRequestedRightWheelVel() / wheelRadius;
516 }
517 
519 {
520  float32_msg_.data = robot_->getVoltage();
522  float32_msg_.data = robot_->getCurrent();
528  int16_msg_.data = robot_->getTemperature();
532 
533  const create::ChargingState charging_state = robot_->getChargingState();
534  charging_state_msg_.header.stamp = ros::Time::now();
535  switch (charging_state)
536  {
537  case create::CHARGE_NONE:
538  charging_state_msg_.state = charging_state_msg_.CHARGE_NONE;
539  break;
541  charging_state_msg_.state = charging_state_msg_.CHARGE_RECONDITION;
542  break;
543 
544  case create::CHARGE_FULL:
545  charging_state_msg_.state = charging_state_msg_.CHARGE_FULL;
546  break;
547 
549  charging_state_msg_.state = charging_state_msg_.CHARGE_TRICKLE;
550  break;
551 
553  charging_state_msg_.state = charging_state_msg_.CHARGE_WAITING;
554  break;
555 
557  charging_state_msg_.state = charging_state_msg_.CHARGE_FAULT;
558  break;
559  }
561 }
562 
564 {
566  {
568  }
569  if (robot_->isDayButtonPressed())
570  {
572  }
574  {
576  }
577  if (robot_->isMinButtonPressed())
578  {
580  }
582  {
584  }
586  {
588  }
589 }
590 
592 {
593  uint8_t ir_char = robot_->getIROmni();
594  uint16_msg_.data = ir_char;
596  // TODO(jacobperron): Publish info based on character, such as dock in sight
597 }
598 
600 {
601  const create::CreateMode mode = robot_->getMode();
602  mode_msg_.header.stamp = ros::Time::now();
603  switch (mode)
604  {
605  case create::MODE_OFF:
606  mode_msg_.mode = mode_msg_.MODE_OFF;
607  break;
609  mode_msg_.mode = mode_msg_.MODE_PASSIVE;
610  break;
611  case create::MODE_SAFE:
612  mode_msg_.mode = mode_msg_.MODE_SAFE;
613  break;
614  case create::MODE_FULL:
615  mode_msg_.mode = mode_msg_.MODE_FULL;
616  break;
617  default:
618  ROS_ERROR("[CREATE] Unknown mode detected");
619  break;
620  }
622 }
623 
625 {
626  bumper_msg_.header.stamp = ros::Time::now();
627  bumper_msg_.is_left_pressed = robot_->isLeftBumper();
628  bumper_msg_.is_right_pressed = robot_->isRightBumper();
629 
630  if (model_.getVersion() >= create::V_3)
631  {
632  bumper_msg_.is_light_left = robot_->isLightBumperLeft();
633  bumper_msg_.is_light_front_left = robot_->isLightBumperFrontLeft();
634  bumper_msg_.is_light_center_left = robot_->isLightBumperCenterLeft();
635  bumper_msg_.is_light_right = robot_->isLightBumperRight();
636  bumper_msg_.is_light_front_right = robot_->isLightBumperFrontRight();
637  bumper_msg_.is_light_center_right = robot_->isLightBumperCenterRight();
638 
639  bumper_msg_.light_signal_left = robot_->getLightSignalLeft();
640  bumper_msg_.light_signal_front_left = robot_->getLightSignalFrontLeft();
641  bumper_msg_.light_signal_center_left = robot_->getLightSignalCenterLeft();
642  bumper_msg_.light_signal_right = robot_->getLightSignalRight();
643  bumper_msg_.light_signal_front_right = robot_->getLightSignalFrontRight();
644  bumper_msg_.light_signal_center_right = robot_->getLightSignalCenterRight();
645  }
646 
648 }
649 
651 {
652  if (robot_->isWheeldrop())
654 }
655 
657 {
658  update();
660  ros::spinOnce();
661 }
662 
664 {
665  ros::Rate rate(loop_hz_);
666  while (ros::ok())
667  {
668  spinOnce();
669 
670  is_running_slowly_ = !rate.sleep();
671  if (is_running_slowly_)
672  {
673  ROS_WARN("[CREATE] Loop running slowly.");
674  }
675  }
676 }
677 
678 int main(int argc, char** argv)
679 {
680  ros::init(argc, argv, "create_driver");
681  ros::NodeHandle nh;
682 
683  CreateDriver create_driver(nh);
684 
685  try
686  {
687  create_driver.spin();
688  }
689  catch (std::runtime_error& ex)
690  {
691  ROS_FATAL_STREAM("[CREATE] Runtime error: " << ex.what());
692  return 1;
693  }
694  return 0;
695 }
bool isDockButtonPressed() const
void mainBrushMotor(const create_msgs::MotorSetpointConstPtr &msg)
void updateDriverDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
virtual void spinOnce()
bool setSideMotor(const float &power)
create_msgs::Bumper bumper_msg_
bool isLightBumperLeft() const
bool isSpotButtonPressed() const
uint16_t getLightSignalLeft() const
std::string odom_frame_
void debrisLEDCallback(const std_msgs::BoolConstPtr &msg)
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
ros::Subscriber define_song_sub_
Definition: create_driver.h:80
uint16_t getLightSignalCenterRight() const
ProtocolVersion getVersion() const
ros::Subscriber power_led_sub_
Definition: create_driver.h:76
#define ROS_FATAL(...)
ros::Subscriber set_ascii_sub_
Definition: create_driver.h:77
ros::Time last_cmd_vel_time_
create_msgs::Mode mode_msg_
void checkLEDCallback(const std_msgs::BoolConstPtr &msg)
void publishBumperInfo()
ros::Subscriber dock_led_sub_
Definition: create_driver.h:74
ros::Subscriber spot_led_sub_
Definition: create_driver.h:73
bool setVacuumMotor(const float &power)
ros::Publisher wheel_joint_pub_
void updateSafetyDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Publisher voltage_pub_
Definition: create_driver.h:93
void summary(unsigned char lvl, const std::string s)
ros::Publisher charging_state_pub_
Definition: create_driver.h:99
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void updateBatteryDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
bool is_running_slowly_
float getWheelDiameter() const
static RobotModel CREATE_1
void publishJointState()
ros::Publisher omni_char_pub_
void setHardwareID(const std::string &hwid)
uint16_t getLightSignalRight() const
bool isHourButtonPressed() const
ros::Publisher min_btn_pub_
Definition: create_driver.h:90
void publishButtonPresses() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
float getVoltage() const
ros::Publisher bumper_pub_
void add(const std::string &name, TaskFunction f)
bool dock() const
bool setDigitsASCII(const uint8_t &digit1, const uint8_t &digit2, const uint8_t &digit3, const uint8_t &digit4) const
ros::Subscriber check_led_sub_
Definition: create_driver.h:75
float getBatteryCapacity() const
std_msgs::Float32 float32_msg_
diagnostic_updater::Updater diagnostics_
CreateDriver(ros::NodeHandle &nh)
std_msgs::UInt16 uint16_msg_
ros::Publisher temperature_pub_
Definition: create_driver.h:98
ros::Subscriber debris_led_sub_
Definition: create_driver.h:72
void publishWheeldrop()
#define ROS_WARN(...)
void dockCallback(const std_msgs::EmptyConstPtr &msg)
bool isCleanButtonPressed() const
bool isLightBumperCenterRight() const
ros::Subscriber side_brush_motor_sub_
Definition: create_driver.h:82
ros::Publisher clean_btn_pub_
Definition: create_driver.h:87
ros::Publisher odom_pub_
Definition: create_driver.h:86
void playSongCallback(const create_msgs::PlaySongConstPtr &msg)
bool isLeftBumper() const
ros::Subscriber play_song_sub_
Definition: create_driver.h:81
ros::Subscriber main_brush_motor_sub_
Definition: create_driver.h:83
bool enableDockLED(const bool &enable)
bool setPowerLED(const uint8_t &power, const uint8_t &intensity=255)
unsigned int getBaud() const
ros::Publisher day_btn_pub_
Definition: create_driver.h:88
void cmdVelCallback(const geometry_msgs::TwistConstPtr &msg)
ros::Publisher charge_ratio_pub_
Definition: create_driver.h:96
nav_msgs::Odometry odom_msg_
void setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
uint16_t getLightSignalFrontRight() const
void publish(const boost::shared_ptr< M > &message) const
MODE_UNAVAILABLE
void updateSerialDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
double latch_duration_
virtual void spin()
ros::Subscriber vacuum_motor_sub_
Definition: create_driver.h:84
ros::Publisher dock_btn_pub_
Definition: create_driver.h:91
std::vector< float > covariance
#define ROS_FATAL_STREAM(args)
std_msgs::Int16 int16_msg_
ros::Subscriber cmd_vel_sub_
Definition: create_driver.h:71
#define ROS_INFO(...)
void spotLEDCallback(const std_msgs::BoolConstPtr &msg)
float getRequestedRightWheelVel() const
void publishOmniChar()
uint16_t getLightSignalCenterLeft() const
float getLeftWheelDistance() const
void updateModeDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
bool connected() const
bool enableCheckRobotLED(const bool &enable)
ROSCPP_DECL bool ok()
bool enableSpotLED(const bool &enable)
void powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
void publishBatteryInfo()
bool setMainMotor(const float &power)
uint64_t getNumCorruptPackets() const
float getCurrent() const
static const double COVARIANCE[36]
Definition: create_driver.h:55
bool drive(const float &xVel, const float &angularVel)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher hour_btn_pub_
Definition: create_driver.h:89
create_msgs::ChargingState charging_state_msg_
uint8_t getIROmni() const
bool isLightBumperFrontRight() const
bool enableDebrisLED(const bool &enable)
ros::Subscriber dock_sub_
Definition: create_driver.h:78
void sendTransform(const geometry_msgs::TransformStamped &transform)
void sideBrushMotor(const create_msgs::MotorSetpointConstPtr &msg)
std::string base_frame_
uint64_t getTotalPackets() const
bool sleep()
ros::Publisher capacity_pub_
Definition: create_driver.h:97
bool isCliff() const
B toMsg(const A &a)
ros::Publisher wheeldrop_pub_
create::ChargingState getChargingState() const
bool isRightBumper() const
std::string dev_
float getRightWheelDistance() const
ros::Publisher charge_pub_
Definition: create_driver.h:95
bool isLightBumperRight() const
#define ROS_INFO_STREAM(args)
tf2_ros::TransformBroadcaster tf_broadcaster_
std_msgs::Empty empty_msg_
bool isMinButtonPressed() const
int8_t getTemperature() const
bool defineSong(const uint8_t &songNumber, const uint8_t &songLength, const uint8_t *notes, const float *durations) const
void undockCallback(const std_msgs::EmptyConstPtr &msg)
bool playSong(const uint8_t &songNumber) const
void dockLEDCallback(const std_msgs::BoolConstPtr &msg)
static Time now()
ros::NodeHandle priv_nh_
Definition: create_driver.h:69
create::Create * robot_
Definition: create_driver.h:65
ROSCPP_DECL void shutdown()
ros::Publisher mode_pub_
CHARGE_RECONDITION
static RobotModel CREATE_2
ros::Subscriber undock_sub_
Definition: create_driver.h:79
void add(const std::string &key, const T &val)
bool isLightBumperFrontLeft() const
create::RobotModel model_
Definition: create_driver.h:66
#define ROS_ERROR_STREAM(args)
ros::Publisher current_pub_
Definition: create_driver.h:94
void defineSongCallback(const create_msgs::DefineSongConstPtr &msg)
bool isLightBumperCenterLeft() const
ROSCPP_DECL void spinOnce()
ros::Publisher spot_btn_pub_
Definition: create_driver.h:92
static RobotModel ROOMBA_400
#define ROS_ERROR(...)
geometry_msgs::TransformStamped tf_odom_
void vacuumBrushMotor(const create_msgs::MotorSetpointConstPtr &msg)
uint16_t getLightSignalFrontLeft() const
create::Vel getVel() const
create::Pose getPose() const
bool setMode(const create::CreateMode &mode)
create::CreateMode getMode()
float getBatteryCharge() const
float getRequestedLeftWheelVel() const
sensor_msgs::JointState joint_state_msg_
bool isWheeldrop() const
bool isDayButtonPressed() const


create_driver
Author(s): Jacob Perron
autogenerated on Mon May 22 2023 02:31:38