create_driver.cpp
Go to the documentation of this file.
00001 
00028 #include "create_driver/create_driver.h"
00029 
00030 #include <tf/transform_datatypes.h>
00031 
00032 #include <string>
00033 
00034 CreateDriver::CreateDriver(ros::NodeHandle& nh)
00035   : nh_(nh),
00036     priv_nh_("~"),
00037     diagnostics_(),
00038     model_(create::RobotModel::CREATE_2),
00039     is_running_slowly_(false)
00040 {
00041   bool create_one;
00042   std::string robot_model_name;
00043   priv_nh_.param<std::string>("dev", dev_, "/dev/ttyUSB0");
00044   priv_nh_.param<std::string>("robot_model", robot_model_name, "CREATE_2");
00045   priv_nh_.param<std::string>("base_frame", base_frame_, "base_footprint");
00046   priv_nh_.param<std::string>("odom_frame", odom_frame_, "odom");
00047   priv_nh_.param<double>("latch_cmd_duration", latch_duration_, 0.2);
00048   priv_nh_.param<double>("loop_hz", loop_hz_, 10.0);
00049   priv_nh_.param<bool>("publish_tf", publish_tf_, true);
00050 
00051   if (robot_model_name == "ROOMBA_400")
00052   {
00053     model_ = create::RobotModel::ROOMBA_400;
00054   }
00055   else if (robot_model_name == "CREATE_1")
00056   {
00057     model_ = create::RobotModel::CREATE_1;
00058   }
00059   else if (robot_model_name == "CREATE_2")
00060   {
00061     model_ = create::RobotModel::CREATE_2;
00062   }
00063   else
00064   {
00065     ROS_FATAL_STREAM("[CREATE] Robot model \"" + robot_model_name + "\" is not known.");
00066     ros::shutdown();
00067     return;
00068   }
00069 
00070   ROS_INFO_STREAM("[CREATE] \"" << robot_model_name << "\" selected");
00071 
00072   priv_nh_.param<int>("baud", baud_, model_.getBaud());
00073 
00074   robot_ = new create::Create(model_);
00075 
00076   if (!robot_->connect(dev_, baud_))
00077   {
00078     ROS_FATAL("[CREATE] Failed to establish serial connection with Create.");
00079     ros::shutdown();
00080   }
00081 
00082   ROS_INFO("[CREATE] Connection established.");
00083 
00084   // Start in full control mode
00085   robot_->setMode(create::MODE_FULL);
00086 
00087   // Show robot's battery level
00088   ROS_INFO("[CREATE] Battery level %.2f %%", (robot_->getBatteryCharge() / robot_->getBatteryCapacity()) * 100.0);
00089 
00090   // Set frame_id's
00091   mode_msg_.header.frame_id = base_frame_;
00092   bumper_msg_.header.frame_id = base_frame_;
00093   charging_state_msg_.header.frame_id = base_frame_;
00094   tf_odom_.header.frame_id = odom_frame_;
00095   tf_odom_.child_frame_id = base_frame_;
00096   odom_msg_.header.frame_id = odom_frame_;
00097   odom_msg_.child_frame_id = base_frame_;
00098   joint_state_msg_.name.resize(2);
00099   joint_state_msg_.position.resize(2);
00100   joint_state_msg_.velocity.resize(2);
00101   joint_state_msg_.effort.resize(2);
00102   joint_state_msg_.name[0] = "left_wheel_joint";
00103   joint_state_msg_.name[1] = "right_wheel_joint";
00104 
00105   // Populate intial covariances
00106   for (int i = 0; i < 36; i++)
00107   {
00108     odom_msg_.pose.covariance[i] = COVARIANCE[i];
00109     odom_msg_.twist.covariance[i] = COVARIANCE[i];
00110   }
00111 
00112   // Setup subscribers
00113   cmd_vel_sub_ = nh.subscribe("cmd_vel", 1, &CreateDriver::cmdVelCallback, this);
00114   debris_led_sub_ = nh.subscribe("debris_led", 10, &CreateDriver::debrisLEDCallback, this);
00115   spot_led_sub_ = nh.subscribe("spot_led", 10, &CreateDriver::spotLEDCallback, this);
00116   dock_led_sub_ = nh.subscribe("dock_led", 10, &CreateDriver::dockLEDCallback, this);
00117   check_led_sub_ = nh.subscribe("check_led", 10, &CreateDriver::checkLEDCallback, this);
00118   power_led_sub_ = nh.subscribe("power_led", 10, &CreateDriver::powerLEDCallback, this);
00119   set_ascii_sub_ = nh.subscribe("set_ascii", 10, &CreateDriver::setASCIICallback, this);
00120   dock_sub_ = nh.subscribe("dock", 10, &CreateDriver::dockCallback, this);
00121   undock_sub_ = nh.subscribe("undock", 10, &CreateDriver::undockCallback, this);
00122   define_song_sub_ = nh.subscribe("define_song", 10, &CreateDriver::defineSongCallback, this);
00123   play_song_sub_ = nh.subscribe("play_song", 10, &CreateDriver::playSongCallback, this);
00124 
00125   // Setup publishers
00126   odom_pub_ = nh.advertise<nav_msgs::Odometry>("odom", 30);
00127   clean_btn_pub_ = nh.advertise<std_msgs::Empty>("clean_button", 30);
00128   day_btn_pub_ = nh.advertise<std_msgs::Empty>("day_button", 30);
00129   hour_btn_pub_ = nh.advertise<std_msgs::Empty>("hour_button", 30);
00130   min_btn_pub_ = nh.advertise<std_msgs::Empty>("minute_button", 30);
00131   dock_btn_pub_ = nh.advertise<std_msgs::Empty>("dock_button", 30);
00132   spot_btn_pub_ = nh.advertise<std_msgs::Empty>("spot_button", 30);
00133   voltage_pub_ = nh.advertise<std_msgs::Float32>("battery/voltage", 30);
00134   current_pub_ = nh.advertise<std_msgs::Float32>("battery/current", 30);
00135   charge_pub_ = nh.advertise<std_msgs::Float32>("battery/charge", 30);
00136   charge_ratio_pub_ = nh.advertise<std_msgs::Float32>("battery/charge_ratio", 30);
00137   capacity_pub_ = nh.advertise<std_msgs::Float32>("battery/capacity", 30);
00138   temperature_pub_ = nh.advertise<std_msgs::Int16>("battery/temperature", 30);
00139   charging_state_pub_ = nh.advertise<ca_msgs::ChargingState>("battery/charging_state", 30);
00140   omni_char_pub_ = nh.advertise<std_msgs::UInt16>("ir_omni", 30);
00141   mode_pub_ = nh.advertise<ca_msgs::Mode>("mode", 30);
00142   bumper_pub_ = nh.advertise<ca_msgs::Bumper>("bumper", 30);
00143   wheeldrop_pub_ = nh.advertise<std_msgs::Empty>("wheeldrop", 30);
00144   wheel_joint_pub_ = nh.advertise<sensor_msgs::JointState>("joint_states", 10);
00145 
00146   // Setup diagnostics
00147   diagnostics_.add("Battery Status", this, &CreateDriver::updateBatteryDiagnostics);
00148   diagnostics_.add("Safety Status", this, &CreateDriver::updateSafetyDiagnostics);
00149   diagnostics_.add("Serial Status", this, &CreateDriver::updateSerialDiagnostics);
00150   diagnostics_.add("Base Mode", this, &CreateDriver::updateModeDiagnostics);
00151   diagnostics_.add("Driver Status", this, &CreateDriver::updateDriverDiagnostics);
00152 
00153   diagnostics_.setHardwareID(robot_model_name);
00154 
00155   ROS_INFO("[CREATE] Ready.");
00156 }
00157 
00158 CreateDriver::~CreateDriver()
00159 {
00160   ROS_INFO("[CREATE] Destruct sequence initiated.");
00161   robot_->disconnect();
00162   delete robot_;
00163 }
00164 
00165 void CreateDriver::cmdVelCallback(const geometry_msgs::TwistConstPtr& msg)
00166 {
00167   robot_->drive(msg->linear.x, msg->angular.z);
00168   last_cmd_vel_time_ = ros::Time::now();
00169 }
00170 
00171 void CreateDriver::debrisLEDCallback(const std_msgs::BoolConstPtr& msg)
00172 {
00173   robot_->enableDebrisLED(msg->data);
00174 }
00175 
00176 void CreateDriver::spotLEDCallback(const std_msgs::BoolConstPtr& msg)
00177 {
00178   robot_->enableSpotLED(msg->data);
00179 }
00180 
00181 void CreateDriver::dockLEDCallback(const std_msgs::BoolConstPtr& msg)
00182 {
00183   robot_->enableDockLED(msg->data);
00184 }
00185 
00186 void CreateDriver::checkLEDCallback(const std_msgs::BoolConstPtr& msg)
00187 {
00188   robot_->enableCheckRobotLED(msg->data);
00189 }
00190 
00191 void CreateDriver::powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr& msg)
00192 {
00193   if (msg->data.size() < 1)
00194   {
00195     ROS_ERROR("[CREATE] No values provided to set power LED");
00196   }
00197   else
00198   {
00199     if (msg->data.size() < 2)
00200     {
00201       robot_->setPowerLED(msg->data[0]);
00202     }
00203     else
00204     {
00205       robot_->setPowerLED(msg->data[0], msg->data[1]);
00206     }
00207   }
00208 }
00209 
00210 void CreateDriver::setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr& msg)
00211 {
00212   bool result;
00213   if (msg->data.size() < 1)
00214   {
00215     ROS_ERROR("[CREATE] No ASCII digits provided");
00216   }
00217   else if (msg->data.size() < 2)
00218   {
00219     result = robot_->setDigitsASCII(msg->data[0], ' ', ' ', ' ');
00220   }
00221   else if (msg->data.size() < 3)
00222   {
00223     result = robot_->setDigitsASCII(msg->data[0], msg->data[1], ' ', ' ');
00224   }
00225   else if (msg->data.size() < 4)
00226   {
00227     result = robot_->setDigitsASCII(msg->data[0], msg->data[1], msg->data[2], ' ');
00228   }
00229   else
00230   {
00231     result = robot_->setDigitsASCII(msg->data[0], msg->data[1], msg->data[2], msg->data[3]);
00232   }
00233 
00234   if (!result)
00235   {
00236     ROS_ERROR("[CREATE] ASCII character out of range [32, 126]");
00237   }
00238 }
00239 
00240 void CreateDriver::dockCallback(const std_msgs::EmptyConstPtr& msg)
00241 {
00242   robot_->setMode(create::MODE_PASSIVE);
00243 
00244   if (model_.getVersion() <= create::V_2)
00245     usleep(1000000);  // Create 1 requires a delay (1 sec)
00246 
00247   // Call docking behaviour
00248   robot_->dock();
00249 }
00250 
00251 void CreateDriver::undockCallback(const std_msgs::EmptyConstPtr& msg)
00252 {
00253   // Switch robot back to FULL mode
00254   robot_->setMode(create::MODE_FULL);
00255 }
00256 
00257 void CreateDriver::defineSongCallback(const ca_msgs::DefineSongConstPtr& msg)
00258 {
00259   if (!robot_->defineSong(msg->song, msg->length, &(msg->notes.front()), &(msg->durations.front())))
00260   {
00261     ROS_ERROR_STREAM("[CREATE] Failed to define song " << msg->song << " of length " << msg->length);
00262   }
00263 }
00264 
00265 void CreateDriver::playSongCallback(const ca_msgs::PlaySongConstPtr& msg)
00266 {
00267   if (!robot_->playSong(msg->song))
00268   {
00269     ROS_ERROR_STREAM("[CREATE] Failed to play song " << msg->song);
00270   }
00271 }
00272 
00273 bool CreateDriver::update()
00274 {
00275   publishOdom();
00276   publishJointState();
00277   publishBatteryInfo();
00278   publishButtonPresses();
00279   publishOmniChar();
00280   publishMode();
00281   publishBumperInfo();
00282   publishWheeldrop();
00283 
00284   // If last velocity command was sent longer than latch duration, stop robot
00285   if (ros::Time::now() - last_cmd_vel_time_ >= ros::Duration(latch_duration_))
00286   {
00287     robot_->drive(0, 0);
00288   }
00289 
00290   return true;
00291 }
00292 
00293 void CreateDriver::updateBatteryDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00294 {
00295   const float charge = robot_->getBatteryCharge();
00296   const float capacity = robot_->getBatteryCapacity();
00297   const create::ChargingState charging_state = robot_->getChargingState();
00298   const float charge_ratio = charge / capacity;
00299 
00300   if (charging_state == create::CHARGE_FAULT)
00301   {
00302     stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Charging fault reported by base");
00303   }
00304   else if (charge_ratio == 0)
00305   {
00306     stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Battery reports no charge");
00307   }
00308   else if (charge_ratio < 0.1)
00309   {
00310     stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Battery reports less than 10% charge");
00311   }
00312   else
00313   {
00314     stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Battery is OK");
00315   }
00316 
00317   stat.add("Charge (Ah)", charge);
00318   stat.add("Capacity (Ah)", capacity);
00319   stat.add("Temperature (Celsius)", robot_->getTemperature());
00320   stat.add("Current (A)", robot_->getCurrent());
00321   stat.add("Voltage (V)", robot_->getVoltage());
00322 
00323   switch (charging_state)
00324   {
00325     case create::CHARGE_NONE:
00326       stat.add("Charging state", "Not charging");
00327       break;
00328     case create::CHARGE_RECONDITION:
00329       stat.add("Charging state", "Reconditioning");
00330       break;
00331     case create::CHARGE_FULL:
00332       stat.add("Charging state", "Full charge");
00333       break;
00334     case create::CHARGE_TRICKLE:
00335       stat.add("Charging state", "Trickle charging");
00336       break;
00337     case create::CHARGE_WAITING:
00338       stat.add("Charging state", "Waiting");
00339       break;
00340     case create::CHARGE_FAULT:
00341       stat.add("Charging state", "Fault");
00342       break;
00343   }
00344 }
00345 
00346 void CreateDriver::updateSafetyDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00347 {
00348   const bool is_wheeldrop = robot_->isWheeldrop();
00349   const bool is_cliff = robot_->isCliff();
00350   if (is_wheeldrop)
00351   {
00352     stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Wheeldrop detected");
00353   }
00354   else if (is_cliff)
00355   {
00356     stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Cliff detected");
00357   }
00358   else
00359   {
00360     stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "No safety issues detected");
00361   }
00362 
00363   stat.add("Wheeldrop", is_wheeldrop);
00364   stat.add("Cliff", is_cliff);
00365 }
00366 
00367 void CreateDriver::updateSerialDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00368 {
00369   const bool is_connected = robot_->connected();
00370   const uint64_t corrupt_packets = robot_->getNumCorruptPackets();
00371   const uint64_t total_packets = robot_->getTotalPackets();
00372 
00373   if (!is_connected)
00374   {
00375     stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Serial port to base not open");
00376   }
00377   else if (corrupt_packets)
00378   {
00379     stat.summary(diagnostic_msgs::DiagnosticStatus::WARN,
00380                  "Corrupt packets detected. If the number of corrupt packets is increasing, data may be unreliable");
00381   }
00382   else
00383   {
00384     stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Serial connection is good");
00385   }
00386 
00387   stat.add("Corrupt packets", corrupt_packets);
00388   stat.add("Total packets", total_packets);
00389 }
00390 
00391 void CreateDriver::updateModeDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00392 {
00393   const create::CreateMode mode = robot_->getMode();
00394   switch (mode)
00395   {
00396     case create::MODE_UNAVAILABLE:
00397       stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Unknown mode of operation");
00398       break;
00399     case create::MODE_OFF:
00400       stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Mode is set to OFF");
00401       break;
00402     case create::MODE_PASSIVE:
00403       stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Mode is set to PASSIVE");
00404       break;
00405     case create::MODE_SAFE:
00406       stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Mode is set to SAFE");
00407       break;
00408     case create::MODE_FULL:
00409       stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Mode is set to FULL");
00410       break;
00411   }
00412 }
00413 
00414 void CreateDriver::updateDriverDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat)
00415 {
00416   if (is_running_slowly_)
00417   {
00418     stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Internal loop running slowly");
00419   }
00420   else
00421   {
00422     stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Maintaining loop frequency");
00423   }
00424 }
00425 
00426 void CreateDriver::publishOdom()
00427 {
00428   create::Pose pose = robot_->getPose();
00429   create::Vel vel = robot_->getVel();
00430 
00431   // Populate position info
00432   geometry_msgs::Quaternion quat = tf::createQuaternionMsgFromRollPitchYaw(0, 0, pose.yaw);
00433   odom_msg_.header.stamp = ros::Time::now();
00434   odom_msg_.pose.pose.position.x = pose.x;
00435   odom_msg_.pose.pose.position.y = pose.y;
00436   odom_msg_.pose.pose.orientation = quat;
00437 
00438   // Populate velocity info
00439   odom_msg_.twist.twist.linear.x = vel.x;
00440   odom_msg_.twist.twist.linear.y = vel.y;
00441   odom_msg_.twist.twist.angular.z = vel.yaw;
00442 
00443   // Update covariances
00444   odom_msg_.pose.covariance[0] = static_cast<double>(pose.covariance[0]);
00445   odom_msg_.pose.covariance[1] = pose.covariance[1];
00446   odom_msg_.pose.covariance[5] = pose.covariance[2];
00447   odom_msg_.pose.covariance[6] = pose.covariance[3];
00448   odom_msg_.pose.covariance[7] = pose.covariance[4];
00449   odom_msg_.pose.covariance[11] = pose.covariance[5];
00450   odom_msg_.pose.covariance[30] = pose.covariance[6];
00451   odom_msg_.pose.covariance[31] = pose.covariance[7];
00452   odom_msg_.pose.covariance[35] = pose.covariance[8];
00453   odom_msg_.twist.covariance[0] = vel.covariance[0];
00454   odom_msg_.twist.covariance[1] = vel.covariance[1];
00455   odom_msg_.twist.covariance[5] = vel.covariance[2];
00456   odom_msg_.twist.covariance[6] = vel.covariance[3];
00457   odom_msg_.twist.covariance[7] = vel.covariance[4];
00458   odom_msg_.twist.covariance[11] = vel.covariance[5];
00459   odom_msg_.twist.covariance[30] = vel.covariance[6];
00460   odom_msg_.twist.covariance[31] = vel.covariance[7];
00461   odom_msg_.twist.covariance[35] = vel.covariance[8];
00462 
00463   if (publish_tf_)
00464   {
00465     tf_odom_.header.stamp = ros::Time::now();
00466     tf_odom_.transform.translation.x = pose.x;
00467     tf_odom_.transform.translation.y = pose.y;
00468     tf_odom_.transform.rotation = quat;
00469     tf_broadcaster_.sendTransform(tf_odom_);
00470   }
00471 
00472   odom_pub_.publish(odom_msg_);
00473 }
00474 
00475 void CreateDriver::publishJointState()
00476 {
00477   // Publish joint states
00478   float wheelRadius = model_.getWheelDiameter() / 2.0;
00479 
00480   joint_state_msg_.header.stamp = ros::Time::now();
00481   joint_state_msg_.position[0] = robot_->getLeftWheelDistance() / wheelRadius;
00482   joint_state_msg_.position[1] = robot_->getRightWheelDistance() / wheelRadius;
00483   joint_state_msg_.velocity[0] = robot_->getRequestedLeftWheelVel() / wheelRadius;
00484   joint_state_msg_.velocity[1] = robot_->getRequestedRightWheelVel() / wheelRadius;
00485   wheel_joint_pub_.publish(joint_state_msg_);
00486 }
00487 
00488 void CreateDriver::publishBatteryInfo()
00489 {
00490   float32_msg_.data = robot_->getVoltage();
00491   voltage_pub_.publish(float32_msg_);
00492   float32_msg_.data = robot_->getCurrent();
00493   current_pub_.publish(float32_msg_);
00494   float32_msg_.data = robot_->getBatteryCharge();
00495   charge_pub_.publish(float32_msg_);
00496   float32_msg_.data = robot_->getBatteryCapacity();
00497   capacity_pub_.publish(float32_msg_);
00498   int16_msg_.data = robot_->getTemperature();
00499   temperature_pub_.publish(int16_msg_);
00500   float32_msg_.data = robot_->getBatteryCharge() / robot_->getBatteryCapacity();
00501   charge_ratio_pub_.publish(float32_msg_);
00502 
00503   const create::ChargingState charging_state = robot_->getChargingState();
00504   charging_state_msg_.header.stamp = ros::Time::now();
00505   switch (charging_state)
00506   {
00507     case create::CHARGE_NONE:
00508       charging_state_msg_.state = charging_state_msg_.CHARGE_NONE;
00509       break;
00510     case create::CHARGE_RECONDITION:
00511       charging_state_msg_.state = charging_state_msg_.CHARGE_RECONDITION;
00512       break;
00513 
00514     case create::CHARGE_FULL:
00515       charging_state_msg_.state = charging_state_msg_.CHARGE_FULL;
00516       break;
00517 
00518     case create::CHARGE_TRICKLE:
00519       charging_state_msg_.state = charging_state_msg_.CHARGE_TRICKLE;
00520       break;
00521 
00522     case create::CHARGE_WAITING:
00523       charging_state_msg_.state = charging_state_msg_.CHARGE_WAITING;
00524       break;
00525 
00526     case create::CHARGE_FAULT:
00527       charging_state_msg_.state = charging_state_msg_.CHARGE_FAULT;
00528       break;
00529   }
00530   charging_state_pub_.publish(charging_state_msg_);
00531 }
00532 
00533 void CreateDriver::publishButtonPresses() const
00534 {
00535   if (robot_->isCleanButtonPressed())
00536   {
00537     clean_btn_pub_.publish(empty_msg_);
00538   }
00539   if (robot_->isDayButtonPressed())
00540   {
00541     day_btn_pub_.publish(empty_msg_);
00542   }
00543   if (robot_->isHourButtonPressed())
00544   {
00545     hour_btn_pub_.publish(empty_msg_);
00546   }
00547   if (robot_->isMinButtonPressed())
00548   {
00549     min_btn_pub_.publish(empty_msg_);
00550   }
00551   if (robot_->isDockButtonPressed())
00552   {
00553     dock_btn_pub_.publish(empty_msg_);
00554   }
00555   if (robot_->isSpotButtonPressed())
00556   {
00557     spot_btn_pub_.publish(empty_msg_);
00558   }
00559 }
00560 
00561 void CreateDriver::publishOmniChar()
00562 {
00563   uint8_t ir_char = robot_->getIROmni();
00564   uint16_msg_.data = ir_char;
00565   omni_char_pub_.publish(uint16_msg_);
00566   // TODO(jacobperron): Publish info based on character, such as dock in sight
00567 }
00568 
00569 void CreateDriver::publishMode()
00570 {
00571   const create::CreateMode mode = robot_->getMode();
00572   mode_msg_.header.stamp = ros::Time::now();
00573   switch (mode)
00574   {
00575     case create::MODE_OFF:
00576       mode_msg_.mode = mode_msg_.MODE_OFF;
00577       break;
00578     case create::MODE_PASSIVE:
00579       mode_msg_.mode = mode_msg_.MODE_PASSIVE;
00580       break;
00581     case create::MODE_SAFE:
00582       mode_msg_.mode = mode_msg_.MODE_SAFE;
00583       break;
00584     case create::MODE_FULL:
00585       mode_msg_.mode = mode_msg_.MODE_FULL;
00586       break;
00587     default:
00588       ROS_ERROR("[CREATE] Unknown mode detected");
00589       break;
00590   }
00591   mode_pub_.publish(mode_msg_);
00592 }
00593 
00594 void CreateDriver::publishBumperInfo()
00595 {
00596   bumper_msg_.header.stamp = ros::Time::now();
00597   bumper_msg_.is_left_pressed = robot_->isLeftBumper();
00598   bumper_msg_.is_right_pressed = robot_->isRightBumper();
00599 
00600   if (model_.getVersion() >= create::V_3)
00601   {
00602     bumper_msg_.is_light_left = robot_->isLightBumperLeft();
00603     bumper_msg_.is_light_front_left = robot_->isLightBumperFrontLeft();
00604     bumper_msg_.is_light_center_left = robot_->isLightBumperCenterLeft();
00605     bumper_msg_.is_light_right = robot_->isLightBumperRight();
00606     bumper_msg_.is_light_front_right = robot_->isLightBumperFrontRight();
00607     bumper_msg_.is_light_center_right = robot_->isLightBumperCenterRight();
00608 
00609     bumper_msg_.light_signal_left = robot_->getLightSignalLeft();
00610     bumper_msg_.light_signal_front_left = robot_->getLightSignalFrontLeft();
00611     bumper_msg_.light_signal_center_left = robot_->getLightSignalCenterLeft();
00612     bumper_msg_.light_signal_right = robot_->getLightSignalRight();
00613     bumper_msg_.light_signal_front_right = robot_->getLightSignalFrontRight();
00614     bumper_msg_.light_signal_center_right = robot_->getLightSignalCenterRight();
00615   }
00616 
00617   bumper_pub_.publish(bumper_msg_);
00618 }
00619 
00620 void CreateDriver::publishWheeldrop()
00621 {
00622   if (robot_->isWheeldrop())
00623     wheeldrop_pub_.publish(empty_msg_);
00624 }
00625 
00626 void CreateDriver::spinOnce()
00627 {
00628   update();
00629   diagnostics_.update();
00630   ros::spinOnce();
00631 }
00632 
00633 void CreateDriver::spin()
00634 {
00635   ros::Rate rate(loop_hz_);
00636   while (ros::ok())
00637   {
00638     spinOnce();
00639 
00640     is_running_slowly_ = !rate.sleep();
00641     if (is_running_slowly_)
00642     {
00643       ROS_WARN("[CREATE] Loop running slowly.");
00644     }
00645   }
00646 }
00647 
00648 int main(int argc, char** argv)
00649 {
00650   ros::init(argc, argv, "ca_driver");
00651   ros::NodeHandle nh;
00652 
00653   CreateDriver create_driver(nh);
00654 
00655   try
00656   {
00657     create_driver.spin();
00658   }
00659   catch (std::runtime_error& ex)
00660   {
00661     ROS_FATAL_STREAM("[CREATE] Runtime error: " << ex.what());
00662     return 1;
00663   }
00664   return 0;
00665 }


ca_driver
Author(s): Jacob Perron
autogenerated on Thu Jun 6 2019 20:38:21