Public Member Functions | Private Member Functions | Private Attributes
kobuki::BumpBlinkController Class Reference

#include <bump_blink_controller.hpp>

Inheritance diagram for kobuki::BumpBlinkController:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 BumpBlinkController (ros::NodeHandle &nh, std::string &name)
bool init ()
 ~BumpBlinkController ()

Private Member Functions

void bumperEventCB (const kobuki_msgs::BumperEventConstPtr msg)
 Turns on/off a LED, when a bumper is pressed/released.
void disableCB (const std_msgs::EmptyConstPtr msg)
 ROS logging output for disabling the controller.
void enableCB (const std_msgs::EmptyConstPtr msg)
 ROS logging output for enabling the controller.

Private Attributes

ros::Publisher blink_publisher_
ros::Subscriber bumper_event_subscriber_
ros::Subscriber disable_controller_subscriber_
ros::Subscriber enable_controller_subscriber_
std::string name_
ros::NodeHandle nh_

Detailed Description

@ brief A simple bump-blink-controller

A simple nodelet-based controller for Kobuki, which makes one of Kobuki's LEDs blink, when a bumper is pressed.

Definition at line 65 of file bump_blink_controller.hpp.


Constructor & Destructor Documentation

kobuki::BumpBlinkController::BumpBlinkController ( ros::NodeHandle nh,
std::string &  name 
) [inline]

Definition at line 68 of file bump_blink_controller.hpp.

Definition at line 69 of file bump_blink_controller.hpp.


Member Function Documentation

void kobuki::BumpBlinkController::bumperEventCB ( const kobuki_msgs::BumperEventConstPtr  msg) [private]

Turns on/off a LED, when a bumper is pressed/released.

Parameters:
msgincoming topic message

Definition at line 135 of file bump_blink_controller.hpp.

void kobuki::BumpBlinkController::disableCB ( const std_msgs::EmptyConstPtr  msg) [private]

ROS logging output for disabling the controller.

Parameters:
msgincoming topic message

Definition at line 123 of file bump_blink_controller.hpp.

void kobuki::BumpBlinkController::enableCB ( const std_msgs::EmptyConstPtr  msg) [private]

ROS logging output for enabling the controller.

Parameters:
msgincoming topic message

Definition at line 111 of file bump_blink_controller.hpp.

bool kobuki::BumpBlinkController::init ( ) [inline, virtual]

Set-up necessary publishers/subscribers

Returns:
true, if successful

Implements yocs::Controller.

Definition at line 75 of file bump_blink_controller.hpp.


Member Data Documentation

Definition at line 90 of file bump_blink_controller.hpp.

Definition at line 89 of file bump_blink_controller.hpp.

Definition at line 88 of file bump_blink_controller.hpp.

Definition at line 88 of file bump_blink_controller.hpp.

std::string kobuki::BumpBlinkController::name_ [private]

Definition at line 87 of file bump_blink_controller.hpp.

Definition at line 83 of file bump_blink_controller.hpp.


The documentation for this class was generated from the following file:


kobuki_controller_tutorial
Author(s): Marcus Liebhardt
autogenerated on Mon Oct 6 2014 01:32:03