create_driver.h
Go to the documentation of this file.
1 
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"
35 
36 #include "create/create.h"
37 
39 #include <geometry_msgs/TransformStamped.h>
40 #include <geometry_msgs/Twist.h>
41 #include <nav_msgs/Odometry.h>
42 #include <ros/ros.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>
51 
52 #include <limits>
53 #include <string>
54 
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, // NOLINT(whitespace/braces)
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};
62 
64 {
65 private:
70  ca_msgs::Mode mode_msg_;
71  ca_msgs::ChargingState charging_state_msg_;
72  ca_msgs::Bumper bumper_msg_;
73  nav_msgs::Odometry odom_msg_;
74  geometry_msgs::TransformStamped tf_odom_;
76  std_msgs::Empty empty_msg_;
77  std_msgs::Float32 float32_msg_;
78  std_msgs::UInt16 uint16_msg_;
79  std_msgs::Int16 int16_msg_;
80  sensor_msgs::JointState joint_state_msg_;
82 
83  // ROS params
84  std::string dev_;
85  std::string base_frame_;
86  std::string odom_frame_;
88  double loop_hz_;
90  int baud_;
91 
92  void cmdVelCallback(const geometry_msgs::TwistConstPtr& msg);
93  void debrisLEDCallback(const std_msgs::BoolConstPtr& msg);
94  void spotLEDCallback(const std_msgs::BoolConstPtr& msg);
95  void dockLEDCallback(const std_msgs::BoolConstPtr& msg);
96  void checkLEDCallback(const std_msgs::BoolConstPtr& msg);
97  void powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr& msg);
98  void setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr& msg);
99  void dockCallback(const std_msgs::EmptyConstPtr& msg);
100  void undockCallback(const std_msgs::EmptyConstPtr& msg);
101  void defineSongCallback(const ca_msgs::DefineSongConstPtr& msg);
102  void playSongCallback(const ca_msgs::PlaySongConstPtr& msg);
103 
104  bool update();
110  void publishOdom();
111  void publishJointState();
112  void publishBatteryInfo();
113  void publishButtonPresses() const;
114  void publishOmniChar();
115  void publishMode();
116  void publishBumperInfo();
117  void publishWheeldrop();
118 
119 protected:
133 
153 
154 public:
155  explicit CreateDriver(ros::NodeHandle& nh);
156  ~CreateDriver();
157  virtual void spin();
158  virtual void spinOnce();
159 }; // class CreateDriver
160 
161 #endif // CREATE_DRIVER_CREATE_DRIVER_H
void updateDriverDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
virtual void spinOnce()
std::string odom_frame_
Definition: create_driver.h:86
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_
Definition: create_driver.h:75
void checkLEDCallback(const std_msgs::BoolConstPtr &msg)
void publishBumperInfo()
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)
bool is_running_slowly_
Definition: create_driver.h:81
void playSongCallback(const ca_msgs::PlaySongConstPtr &msg)
void publishJointState()
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_
Definition: create_driver.h:77
tf::TransformBroadcaster tf_broadcaster_
Definition: create_driver.h:68
diagnostic_updater::Updater diagnostics_
Definition: create_driver.h:69
CreateDriver(ros::NodeHandle &nh)
double loop_hz_
Definition: create_driver.h:88
std_msgs::UInt16 uint16_msg_
Definition: create_driver.h:78
ros::Publisher temperature_pub_
ros::Subscriber debris_led_sub_
ca_msgs::ChargingState charging_state_msg_
Definition: create_driver.h:71
static const double MAX_DBL
Definition: create_driver.h:55
void publishWheeldrop()
void dockCallback(const std_msgs::EmptyConstPtr &msg)
void publishButtonPresses() const
ros::Publisher clean_btn_pub_
ros::Publisher odom_pub_
ros::Subscriber play_song_sub_
ca_msgs::Bumper bumper_msg_
Definition: create_driver.h:72
ros::Publisher day_btn_pub_
void cmdVelCallback(const geometry_msgs::TwistConstPtr &msg)
ros::Publisher charge_ratio_pub_
nav_msgs::Odometry odom_msg_
Definition: create_driver.h:73
void setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
void updateSerialDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
double latch_duration_
Definition: create_driver.h:87
virtual void spin()
ros::Publisher dock_btn_pub_
std_msgs::Int16 int16_msg_
Definition: create_driver.h:79
ros::Subscriber cmd_vel_sub_
void spotLEDCallback(const std_msgs::BoolConstPtr &msg)
void publishOmniChar()
void updateModeDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr &msg)
void publishBatteryInfo()
static const double COVARIANCE[36]
Definition: create_driver.h:56
ros::Publisher hour_btn_pub_
ros::Subscriber dock_sub_
std::string base_frame_
Definition: create_driver.h:85
ros::Publisher capacity_pub_
ros::Publisher wheeldrop_pub_
std::string dev_
Definition: create_driver.h:84
ros::Publisher charge_pub_
std_msgs::Empty empty_msg_
Definition: create_driver.h:76
void undockCallback(const std_msgs::EmptyConstPtr &msg)
void dockLEDCallback(const std_msgs::BoolConstPtr &msg)
ros::NodeHandle priv_nh_
create::Create * robot_
Definition: create_driver.h:66
ros::Publisher mode_pub_
ros::Subscriber undock_sub_
create::RobotModel model_
Definition: create_driver.h:67
ros::Publisher current_pub_
ros::NodeHandle nh_
ros::Publisher spot_btn_pub_
geometry_msgs::TransformStamped tf_odom_
Definition: create_driver.h:74
ca_msgs::Mode mode_msg_
Definition: create_driver.h:70
sensor_msgs::JointState joint_state_msg_
Definition: create_driver.h:80


ca_driver
Author(s): Jacob Perron
autogenerated on Fri Jun 7 2019 21:45:23