28 #ifndef CREATE_DRIVER_CREATE_DRIVER_H 29 #define CREATE_DRIVER_CREATE_DRIVER_H 30 #include "ca_msgs/ChargingState.h" 31 #include "ca_msgs/Mode.h" 32 #include "ca_msgs/Bumper.h" 33 #include "ca_msgs/DefineSong.h" 34 #include "ca_msgs/PlaySong.h" 39 #include <geometry_msgs/TransformStamped.h> 40 #include <geometry_msgs/Twist.h> 41 #include <nav_msgs/Odometry.h> 43 #include <sensor_msgs/JointState.h> 44 #include <std_msgs/Bool.h> 45 #include <std_msgs/Empty.h> 46 #include <std_msgs/Float32.h> 47 #include <std_msgs/Int16.h> 48 #include <std_msgs/UInt16.h> 49 #include <std_msgs/UInt8MultiArray.h> 55 static const double MAX_DBL = std::numeric_limits<double>::max();
56 static const double COVARIANCE[36] = {1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5,
57 1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5,
58 0.0, 0.0,
MAX_DBL, 0.0, 0.0, 0.0,
59 0.0, 0.0, 0.0,
MAX_DBL, 0.0, 0.0,
60 0.0, 0.0, 0.0, 0.0,
MAX_DBL, 0.0,
61 1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5};
161 #endif // CREATE_DRIVER_CREATE_DRIVER_H void updateDriverDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
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_
ros::Publisher wheel_joint_pub_
void updateSafetyDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Publisher voltage_pub_
ros::Publisher charging_state_pub_
void updateBatteryDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void playSongCallback(const ca_msgs::PlaySongConstPtr &msg)
ros::Publisher omni_char_pub_
ros::Publisher min_btn_pub_
void defineSongCallback(const ca_msgs::DefineSongConstPtr &msg)
ros::Publisher bumper_pub_
ros::Subscriber check_led_sub_
std_msgs::Float32 float32_msg_
tf::TransformBroadcaster tf_broadcaster_
diagnostic_updater::Updater diagnostics_
CreateDriver(ros::NodeHandle &nh)
std_msgs::UInt16 uint16_msg_
ros::Publisher temperature_pub_
ros::Subscriber debris_led_sub_
ca_msgs::ChargingState charging_state_msg_
static const double MAX_DBL
void dockCallback(const std_msgs::EmptyConstPtr &msg)
void publishButtonPresses() const
ros::Publisher clean_btn_pub_
ros::Subscriber play_song_sub_
ca_msgs::Bumper bumper_msg_
ros::Publisher day_btn_pub_
void cmdVelCallback(const geometry_msgs::TwistConstPtr &msg)
ros::Publisher charge_ratio_pub_
nav_msgs::Odometry odom_msg_
void setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
void updateSerialDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
ros::Publisher dock_btn_pub_
std_msgs::Int16 int16_msg_
ros::Subscriber cmd_vel_sub_
void spotLEDCallback(const std_msgs::BoolConstPtr &msg)
void updateModeDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
void publishBatteryInfo()
static const double COVARIANCE[36]
ros::Publisher hour_btn_pub_
ros::Subscriber dock_sub_
ros::Publisher capacity_pub_
ros::Publisher wheeldrop_pub_
ros::Publisher charge_pub_
std_msgs::Empty empty_msg_
void undockCallback(const std_msgs::EmptyConstPtr &msg)
void dockLEDCallback(const std_msgs::BoolConstPtr &msg)
ros::Subscriber undock_sub_
create::RobotModel model_
ros::Publisher current_pub_
ros::Publisher spot_btn_pub_
geometry_msgs::TransformStamped tf_odom_
sensor_msgs::JointState joint_state_msg_