$search

pr2_wrappers::BaseClient Class Reference

#include <base_client.h>

List of all members.

Public Member Functions

void applyTwist (const geometry_msgs::TwistStamped &twist)
 Commands a straight-up movement command to the base.
 BaseClient (ros::NodeHandle &nh, const ros::Duration &timeout, tf::TransformListener *tfl=0)
 Initialization.
void cancelGoals ()
 Deprecated...
void clearLocalCostmap ()
bool hasGoal ()
 Returns true if the nav stack is active.
void sendNavGoal (const geometry_msgs::PoseStamped &ps)
 ~BaseClient ()

Private Member Functions

void moveBaseStatusCB (const actionlib_msgs::GoalStatusArrayConstPtr &array)
 Callback for receiving status of move base client.
void publishTwist (const ros::TimerEvent &e)
 Publish last stored twist message at each timer interval; has a (very CRITICAL) time-out for safety.

Private Attributes

geometry_msgs::TwistStamped base_cmd_
ros::Publisher cmd_vel_pub_
 Publisher handle; default topic will be "cmd_vel".
bool delete_tfl_
 A flag to determine whether to delete the TF listener on destruction.
btVector3 last_angular_
btVector3 last_linear_
object_manipulator::ServiceWrapper
< std_srvs::Empty > 
local_costmap_reset_srv_
bool move_base_active_
 A bool representing if the move_base action server is active.
object_manipulator::ActionWrapper
< move_base_msgs::MoveBaseAction
move_base_client_
 A actionlib client to the move_base action server.
ros::NodeHandle nh_
 The node handle we'll be using.
ros::Timer publish_timer_
ros::Subscriber sub_nav_status_
 A subscriber for listening to the status of the nav stack.
tf::TransformListenertfl_
 TF listener pointer; a new one only gets created if one is not passed in on construction.
ros::Duration timeout_

Detailed Description

Definition at line 50 of file base_client.h.


Constructor & Destructor Documentation

pr2_wrappers::BaseClient::BaseClient ( ros::NodeHandle nh,
const ros::Duration timeout,
tf::TransformListener tfl = 0 
)

Initialization.

Definition at line 37 of file base_client.cpp.

pr2_wrappers::BaseClient::~BaseClient (  ) 

Definition at line 66 of file base_client.cpp.


Member Function Documentation

void pr2_wrappers::BaseClient::applyTwist ( const geometry_msgs::TwistStamped twist  ) 

Commands a straight-up movement command to the base.

Stores a new command to send to the base.

Definition at line 110 of file base_client.cpp.

void pr2_wrappers::BaseClient::cancelGoals (  ) 

Deprecated...

Sends a "cancel all goals" request to the move_base server.

Tells the nav stack to STOP!

Definition at line 85 of file base_client.cpp.

void pr2_wrappers::BaseClient::clearLocalCostmap (  ) 

Definition at line 155 of file base_client.cpp.

bool pr2_wrappers::BaseClient::hasGoal (  ) 

Returns true if the nav stack is active.

Public method to check if the action server has a goal.

Definition at line 72 of file base_client.cpp.

void pr2_wrappers::BaseClient::moveBaseStatusCB ( const actionlib_msgs::GoalStatusArrayConstPtr array  )  [private]

Callback for receiving status of move base client.

Callback for receiving status of move_base_client.

Definition at line 92 of file base_client.cpp.

void pr2_wrappers::BaseClient::publishTwist ( const ros::TimerEvent e  )  [private]

Publish last stored twist message at each timer interval; has a (very CRITICAL) time-out for safety.

Publishes the most recent twist message to the base controller.

Definition at line 117 of file base_client.cpp.

void pr2_wrappers::BaseClient::sendNavGoal ( const geometry_msgs::PoseStamped ps  ) 

Definition at line 143 of file base_client.cpp.


Member Data Documentation

Definition at line 76 of file base_client.h.

Publisher handle; default topic will be "cmd_vel".

Definition at line 57 of file base_client.h.

A flag to determine whether to delete the TF listener on destruction.

Definition at line 63 of file base_client.h.

Definition at line 78 of file base_client.h.

Definition at line 77 of file base_client.h.

Definition at line 85 of file base_client.h.

A bool representing if the move_base action server is active.

Definition at line 73 of file base_client.h.

A actionlib client to the move_base action server.

Definition at line 69 of file base_client.h.

The node handle we'll be using.

Definition at line 54 of file base_client.h.

Definition at line 82 of file base_client.h.

A subscriber for listening to the status of the nav stack.

Definition at line 66 of file base_client.h.

TF listener pointer; a new one only gets created if one is not passed in on construction.

Definition at line 60 of file base_client.h.

Definition at line 80 of file base_client.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pr2_wrappers
Author(s): Adam Leeper
autogenerated on Tue Mar 5 14:28:03 2013