#include <base_client.h>
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) |
void | sendPoseEstimate (const geometry_msgs::PoseWithCovarianceStamped &ps) |
~BaseClient () | |
Private Member Functions | |
void | moveBaseResultCB (const move_base_msgs::MoveBaseActionResultConstPtr &result) |
Callback for receiving results of move base client. | |
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 for twist messages. | |
bool | delete_tfl_ |
A flag to determine whether to delete the TF listener on destruction. | |
tf::Vector3 | last_angular_ |
tf::Vector3 | 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::Publisher | pose_estimate_pub_ |
Publisher for initial pose estimates; default topic is "/initialpose". | |
ros::Timer | publish_timer_ |
ros::Subscriber | sub_nav_result_ |
A subscriber for the result of the nav stack. | |
ros::Subscriber | sub_nav_status_ |
A subscriber for listening to the status of the nav stack. | |
tf::TransformListener * | tfl_ |
TF listener pointer; a new one only gets created if one is not passed in on construction. | |
ros::Duration | timeout_ |
Definition at line 51 of file base_client.h.
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.
Definition at line 72 of file base_client.cpp.
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 144 of file base_client.cpp.
Deprecated...
Sends a "cancel all goals" request to the move_base server.
Tells the nav stack to STOP!
Definition at line 91 of file base_client.cpp.
Definition at line 193 of file base_client.cpp.
Returns true if the nav stack is active.
Public method to check if the action server has a goal.
Definition at line 78 of file base_client.cpp.
void pr2_wrappers::BaseClient::moveBaseResultCB | ( | const move_base_msgs::MoveBaseActionResultConstPtr & | result | ) | [private] |
Callback for receiving results of move base client.
Callback for receiving status of move_base_client.
Definition at line 98 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 123 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 151 of file base_client.cpp.
void pr2_wrappers::BaseClient::sendNavGoal | ( | const geometry_msgs::PoseStamped & | ps | ) |
Definition at line 177 of file base_client.cpp.
void pr2_wrappers::BaseClient::sendPoseEstimate | ( | const geometry_msgs::PoseWithCovarianceStamped & | ps | ) |
Definition at line 187 of file base_client.cpp.
geometry_msgs::TwistStamped pr2_wrappers::BaseClient::base_cmd_ [private] |
Definition at line 83 of file base_client.h.
Publisher for twist messages.
Definition at line 58 of file base_client.h.
bool pr2_wrappers::BaseClient::delete_tfl_ [private] |
A flag to determine whether to delete the TF listener on destruction.
Definition at line 67 of file base_client.h.
tf::Vector3 pr2_wrappers::BaseClient::last_angular_ [private] |
Definition at line 85 of file base_client.h.
tf::Vector3 pr2_wrappers::BaseClient::last_linear_ [private] |
Definition at line 84 of file base_client.h.
object_manipulator::ServiceWrapper<std_srvs::Empty> pr2_wrappers::BaseClient::local_costmap_reset_srv_ [private] |
Definition at line 92 of file base_client.h.
A bool representing if the move_base action server is active.
Definition at line 80 of file base_client.h.
object_manipulator::ActionWrapper<move_base_msgs::MoveBaseAction> pr2_wrappers::BaseClient::move_base_client_ [private] |
A actionlib client to the move_base action server.
Definition at line 76 of file base_client.h.
ros::NodeHandle pr2_wrappers::BaseClient::nh_ [private] |
The node handle we'll be using.
Definition at line 55 of file base_client.h.
Publisher for initial pose estimates; default topic is "/initialpose".
Definition at line 61 of file base_client.h.
Definition at line 89 of file base_client.h.
A subscriber for the result of the nav stack.
Definition at line 73 of file base_client.h.
A subscriber for listening to the status of the nav stack.
Definition at line 70 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 64 of file base_client.h.
Definition at line 87 of file base_client.h.