bump_blink_controller.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Yujin Robot.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Yujin Robot nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
40 /*****************************************************************************
41 ** Ifdefs
42 *****************************************************************************/
43 
44 #ifndef BUMP_BLINK_CONTROLLER_HPP_
45 #define BUMP_BLINK_CONTROLLER_HPP_
46 
47 /*****************************************************************************
48 ** Includes
49 *****************************************************************************/
50 // %Tag(FULLTEXT)%
51 #include <ros/ros.h>
52 #include <std_msgs/Empty.h>
54 #include <kobuki_msgs/BumperEvent.h>
55 #include <kobuki_msgs/Led.h>
56 
57 namespace kobuki
58 {
59 
66 {
67 public:
68  BumpBlinkController(ros::NodeHandle& nh, std::string& name) : Controller(), nh_(nh), name_(name){};
70 
75  bool init()
76  {
80  // choose between led1 and led2
81  blink_publisher_ = nh_.advertise< kobuki_msgs::Led >("commands/led1", 10);
82  return true;
83  };
84 
85 private:
87  std::string name_;
91 
96  void enableCB(const std_msgs::EmptyConstPtr msg);
97 
102  void disableCB(const std_msgs::EmptyConstPtr msg);
103 
108  void bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg);
109 };
110 
111 void BumpBlinkController::enableCB(const std_msgs::EmptyConstPtr msg)
112 {
113  if (this->enable())
114  {
115  ROS_INFO_STREAM("Controller has been enabled. [" << name_ << "]");
116  }
117  else
118  {
119  ROS_INFO_STREAM("Controller was already enabled. [" << name_ <<"]");
120  }
121 };
122 
123 void BumpBlinkController::disableCB(const std_msgs::EmptyConstPtr msg)
124 {
125  if (this->disable())
126  {
127  ROS_INFO_STREAM("Controller has been disabled. [" << name_ <<"]");
128  }
129  else
130  {
131  ROS_INFO_STREAM("Controller was already disabled. [" << name_ <<"]");
132  }
133 };
134 
135 void BumpBlinkController::bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg)
136 {
137  if (this->getState()) // check, if the controller is active
138  {
139  // Preparing LED message
140  kobuki_msgs::LedPtr led_msg_ptr;
141  led_msg_ptr.reset(new kobuki_msgs::Led());
142 
143  if (msg->state == kobuki_msgs::BumperEvent::PRESSED)
144  {
145  ROS_INFO_STREAM("Bumper pressed. Turning LED on. [" << name_ << "]");
146  led_msg_ptr->value = kobuki_msgs::Led::GREEN;
147  blink_publisher_.publish(led_msg_ptr);
148  }
149  else // kobuki_msgs::BumperEvent::RELEASED
150  {
151  ROS_INFO_STREAM("Bumper released. Turning LED off. [" << name_ << "]");
152  led_msg_ptr->value = kobuki_msgs::Led::BLACK;
153  blink_publisher_.publish(led_msg_ptr);
154  }
155  }
156 };
157 
158 } // namespace kobuki
159 // %EndTag(FULLTEXT)%
160 #endif /* BUMP_BLINK_CONTROLLER_HPP_ */
ros::Subscriber disable_controller_subscriber_
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
BumpBlinkController(ros::NodeHandle &nh, std::string &name)
void disableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for disabling the controller.
void bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg)
Turns on/off a LED, when a bumper is pressed/released.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void enableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for enabling the controller.
#define ROS_INFO_STREAM(args)


kobuki_controller_tutorial
Author(s): Marcus Liebhardt
autogenerated on Mon Jun 10 2019 13:45:01