bump_blink_controller.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, Yujin Robot.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Yujin Robot nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00040 /*****************************************************************************
00041 ** Ifdefs
00042 *****************************************************************************/
00043 
00044 #ifndef BUMP_BLINK_CONTROLLER_HPP_
00045 #define BUMP_BLINK_CONTROLLER_HPP_
00046 
00047 /*****************************************************************************
00048 ** Includes
00049 *****************************************************************************/
00050 // %Tag(FULLTEXT)%
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     // choose between led1 and led2
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()) // check, if the controller is active
00138   {
00139     // Preparing LED message
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 // kobuki_msgs::BumperEvent::RELEASED
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 } // namespace kobuki
00159 // %EndTag(FULLTEXT)%
00160 #endif /* BUMP_BLINK_CONTROLLER_HPP_ */


kobuki_controller_tutorial
Author(s): Marcus Liebhardt
autogenerated on Thu Jun 6 2019 17:37:42