44 #ifndef BUMP_BLINK_CONTROLLER_HPP_ 45 #define BUMP_BLINK_CONTROLLER_HPP_ 52 #include <std_msgs/Empty.h> 54 #include <kobuki_msgs/BumperEvent.h> 55 #include <kobuki_msgs/Led.h> 96 void enableCB(
const std_msgs::EmptyConstPtr msg);
102 void disableCB(
const std_msgs::EmptyConstPtr msg);
108 void bumperEventCB(
const kobuki_msgs::BumperEventConstPtr msg);
140 kobuki_msgs::LedPtr led_msg_ptr;
141 led_msg_ptr.reset(
new kobuki_msgs::Led());
143 if (msg->state == kobuki_msgs::BumperEvent::PRESSED)
146 led_msg_ptr->value = kobuki_msgs::Led::GREEN;
152 led_msg_ptr->value = kobuki_msgs::Led::BLACK;
ros::Subscriber disable_controller_subscriber_
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber enable_controller_subscriber_
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.
ros::Subscriber bumper_event_subscriber_
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.
ros::Publisher blink_publisher_
#define ROS_INFO_STREAM(args)