00001 00034 #ifndef RIDGEBACK_BASE_RIDGEBACK_COOLING_H 00035 #define RIDGEBACK_BASE_RIDGEBACK_COOLING_H 00036 00037 #include "ros/ros.h" 00038 #include "geometry_msgs/Twist.h" 00039 #include "ridgeback_msgs/Status.h" 00040 #include "ridgeback_msgs/Fans.h" 00041 00042 namespace ridgeback_base 00043 { 00044 00045 class RidgebackCooling 00046 { 00047 public: 00048 explicit RidgebackCooling(ros::NodeHandle* nh); 00049 00050 private: 00051 ros::NodeHandle* nh_; 00052 00053 ros::Publisher cmd_fans_pub_; 00054 00055 ros::Subscriber status_sub_; 00056 ros::Subscriber cmd_vel_sub_; 00057 00058 ros::Timer cmd_fans_timer_; 00059 00060 bool charger_disconnected_; 00061 ridgeback_msgs::Fans cmd_fans_msg_; 00062 double last_motion_cmd_time_; 00063 00064 static const double LINEAR_VEL_THRESHOLD; 00065 static const double ANGULAR_VEL_THRESHOLD; 00066 static const double MOITON_COMMAND_TIMEOUT; 00067 00068 void statusCallback(const ridgeback_msgs::Status::ConstPtr& status); 00069 void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& twist); 00070 void cmdFansCallback(const ros::TimerEvent&); 00071 }; 00072 00073 } // namespace ridgeback_base 00074 00075 #endif // RIDGEBACK_BASE_RIDGEBACK_COOLING_H