Public Member Functions | Private Member Functions | Private Attributes | List of all members
kobuki::RandomWalkerController Class Reference

#include <random_walker_controller.hpp>

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

Public Member Functions

bool init ()
 
 RandomWalkerController (ros::NodeHandle &nh_priv, std::string &name)
 
void spin ()
 Publishes velocity commands and triggers the LEDs. More...
 
 ~RandomWalkerController ()
 
- Public Member Functions inherited from yocs::Controller
 Controller ()
 
bool disable ()
 
bool enable ()
 
bool getState ()
 
virtual ~Controller ()
 

Private Member Functions

void bumperEventCB (const kobuki_msgs::BumperEventConstPtr msg)
 Trigger direction change and LED blink, when a bumper is pressed. More...
 
void cliffEventCB (const kobuki_msgs::CliffEventConstPtr msg)
 Trigger direction change and LED blink, when a cliff is detected. More...
 
void disableCB (const std_msgs::EmptyConstPtr msg)
 ROS logging output for disabling the controller. More...
 
void enableCB (const std_msgs::EmptyConstPtr msg)
 ROS logging output for enabling the controller. More...
 
void wheelDropEventCB (const kobuki_msgs::WheelDropEventConstPtr msg)
 Trigger stopping and LED blink, when a wheel drop is detected. More...
 

Private Attributes

bool bumper_center_pressed_
 Flag for center bumper's state. More...
 
ros::Subscriber bumper_event_subscriber_
 Subscribers. More...
 
bool bumper_left_pressed_
 Flag for left bumper's state. More...
 
bool bumper_right_pressed_
 Flag for right bumper's state. More...
 
bool change_direction_
 Flag for changing direction. More...
 
bool cliff_center_detected_
 Flag for center cliff sensor's state. More...
 
ros::Subscriber cliff_event_subscriber_
 
bool cliff_left_detected_
 Flag for left cliff sensor's state. More...
 
bool cliff_right_detected_
 Flag for right cliff sensor's state. More...
 
ros::Publisher cmd_vel_publisher_
 Publishers. More...
 
ros::Subscriber disable_controller_subscriber_
 
ros::Subscriber enable_controller_subscriber_
 Subscribers. More...
 
ros::Publisher led1_publisher_
 
ros::Publisher led2_publisher_
 
bool led_bumper_on_
 Flag for bumper LED's state. More...
 
bool led_cliff_on_
 Flag for cliff sensor LED's state. More...
 
bool led_wheel_drop_on_
 Flag for wheel drop sensor LED's state. More...
 
std::string name_
 Node(let) name. More...
 
ros::NodeHandle nh_priv_
 Private ROS handle. More...
 
bool stop_
 Flag for stopping. More...
 
bool turning_
 Flag for turning state. More...
 
int turning_direction_
 Randomly chosen turning direction. More...
 
ros::Duration turning_duration_
 Randomly chosen turning duration. More...
 
ros::Time turning_start_
 Start time of turning. More...
 
double vel_ang_
 Angular velocity for rotating. More...
 
double vel_lin_
 Linear velocity for moving straight. More...
 
ros::Subscriber wheel_drop_event_subscriber_
 
bool wheel_drop_left_detected_
 Flag for left wheel drop sensor's state. More...
 
bool wheel_drop_right_detected_
 Flag for right wheel drop sensor's state. More...
 

Detailed Description

@ brief A controller implementing a simple random walker algorithm

Controller moves the robot around, changing direction whenever a bumper or cliff event occurs For changing direction random angles are used.

Definition at line 42 of file random_walker_controller.hpp.

Constructor & Destructor Documentation

kobuki::RandomWalkerController::RandomWalkerController ( ros::NodeHandle nh_priv,
std::string &  name 
)
inline

Definition at line 45 of file random_walker_controller.hpp.

kobuki::RandomWalkerController::~RandomWalkerController ( )
inline

Definition at line 62 of file random_walker_controller.hpp.

Member Function Documentation

void kobuki::RandomWalkerController::bumperEventCB ( const kobuki_msgs::BumperEventConstPtr  msg)
private

Trigger direction change and LED blink, when a bumper is pressed.

Parameters
msgbumper event

Definition at line 202 of file random_walker_controller.hpp.

void kobuki::RandomWalkerController::cliffEventCB ( const kobuki_msgs::CliffEventConstPtr  msg)
private

Trigger direction change and LED blink, when a cliff is detected.

Parameters
msgcliff event

Definition at line 265 of file random_walker_controller.hpp.

void kobuki::RandomWalkerController::disableCB ( const std_msgs::EmptyConstPtr  msg)
private

ROS logging output for disabling the controller.

Parameters
msgincoming topic message

Definition at line 190 of file random_walker_controller.hpp.

void kobuki::RandomWalkerController::enableCB ( const std_msgs::EmptyConstPtr  msg)
private

ROS logging output for enabling the controller.

Parameters
msgincoming topic message

Definition at line 178 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::init ( )
inlinevirtual

Set-up necessary publishers/subscribers and initialise time

Returns
true, if successful

Implements yocs::Controller.

Definition at line 68 of file random_walker_controller.hpp.

void kobuki::RandomWalkerController::spin ( )
virtual

Publishes velocity commands and triggers the LEDs.

Reimplemented from yocs::Controller.

Definition at line 379 of file random_walker_controller.hpp.

void kobuki::RandomWalkerController::wheelDropEventCB ( const kobuki_msgs::WheelDropEventConstPtr  msg)
private

Trigger stopping and LED blink, when a wheel drop is detected.

Parameters
msgwheel drop event

Definition at line 325 of file random_walker_controller.hpp.

Member Data Documentation

bool kobuki::RandomWalkerController::bumper_center_pressed_
private

Flag for center bumper's state.

Definition at line 115 of file random_walker_controller.hpp.

ros::Subscriber kobuki::RandomWalkerController::bumper_event_subscriber_
private

Subscribers.

Definition at line 105 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::bumper_left_pressed_
private

Flag for left bumper's state.

Definition at line 113 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::bumper_right_pressed_
private

Flag for right bumper's state.

Definition at line 117 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::change_direction_
private

Flag for changing direction.

Definition at line 109 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::cliff_center_detected_
private

Flag for center cliff sensor's state.

Definition at line 121 of file random_walker_controller.hpp.

ros::Subscriber kobuki::RandomWalkerController::cliff_event_subscriber_
private

Definition at line 105 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::cliff_left_detected_
private

Flag for left cliff sensor's state.

Definition at line 119 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::cliff_right_detected_
private

Flag for right cliff sensor's state.

Definition at line 123 of file random_walker_controller.hpp.

ros::Publisher kobuki::RandomWalkerController::cmd_vel_publisher_
private

Publishers.

Definition at line 107 of file random_walker_controller.hpp.

ros::Subscriber kobuki::RandomWalkerController::disable_controller_subscriber_
private

Definition at line 103 of file random_walker_controller.hpp.

ros::Subscriber kobuki::RandomWalkerController::enable_controller_subscriber_
private

Subscribers.

Definition at line 103 of file random_walker_controller.hpp.

ros::Publisher kobuki::RandomWalkerController::led1_publisher_
private

Definition at line 107 of file random_walker_controller.hpp.

ros::Publisher kobuki::RandomWalkerController::led2_publisher_
private

Definition at line 107 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::led_bumper_on_
private

Flag for bumper LED's state.

Definition at line 129 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::led_cliff_on_
private

Flag for cliff sensor LED's state.

Definition at line 131 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::led_wheel_drop_on_
private

Flag for wheel drop sensor LED's state.

Definition at line 133 of file random_walker_controller.hpp.

std::string kobuki::RandomWalkerController::name_
private

Node(let) name.

Definition at line 101 of file random_walker_controller.hpp.

ros::NodeHandle kobuki::RandomWalkerController::nh_priv_
private

Private ROS handle.

Definition at line 99 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::stop_
private

Flag for stopping.

Definition at line 111 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::turning_
private

Flag for turning state.

Definition at line 145 of file random_walker_controller.hpp.

int kobuki::RandomWalkerController::turning_direction_
private

Randomly chosen turning direction.

Definition at line 141 of file random_walker_controller.hpp.

ros::Duration kobuki::RandomWalkerController::turning_duration_
private

Randomly chosen turning duration.

Definition at line 139 of file random_walker_controller.hpp.

ros::Time kobuki::RandomWalkerController::turning_start_
private

Start time of turning.

Definition at line 143 of file random_walker_controller.hpp.

double kobuki::RandomWalkerController::vel_ang_
private

Angular velocity for rotating.

Definition at line 137 of file random_walker_controller.hpp.

double kobuki::RandomWalkerController::vel_lin_
private

Linear velocity for moving straight.

Definition at line 135 of file random_walker_controller.hpp.

ros::Subscriber kobuki::RandomWalkerController::wheel_drop_event_subscriber_
private

Definition at line 105 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::wheel_drop_left_detected_
private

Flag for left wheel drop sensor's state.

Definition at line 125 of file random_walker_controller.hpp.

bool kobuki::RandomWalkerController::wheel_drop_right_detected_
private

Flag for right wheel drop sensor's state.

Definition at line 127 of file random_walker_controller.hpp.


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


kobuki_random_walker
Author(s): Marcus Liebhardt
autogenerated on Mon Jun 10 2019 13:45:06