38 model_(
create::RobotModel::CREATE_2),
39 is_running_slowly_(false)
42 std::string robot_model_name;
44 priv_nh_.
param<std::string>(
"robot_model", robot_model_name,
"CREATE_2");
51 if (robot_model_name ==
"ROOMBA_400")
55 else if (robot_model_name ==
"CREATE_1")
59 else if (robot_model_name ==
"CREATE_2")
65 ROS_FATAL_STREAM(
"[CREATE] Robot model \"" + robot_model_name +
"\" is not known.");
76 if (!robot_->connect(dev_, baud_))
78 ROS_FATAL(
"[CREATE] Failed to establish serial connection with Create.");
82 ROS_INFO(
"[CREATE] Connection established.");
88 ROS_INFO(
"[CREATE] Battery level %.2f %%", (robot_->getBatteryCharge() / robot_->getBatteryCapacity()) * 100.0);
106 for (
int i = 0; i < 36; i++)
160 ROS_INFO(
"[CREATE] Destruct sequence initiated.");
193 if (msg->data.size() < 1)
195 ROS_ERROR(
"[CREATE] No values provided to set power LED");
199 if (msg->data.size() < 2)
213 if (msg->data.size() < 1)
215 ROS_ERROR(
"[CREATE] No ASCII digits provided");
217 else if (msg->data.size() < 2)
221 else if (msg->data.size() < 3)
225 else if (msg->data.size() < 4)
236 ROS_ERROR(
"[CREATE] ASCII character out of range [32, 126]");
259 if (!
robot_->
defineSong(msg->song, msg->length, &(msg->notes.front()), &(msg->durations.front())))
261 ROS_ERROR_STREAM(
"[CREATE] Failed to define song " << msg->song <<
" of length " << msg->length);
298 const float charge_ratio = charge / capacity;
302 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Charging fault reported by base");
304 else if (charge_ratio == 0)
306 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Battery reports no charge");
308 else if (charge_ratio < 0.1)
310 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Battery reports less than 10% charge");
314 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Battery is OK");
317 stat.
add(
"Charge (Ah)", charge);
318 stat.
add(
"Capacity (Ah)", capacity);
323 switch (charging_state)
326 stat.
add(
"Charging state",
"Not charging");
329 stat.
add(
"Charging state",
"Reconditioning");
332 stat.
add(
"Charging state",
"Full charge");
335 stat.
add(
"Charging state",
"Trickle charging");
338 stat.
add(
"Charging state",
"Waiting");
341 stat.
add(
"Charging state",
"Fault");
352 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Wheeldrop detected");
356 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Cliff detected");
360 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"No safety issues detected");
363 stat.
add(
"Wheeldrop", is_wheeldrop);
364 stat.
add(
"Cliff", is_cliff);
375 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Serial port to base not open");
377 else if (corrupt_packets)
379 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
380 "Corrupt packets detected. If the number of corrupt packets is increasing, data may be unreliable");
384 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Serial connection is good");
387 stat.
add(
"Corrupt packets", corrupt_packets);
388 stat.
add(
"Total packets", total_packets);
397 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Unknown mode of operation");
400 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Mode is set to OFF");
403 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Mode is set to PASSIVE");
406 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Mode is set to SAFE");
409 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Mode is set to FULL");
418 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Internal loop running slowly");
422 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Maintaining loop frequency");
466 tf_odom_.transform.translation.x = pose.
x;
467 tf_odom_.transform.translation.y = pose.
y;
505 switch (charging_state)
588 ROS_ERROR(
"[CREATE] Unknown mode detected");
643 ROS_WARN(
"[CREATE] Loop running slowly.");
648 int main(
int argc,
char** argv)
657 create_driver.
spin();
659 catch (std::runtime_error& ex)
uint64_t getTotalPackets() const
void updateDriverDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
uint8_t getIROmni() const
void debrisLEDCallback(const std_msgs::BoolConstPtr &msg)
ros::Subscriber define_song_sub_
ros::Subscriber power_led_sub_
ros::Subscriber set_ascii_sub_
ros::Time last_cmd_vel_time_
void checkLEDCallback(const std_msgs::BoolConstPtr &msg)
ros::Subscriber dock_led_sub_
ros::Subscriber spot_led_sub_
void publish(const boost::shared_ptr< M > &message) const
unsigned int getBaud() const
bool isLightBumperFrontLeft() const
ros::Publisher wheel_joint_pub_
bool setDigitsASCII(const uint8_t &digit1, const uint8_t &digit2, const uint8_t &digit3, const uint8_t &digit4) const
void updateSafetyDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Publisher voltage_pub_
void summary(unsigned char lvl, const std::string s)
ros::Publisher charging_state_pub_
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)
void playSongCallback(const ca_msgs::PlaySongConstPtr &msg)
static RobotModel CREATE_1
ros::Publisher omni_char_pub_
void setHardwareID(const std::string &hwid)
bool isLeftBumper() const
ros::Publisher min_btn_pub_
void defineSongCallback(const ca_msgs::DefineSongConstPtr &msg)
create::ChargingState getChargingState() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher bumper_pub_
void add(const std::string &name, TaskFunction f)
ros::Subscriber check_led_sub_
std_msgs::Float32 float32_msg_
tf::TransformBroadcaster tf_broadcaster_
int8_t getTemperature() const
diagnostic_updater::Updater diagnostics_
CreateDriver(ros::NodeHandle &nh)
bool isHourButtonPressed() const
uint16_t getLightSignalFrontLeft() const
std_msgs::UInt16 uint16_msg_
ros::Publisher temperature_pub_
ros::Subscriber debris_led_sub_
bool isLightBumperCenterRight() const
float getRequestedLeftWheelVel() const
ca_msgs::ChargingState charging_state_msg_
void dockCallback(const std_msgs::EmptyConstPtr &msg)
void publishButtonPresses() const
ros::Publisher clean_btn_pub_
float getRightWheelDistance() const
create::Pose getPose() const
ros::Subscriber play_song_sub_
float getRequestedRightWheelVel() const
ca_msgs::Bumper bumper_msg_
bool enableDockLED(const bool &enable)
bool setPowerLED(const uint8_t &power, const uint8_t &intensity=255)
ros::Publisher day_btn_pub_
void cmdVelCallback(const geometry_msgs::TwistConstPtr &msg)
bool isLightBumperFrontRight() const
float getBatteryCharge() const
ros::Publisher charge_ratio_pub_
nav_msgs::Odometry odom_msg_
ProtocolVersion getVersion() const
void setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
bool playSong(const uint8_t &songNumber) const
void updateSerialDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Publisher dock_btn_pub_
std::vector< float > covariance
create::Vel getVel() const
#define ROS_FATAL_STREAM(args)
uint64_t getNumCorruptPackets() const
uint16_t getLightSignalCenterLeft() const
std_msgs::Int16 int16_msg_
ros::Subscriber cmd_vel_sub_
void spotLEDCallback(const std_msgs::BoolConstPtr &msg)
bool isLightBumperLeft() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
float getWheelDiameter() const
void updateModeDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
bool enableCheckRobotLED(const bool &enable)
bool enableSpotLED(const bool &enable)
void powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
void publishBatteryInfo()
bool isMinButtonPressed() const
bool isCleanButtonPressed() const
static const double COVARIANCE[36]
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_
bool isDockButtonPressed() const
bool enableDebrisLED(const bool &enable)
ros::Subscriber dock_sub_
uint16_t getLightSignalLeft() const
bool isRightBumper() const
bool isDayButtonPressed() const
ros::Publisher capacity_pub_
ros::Publisher wheeldrop_pub_
ros::Publisher charge_pub_
uint16_t getLightSignalCenterRight() const
#define ROS_INFO_STREAM(args)
std_msgs::Empty empty_msg_
bool isSpotButtonPressed() const
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
uint16_t getLightSignalRight() const
void undockCallback(const std_msgs::EmptyConstPtr &msg)
void dockLEDCallback(const std_msgs::BoolConstPtr &msg)
ROSCPP_DECL void shutdown()
float getBatteryCapacity() const
static RobotModel CREATE_2
ros::Subscriber undock_sub_
void add(const std::string &key, const T &val)
create::RobotModel model_
#define ROS_ERROR_STREAM(args)
ros::Publisher current_pub_
ROSCPP_DECL void spinOnce()
ros::Publisher spot_btn_pub_
static RobotModel ROOMBA_400
geometry_msgs::TransformStamped tf_odom_
float getLeftWheelDistance() const
bool setMode(const create::CreateMode &mode)
create::CreateMode getMode()
bool isLightBumperRight() const
sensor_msgs::JointState joint_state_msg_
bool isLightBumperCenterLeft() const
uint16_t getLightSignalFrontRight() const
bool defineSong(const uint8_t &songNumber, const uint8_t &songLength, const uint8_t *notes, const float *durations) const