Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00040
00041
00042
00043
00044 #ifndef BUMP_BLINK_CONTROLLER_HPP_
00045 #define BUMP_BLINK_CONTROLLER_HPP_
00046
00047
00048
00049
00050
00051 #include <ros/ros.h>
00052 #include <std_msgs/Empty.h>
00053 #include <yocs_controllers/default_controller.hpp>
00054 #include <kobuki_msgs/BumperEvent.h>
00055 #include <kobuki_msgs/Led.h>
00056
00057 namespace kobuki
00058 {
00059
00065 class BumpBlinkController : public yocs::Controller
00066 {
00067 public:
00068 BumpBlinkController(ros::NodeHandle& nh, std::string& name) : Controller(), nh_(nh), name_(name){};
00069 ~BumpBlinkController(){};
00070
00075 bool init()
00076 {
00077 enable_controller_subscriber_ = nh_.subscribe("enable", 10, &BumpBlinkController::enableCB, this);
00078 disable_controller_subscriber_ = nh_.subscribe("disable", 10, &BumpBlinkController::disableCB, this);
00079 bumper_event_subscriber_ = nh_.subscribe("events/bumper", 10, &BumpBlinkController::bumperEventCB, this);
00080
00081 blink_publisher_ = nh_.advertise< kobuki_msgs::Led >("commands/led1", 10);
00082 return true;
00083 };
00084
00085 private:
00086 ros::NodeHandle nh_;
00087 std::string name_;
00088 ros::Subscriber enable_controller_subscriber_, disable_controller_subscriber_;
00089 ros::Subscriber bumper_event_subscriber_;
00090 ros::Publisher blink_publisher_;
00091
00096 void enableCB(const std_msgs::EmptyConstPtr msg);
00097
00102 void disableCB(const std_msgs::EmptyConstPtr msg);
00103
00108 void bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg);
00109 };
00110
00111 void BumpBlinkController::enableCB(const std_msgs::EmptyConstPtr msg)
00112 {
00113 if (this->enable())
00114 {
00115 ROS_INFO_STREAM("Controller has been enabled. [" << name_ << "]");
00116 }
00117 else
00118 {
00119 ROS_INFO_STREAM("Controller was already enabled. [" << name_ <<"]");
00120 }
00121 };
00122
00123 void BumpBlinkController::disableCB(const std_msgs::EmptyConstPtr msg)
00124 {
00125 if (this->disable())
00126 {
00127 ROS_INFO_STREAM("Controller has been disabled. [" << name_ <<"]");
00128 }
00129 else
00130 {
00131 ROS_INFO_STREAM("Controller was already disabled. [" << name_ <<"]");
00132 }
00133 };
00134
00135 void BumpBlinkController::bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg)
00136 {
00137 if (this->getState())
00138 {
00139
00140 kobuki_msgs::LedPtr led_msg_ptr;
00141 led_msg_ptr.reset(new kobuki_msgs::Led());
00142
00143 if (msg->state == kobuki_msgs::BumperEvent::PRESSED)
00144 {
00145 ROS_INFO_STREAM("Bumper pressed. Turning LED on. [" << name_ << "]");
00146 led_msg_ptr->value = kobuki_msgs::Led::GREEN;
00147 blink_publisher_.publish(led_msg_ptr);
00148 }
00149 else
00150 {
00151 ROS_INFO_STREAM("Bumper released. Turning LED off. [" << name_ << "]");
00152 led_msg_ptr->value = kobuki_msgs::Led::BLACK;
00153 blink_publisher_.publish(led_msg_ptr);
00154 }
00155 }
00156 };
00157
00158 }
00159
00160 #endif