#include <GoDock.h>
Public Member Functions | |
void | batteryCallback (const roomba_500_series::BatteryConstPtr &bat) |
Battery callback. | |
void | goalCallback (const roomba_500_series::GoDockGoalConstPtr &goal) |
Goal callback. | |
GoDockAction (std::string name) | |
Constructor. | |
void | irCallback (const roomba_500_series::IRCharacterConstPtr &ir) |
IR callback. | |
~GoDockAction () | |
Destructor. | |
Protected Attributes | |
std::string | action_name_ |
Action name. | |
actionlib::SimpleActionServer < roomba_500_series::GoDockAction > | as_ |
Action Server. | |
roomba_500_series::GoDockFeedback | feedback_ |
Message used to published feedback. | |
ros::NodeHandle | nh_ |
Node handle. | |
roomba_500_series::GoDockResult | result_ |
Message used to published result. | |
Private Member Functions | |
void | sendCmdVel (float linear, float angular) |
Send velocity commands. | |
Private Attributes | |
ros::Subscriber | bat_sub_ |
Subscriver for battery, to check if the Roomba is docked. | |
ros::Publisher | cmd_vel_pub_ |
Publisher for cmd_vel, to move the robot. | |
bool | dock_ |
Whether the Roomba is docked or not. | |
roomba_500_series::IRCharacter | ir_character_ |
IR char. | |
ros::Subscriber | ir_sub_ |
Subscriver for ir_char, to read the dock beacon info. |
GoDockAction::GoDockAction | ( | std::string | name | ) |
Destructor.
Definition at line 47 of file GoDock.cpp.
void GoDockAction::batteryCallback | ( | const roomba_500_series::BatteryConstPtr & | bat | ) |
Battery callback.
This function is a callback for battery.
bat | Roomba battery message. |
Definition at line 107 of file GoDock.cpp.
void GoDockAction::goalCallback | ( | const roomba_500_series::GoDockGoalConstPtr & | goal | ) |
Goal callback.
This function is a callback for goals received.
goal | New goal. |
Definition at line 52 of file GoDock.cpp.
void GoDockAction::irCallback | ( | const roomba_500_series::IRCharacterConstPtr & | ir | ) |
IR callback.
This function is a callback for ir_char.
ir | Roomba ir message. |
Definition at line 100 of file GoDock.cpp.
void GoDockAction::sendCmdVel | ( | float | linear, |
float | angular | ||
) | [private] |
Send velocity commands.
This function allows to send velocity commands directly to the Roomba driver. Notice that if you are using move_base to move your Roomba you must cancel any existing goals or else move_base will try to move the Roomba while it tries to dock.
linear | Linear velocity. |
angular | Angular velocity. |
Definition at line 112 of file GoDock.cpp.
std::string GoDockAction::action_name_ [protected] |
ros::Subscriber GoDockAction::bat_sub_ [private] |
ros::Publisher GoDockAction::cmd_vel_pub_ [private] |
bool GoDockAction::dock_ [private] |
ros::Subscriber GoDockAction::ir_sub_ [private] |
ros::NodeHandle GoDockAction::nh_ [protected] |
roomba_500_series::GoDockResult GoDockAction::result_ [protected] |