Go to the documentation of this file.
35 : model_(
create::RobotModel::CREATE_2),
39 is_running_slowly_(false)
41 std::string robot_model_name;
43 priv_nh_.
param<std::string>(
"robot_model", robot_model_name,
"CREATE_2");
50 if (robot_model_name ==
"ROOMBA_400")
54 else if (robot_model_name ==
"CREATE_1")
58 else if (robot_model_name ==
"CREATE_2")
64 ROS_FATAL_STREAM(
"[CREATE] Robot model \"" + robot_model_name +
"\" is not known.");
77 ROS_FATAL(
"[CREATE] Failed to establish serial connection with Create.");
81 ROS_INFO(
"[CREATE] Connection established.");
105 for (
int i = 0; i < 36; i++)
162 ROS_INFO(
"[CREATE] Destruct sequence initiated.");
195 if (
msg->data.size() < 1)
197 ROS_ERROR(
"[CREATE] No values provided to set power LED");
201 if (
msg->data.size() < 2)
215 if (
msg->data.size() < 1)
217 ROS_ERROR(
"[CREATE] No ASCII digits provided");
219 else if (
msg->data.size() < 2)
223 else if (
msg->data.size() < 3)
227 else if (
msg->data.size() < 4)
238 ROS_ERROR(
"[CREATE] ASCII character out of range [32, 126]");
283 ROS_ERROR_STREAM(
"[CREATE] Failed to set duty cycle " <<
msg->duty_cycle <<
" for side brush motor");
290 ROS_ERROR_STREAM(
"[CREATE] Failed to set duty cycle " <<
msg->duty_cycle <<
" for main motor");
297 ROS_ERROR_STREAM(
"[CREATE] Failed to set duty cycle " <<
msg->duty_cycle <<
" for vacuum motor");
326 const float charge_ratio = charge / capacity;
330 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Charging fault reported by base");
332 else if (charge_ratio == 0)
334 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Battery reports no charge");
336 else if (charge_ratio < 0.1)
338 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Battery reports less than 10% charge");
342 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Battery is OK");
345 stat.
add(
"Charge (Ah)", charge);
346 stat.
add(
"Capacity (Ah)", capacity);
351 switch (charging_state)
354 stat.
add(
"Charging state",
"Not charging");
357 stat.
add(
"Charging state",
"Reconditioning");
360 stat.
add(
"Charging state",
"Full charge");
363 stat.
add(
"Charging state",
"Trickle charging");
366 stat.
add(
"Charging state",
"Waiting");
369 stat.
add(
"Charging state",
"Fault");
380 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Wheeldrop detected");
384 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Cliff detected");
388 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"No safety issues detected");
391 stat.
add(
"Wheeldrop", is_wheeldrop);
392 stat.
add(
"Cliff", is_cliff);
403 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Serial port to base not open");
405 else if (corrupt_packets)
407 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
408 "Corrupt packets detected. If the number of corrupt packets is increasing, data may be unreliable");
412 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Serial connection is good");
415 stat.
add(
"Corrupt packets", corrupt_packets);
416 stat.
add(
"Total packets", total_packets);
425 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Unknown mode of operation");
428 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Mode is set to OFF");
431 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Mode is set to PASSIVE");
434 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Mode is set to SAFE");
437 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Mode is set to FULL");
446 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Internal loop running slowly");
450 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Maintaining loop frequency");
462 geometry_msgs::Quaternion quat =
tf2::toMsg(tf_quat);
496 tf_odom_.transform.translation.x = pose.
x;
497 tf_odom_.transform.translation.y = pose.
y;
535 switch (charging_state)
618 ROS_ERROR(
"[CREATE] Unknown mode detected");
673 ROS_WARN(
"[CREATE] Loop running slowly.");
678 int main(
int argc,
char** argv)
687 create_driver.
spin();
689 catch (std::runtime_error& ex)
ros::Publisher charge_ratio_pub_
float getLeftWheelDistance() const
bool isSpotButtonPressed() const
ros::Publisher voltage_pub_
bool isHourButtonPressed() const
bool isDockButtonPressed() const
void debrisLEDCallback(const std_msgs::BoolConstPtr &msg)
bool setMode(const create::CreateMode &mode)
ros::Publisher dock_btn_pub_
ros::Publisher capacity_pub_
void updateSafetyDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
int main(int argc, char **argv)
void powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
ros::Publisher temperature_pub_
#define ROS_ERROR_STREAM(args)
void add(const std::string &key, const bool &b)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
std_msgs::UInt16 uint16_msg_
float getRequestedLeftWheelVel() const
ros::Subscriber set_ascii_sub_
void publishButtonPresses() const
ros::Publisher spot_btn_pub_
static RobotModel CREATE_2
void playSongCallback(const create_msgs::PlaySongConstPtr &msg)
#define ROS_FATAL_STREAM(args)
uint16_t getLightSignalFrontLeft() const
void spotLEDCallback(const std_msgs::BoolConstPtr &msg)
bool isLightBumperRight() const
uint8_t getIROmni() const
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
void checkLEDCallback(const std_msgs::BoolConstPtr &msg)
tf2_ros::TransformBroadcaster tf_broadcaster_
diagnostic_updater::Updater diagnostics_
ros::Subscriber dock_led_sub_
ros::Publisher wheeldrop_pub_
ROSCPP_DECL void spinOnce()
void updateBatteryDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
ROSCPP_DECL void shutdown()
ros::Subscriber play_song_sub_
void cmdVelCallback(const geometry_msgs::TwistConstPtr &msg)
void updateDriverDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void defineSongCallback(const create_msgs::DefineSongConstPtr &msg)
ros::Subscriber dock_sub_
ros::Subscriber vacuum_motor_sub_
bool setMainMotor(const float &power)
void publish(const boost::shared_ptr< M > &message) const
std_msgs::Empty empty_msg_
Publisher advertise(AdvertiseOptions &ops)
bool isDayButtonPressed() const
float getWheelDiameter() const
create_msgs::Mode mode_msg_
uint16_t getLightSignalCenterLeft() const
void setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
bool enableDockLED(const bool &enable)
bool enableSpotLED(const bool &enable)
ros::Subscriber spot_led_sub_
create::Pose getPose() const
create_msgs::ChargingState charging_state_msg_
int8_t getTemperature() const
sensor_msgs::JointState joint_state_msg_
void summary(const diagnostic_msgs::DiagnosticStatus &src)
ros::Subscriber main_brush_motor_sub_
void updateModeDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
uint16_t getLightSignalRight() const
bool isLightBumperCenterLeft() const
static RobotModel CREATE_1
ProtocolVersion getVersion() const
bool setVacuumMotor(const float &power)
uint16_t getLightSignalFrontRight() const
bool drive(const float &xVel, const float &angularVel)
ros::Time last_cmd_vel_time_
ros::Publisher min_btn_pub_
bool enableCheckRobotLED(const bool &enable)
bool isLightBumperFrontRight() const
void undockCallback(const std_msgs::EmptyConstPtr &msg)
uint16_t getLightSignalCenterRight() const
uint64_t getTotalPackets() const
bool isMinButtonPressed() const
create_msgs::Bumper bumper_msg_
nav_msgs::Odometry odom_msg_
void updateSerialDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void publishBatteryInfo()
uint64_t getNumCorruptPackets() const
bool setPowerLED(const uint8_t &power, const uint8_t &intensity=255)
void dockLEDCallback(const std_msgs::BoolConstPtr &msg)
ros::Subscriber check_led_sub_
ros::Publisher hour_btn_pub_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Subscriber debris_led_sub_
float getRequestedRightWheelVel() const
bool enableDebrisLED(const bool &enable)
#define ROS_INFO_STREAM(args)
std_msgs::Float32 float32_msg_
static const double COVARIANCE[36]
void setHardwareID(const std::string &hwid)
ros::Subscriber power_led_sub_
bool isLeftBumper() const
bool isRightBumper() const
bool isLightBumperLeft() const
float getRightWheelDistance() const
void sideBrushMotor(const create_msgs::MotorSetpointConstPtr &msg)
ros::Subscriber side_brush_motor_sub_
bool setDigitsASCII(const uint8_t &digit1, const uint8_t &digit2, const uint8_t &digit3, const uint8_t &digit4) const
ros::Publisher charge_pub_
float getBatteryCharge() const
bool isCleanButtonPressed() const
bool isLightBumperCenterRight() const
ros::Subscriber undock_sub_
bool isLightBumperFrontLeft() const
static RobotModel ROOMBA_400
ros::Subscriber cmd_vel_sub_
create::Vel getVel() const
void vacuumBrushMotor(const create_msgs::MotorSetpointConstPtr &msg)
ros::Publisher clean_btn_pub_
std::vector< float > covariance
T param(const std::string ¶m_name, const T &default_val) const
unsigned int getBaud() const
bool defineSong(const uint8_t &songNumber, const uint8_t &songLength, const uint8_t *notes, const float *durations) const
create::CreateMode getMode()
bool connect(const std::string &port, const int &baud)
ros::Publisher bumper_pub_
ros::Publisher omni_char_pub_
void add(const std::string &name, TaskFunction f)
create::ChargingState getChargingState() const
std_msgs::Int16 int16_msg_
ros::Publisher charging_state_pub_
CreateDriver(ros::NodeHandle &nh)
void dockCallback(const std_msgs::EmptyConstPtr &msg)
bool playSong(const uint8_t &songNumber) const
ros::Publisher wheel_joint_pub_
ros::Subscriber define_song_sub_
void mainBrushMotor(const create_msgs::MotorSetpointConstPtr &msg)
bool setSideMotor(const float &power)
ros::Publisher day_btn_pub_
create::RobotModel model_
geometry_msgs::TransformStamped tf_odom_
float getBatteryCapacity() const
uint16_t getLightSignalLeft() const
ros::Publisher current_pub_
create_driver
Author(s): Jacob Perron
autogenerated on Wed May 24 2023 02:19:10