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