create_driver.h
Go to the documentation of this file.
00001 
00028 #ifndef CREATE_DRIVER_CREATE_DRIVER_H
00029 #define CREATE_DRIVER_CREATE_DRIVER_H
00030 #include "ca_msgs/ChargingState.h"
00031 #include "ca_msgs/Mode.h"
00032 #include "ca_msgs/Bumper.h"
00033 #include "ca_msgs/DefineSong.h"
00034 #include "ca_msgs/PlaySong.h"
00035 
00036 #include "create/create.h"
00037 
00038 #include <diagnostic_updater/diagnostic_updater.h>
00039 #include <geometry_msgs/TransformStamped.h>
00040 #include <geometry_msgs/Twist.h>
00041 #include <nav_msgs/Odometry.h>
00042 #include <ros/ros.h>
00043 #include <sensor_msgs/JointState.h>
00044 #include <std_msgs/Bool.h>
00045 #include <std_msgs/Empty.h>
00046 #include <std_msgs/Float32.h>
00047 #include <std_msgs/Int16.h>
00048 #include <std_msgs/UInt16.h>
00049 #include <std_msgs/UInt8MultiArray.h>
00050 #include <tf/transform_broadcaster.h>
00051 
00052 #include <limits>
00053 #include <string>
00054 
00055 static const double MAX_DBL = std::numeric_limits<double>::max();
00056 static const double COVARIANCE[36] = {1e-5, 1e-5, 0.0,     0.0,     0.0,     1e-5,  // NOLINT(whitespace/braces)
00057                                       1e-5, 1e-5, 0.0,     0.0,     0.0,     1e-5,
00058                                       0.0,  0.0,  MAX_DBL, 0.0,     0.0,     0.0,
00059                                       0.0,  0.0,  0.0,     MAX_DBL, 0.0,     0.0,
00060                                       0.0,  0.0,  0.0,     0.0,     MAX_DBL, 0.0,
00061                                       1e-5, 1e-5, 0.0,     0.0,     0.0,     1e-5};
00062 
00063 class CreateDriver
00064 {
00065 private:
00066   create::Create* robot_;
00067   create::RobotModel model_;
00068   tf::TransformBroadcaster tf_broadcaster_;
00069   diagnostic_updater::Updater diagnostics_;
00070   ca_msgs::Mode mode_msg_;
00071   ca_msgs::ChargingState charging_state_msg_;
00072   ca_msgs::Bumper bumper_msg_;
00073   nav_msgs::Odometry odom_msg_;
00074   geometry_msgs::TransformStamped tf_odom_;
00075   ros::Time last_cmd_vel_time_;
00076   std_msgs::Empty empty_msg_;
00077   std_msgs::Float32 float32_msg_;
00078   std_msgs::UInt16 uint16_msg_;
00079   std_msgs::Int16 int16_msg_;
00080   sensor_msgs::JointState joint_state_msg_;
00081   bool is_running_slowly_;
00082 
00083   // ROS params
00084   std::string dev_;
00085   std::string base_frame_;
00086   std::string odom_frame_;
00087   double latch_duration_;
00088   double loop_hz_;
00089   bool publish_tf_;
00090   int baud_;
00091 
00092   void cmdVelCallback(const geometry_msgs::TwistConstPtr& msg);
00093   void debrisLEDCallback(const std_msgs::BoolConstPtr& msg);
00094   void spotLEDCallback(const std_msgs::BoolConstPtr& msg);
00095   void dockLEDCallback(const std_msgs::BoolConstPtr& msg);
00096   void checkLEDCallback(const std_msgs::BoolConstPtr& msg);
00097   void powerLEDCallback(const std_msgs::UInt8MultiArrayConstPtr& msg);
00098   void setASCIICallback(const std_msgs::UInt8MultiArrayConstPtr& msg);
00099   void dockCallback(const std_msgs::EmptyConstPtr& msg);
00100   void undockCallback(const std_msgs::EmptyConstPtr& msg);
00101   void defineSongCallback(const ca_msgs::DefineSongConstPtr& msg);
00102   void playSongCallback(const ca_msgs::PlaySongConstPtr& msg);
00103 
00104   bool update();
00105   void updateBatteryDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat);
00106   void updateSafetyDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat);
00107   void updateSerialDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat);
00108   void updateModeDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat);
00109   void updateDriverDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat);
00110   void publishOdom();
00111   void publishJointState();
00112   void publishBatteryInfo();
00113   void publishButtonPresses() const;
00114   void publishOmniChar();
00115   void publishMode();
00116   void publishBumperInfo();
00117   void publishWheeldrop();
00118 
00119 protected:
00120   ros::NodeHandle nh_;
00121   ros::NodeHandle priv_nh_;
00122   ros::Subscriber cmd_vel_sub_;
00123   ros::Subscriber debris_led_sub_;
00124   ros::Subscriber spot_led_sub_;
00125   ros::Subscriber dock_led_sub_;
00126   ros::Subscriber check_led_sub_;
00127   ros::Subscriber power_led_sub_;
00128   ros::Subscriber set_ascii_sub_;
00129   ros::Subscriber dock_sub_;
00130   ros::Subscriber undock_sub_;
00131   ros::Subscriber define_song_sub_;
00132   ros::Subscriber play_song_sub_;
00133 
00134   ros::Publisher odom_pub_;
00135   ros::Publisher clean_btn_pub_;
00136   ros::Publisher day_btn_pub_;
00137   ros::Publisher hour_btn_pub_;
00138   ros::Publisher min_btn_pub_;
00139   ros::Publisher dock_btn_pub_;
00140   ros::Publisher spot_btn_pub_;
00141   ros::Publisher voltage_pub_;
00142   ros::Publisher current_pub_;
00143   ros::Publisher charge_pub_;
00144   ros::Publisher charge_ratio_pub_;
00145   ros::Publisher capacity_pub_;
00146   ros::Publisher temperature_pub_;
00147   ros::Publisher charging_state_pub_;
00148   ros::Publisher omni_char_pub_;
00149   ros::Publisher mode_pub_;
00150   ros::Publisher bumper_pub_;
00151   ros::Publisher wheeldrop_pub_;
00152   ros::Publisher wheel_joint_pub_;
00153 
00154 public:
00155   explicit CreateDriver(ros::NodeHandle& nh);
00156   ~CreateDriver();
00157   virtual void spin();
00158   virtual void spinOnce();
00159 };  // class CreateDriver
00160 
00161 #endif  // CREATE_DRIVER_CREATE_DRIVER_H


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