move_base::MoveBase Class Reference

A class that uses the actionlib::ActionServer interface that moves the robot base to a goal location. More...

#include <move_base.h>

List of all members.

Public Member Functions

bool executeCycle (geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &global_plan)
 Performs a control cycle.
 MoveBase (std::string name, tf::TransformListener &tf)
 Constructor for the actions.
virtual ~MoveBase ()
 Destructor - Cleans up.

Private Member Functions

bool clearCostmapsService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
 A service call that clears the costmaps of obstacles.
void clearCostmapWindows (double size_x, double size_y)
 Clears obstacles within a window around the robot.
bool clearUnknownService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
 A service call that clears unknown space in the robot's immediate area.
double distance (const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
void executeCb (const move_base_msgs::MoveBaseGoalConstPtr &move_base_goal)
void goalCB (const geometry_msgs::PoseStamped::ConstPtr &goal)
geometry_msgs::PoseStamped goalToGlobalFrame (const geometry_msgs::PoseStamped &goal_pose_msg)
bool isQuaternionValid (const geometry_msgs::Quaternion &q)
void loadDefaultRecoveryBehaviors ()
 Loads the default recovery behaviors for the navigation stack.
bool loadRecoveryBehaviors (ros::NodeHandle node)
 Load the recovery behaviors for the navigation stack from the parameter server.
bool makePlan (const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
 Make a new global plan.
bool planService (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
 A service call that can be made when the action is inactive that will return a plan.
void publishZeroVelocity ()
 Publishes a velocity command of zero to the base.
void resetState ()
 Reset the state of the move_base action and send a zero velocity command to the base.

Private Attributes

ros::Publisher action_goal_pub_
MoveBaseActionServeras_
pluginlib::ClassLoader
< nav_core::BaseGlobalPlanner > 
bgp_loader_
pluginlib::ClassLoader
< nav_core::BaseLocalPlanner > 
blp_loader_
double circumscribed_radius_
ros::ServiceServer clear_costmaps_srv_
ros::ServiceServer clear_unknown_srv_
double clearing_radius_
bool clearing_roatation_allowed_
double conservative_reset_dist_
costmap_2d::Costmap2DROS * controller_costmap_ros_
double controller_frequency_
double controller_patience_
ros::Publisher current_goal_pub_
std::string global_frame_
tf::Stamped< tf::Pose > global_pose_
ros::Subscriber goal_sub_
double inscribed_radius_
ros::Time last_oscillation_reset_
ros::Time last_valid_control_
ros::Time last_valid_plan_
ros::ServiceServer make_plan_srv_
double oscillation_distance_
geometry_msgs::PoseStamped oscillation_pose_
double oscillation_timeout_
nav_core::BaseGlobalPlanner * planner_
costmap_2d::Costmap2DROS * planner_costmap_ros_
double planner_patience_
bool recovery_behavior_enabled_
std::vector< boost::shared_ptr
< nav_core::RecoveryBehavior > > 
recovery_behaviors_
unsigned int recovery_index_
pluginlib::ClassLoader
< nav_core::RecoveryBehavior > 
recovery_loader_
RecoveryTrigger recovery_trigger_
std::string robot_base_frame_
bool shutdown_costmaps_
MoveBaseState state_
nav_core::BaseLocalPlanner * tc_
tf::TransformListener & tf_
ros::Publisher vel_pub_

Detailed Description

A class that uses the actionlib::ActionServer interface that moves the robot base to a goal location.

Definition at line 79 of file move_base.h.


Constructor & Destructor Documentation

move_base::MoveBase::MoveBase ( std::string  name,
tf::TransformListener &  tf 
)

Constructor for the actions.

Parameters:
name The name of the action
tf A reference to a TransformListener

Definition at line 40 of file move_base.cpp.

move_base::MoveBase::~MoveBase (  )  [virtual]

Destructor - Cleans up.

Definition at line 330 of file move_base.cpp.


Member Function Documentation

bool move_base::MoveBase::clearCostmapsService ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  resp 
) [private]

A service call that clears the costmaps of obstacles.

Parameters:
req The service request
resp The service response
Returns:
True if the service call succeeds, false otherwise

Definition at line 260 of file move_base.cpp.

void move_base::MoveBase::clearCostmapWindows ( double  size_x,
double  size_y 
) [private]

Clears obstacles within a window around the robot.

Parameters:
size_x The x size of the window
size_y The y size of the window

Definition at line 198 of file move_base.cpp.

bool move_base::MoveBase::clearUnknownService ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  resp 
) [private]

A service call that clears unknown space in the robot's immediate area.

Parameters:
req The service request
resp The service response
Returns:
True if the service call succeeds, false otherwise

Definition at line 253 of file move_base.cpp.

double move_base::MoveBase::distance ( const geometry_msgs::PoseStamped &  p1,
const geometry_msgs::PoseStamped &  p2 
) [private]

Definition at line 546 of file move_base.cpp.

void move_base::MoveBase::executeCb ( const move_base_msgs::MoveBaseGoalConstPtr &  move_base_goal  )  [private]

Definition at line 437 of file move_base.cpp.

bool move_base::MoveBase::executeCycle ( geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  global_plan 
)

Performs a control cycle.

Parameters:
goal A reference to the goal to pursue
global_plan A reference to the global plan being used
Returns:
True if processing of the goal is done, false otherwise

Definition at line 552 of file move_base.cpp.

void move_base::MoveBase::goalCB ( const geometry_msgs::PoseStamped::ConstPtr &  goal  )  [private]

Definition at line 189 of file move_base.cpp.

geometry_msgs::PoseStamped move_base::MoveBase::goalToGlobalFrame ( const geometry_msgs::PoseStamped &  goal_pose_msg  )  [private]

Definition at line 413 of file move_base.cpp.

bool move_base::MoveBase::isQuaternionValid ( const geometry_msgs::Quaternion &  q  )  [private]

Definition at line 383 of file move_base.cpp.

void move_base::MoveBase::loadDefaultRecoveryBehaviors (  )  [private]

Loads the default recovery behaviors for the navigation stack.

Definition at line 799 of file move_base.cpp.

bool move_base::MoveBase::loadRecoveryBehaviors ( ros::NodeHandle  node  )  [private]

Load the recovery behaviors for the navigation stack from the parameter server.

Parameters:
node The ros::NodeHandle to be used for loading parameters
Returns:
True if the recovery behaviors were loaded successfully, false otherwise

Definition at line 714 of file move_base.cpp.

bool move_base::MoveBase::makePlan ( const geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
) [private]

Make a new global plan.

Parameters:
goal The goal to plan to
plan Will be filled in with the plan made by the planner
Returns:
True if planning succeeds, false otherwise

Definition at line 349 of file move_base.cpp.

bool move_base::MoveBase::planService ( nav_msgs::GetPlan::Request &  req,
nav_msgs::GetPlan::Response &  resp 
) [private]

A service call that can be made when the action is inactive that will return a plan.

Parameters:
req The goal request
resp The plan request
Returns:
True if planning succeeded, false otherwise

Definition at line 267 of file move_base.cpp.

void move_base::MoveBase::publishZeroVelocity (  )  [private]

Publishes a velocity command of zero to the base.

Definition at line 374 of file move_base.cpp.

void move_base::MoveBase::resetState (  )  [private]

Reset the state of the move_base action and send a zero velocity command to the base.

Definition at line 832 of file move_base.cpp.


Member Data Documentation

ros::Publisher move_base::MoveBase::action_goal_pub_ [private]

Definition at line 191 of file move_base.h.

Definition at line 176 of file move_base.h.

pluginlib::ClassLoader<nav_core::BaseGlobalPlanner> move_base::MoveBase::bgp_loader_ [private]

Definition at line 202 of file move_base.h.

pluginlib::ClassLoader<nav_core::BaseLocalPlanner> move_base::MoveBase::blp_loader_ [private]

Definition at line 203 of file move_base.h.

Definition at line 188 of file move_base.h.

ros::ServiceServer move_base::MoveBase::clear_costmaps_srv_ [private]

Definition at line 193 of file move_base.h.

ros::ServiceServer move_base::MoveBase::clear_unknown_srv_ [private]

Definition at line 193 of file move_base.h.

Definition at line 190 of file move_base.h.

Definition at line 194 of file move_base.h.

Definition at line 190 of file move_base.h.

costmap_2d::Costmap2DROS * move_base::MoveBase::controller_costmap_ros_ [private]

Definition at line 179 of file move_base.h.

Definition at line 188 of file move_base.h.

Definition at line 189 of file move_base.h.

ros::Publisher move_base::MoveBase::current_goal_pub_ [private]

Definition at line 191 of file move_base.h.

std::string move_base::MoveBase::global_frame_ [private]

Definition at line 182 of file move_base.h.

tf::Stamped<tf::Pose> move_base::MoveBase::global_pose_ [private]

Definition at line 187 of file move_base.h.

ros::Subscriber move_base::MoveBase::goal_sub_ [private]

Definition at line 192 of file move_base.h.

Definition at line 188 of file move_base.h.

Definition at line 200 of file move_base.h.

Definition at line 200 of file move_base.h.

Definition at line 200 of file move_base.h.

ros::ServiceServer move_base::MoveBase::make_plan_srv_ [private]

Definition at line 193 of file move_base.h.

Definition at line 195 of file move_base.h.

geometry_msgs::PoseStamped move_base::MoveBase::oscillation_pose_ [private]

Definition at line 201 of file move_base.h.

Definition at line 195 of file move_base.h.

nav_core::BaseGlobalPlanner* move_base::MoveBase::planner_ [private]

Definition at line 181 of file move_base.h.

costmap_2d::Costmap2DROS* move_base::MoveBase::planner_costmap_ros_ [private]

Definition at line 179 of file move_base.h.

Definition at line 189 of file move_base.h.

Definition at line 194 of file move_base.h.

std::vector<boost::shared_ptr<nav_core::RecoveryBehavior> > move_base::MoveBase::recovery_behaviors_ [private]

Definition at line 184 of file move_base.h.

unsigned int move_base::MoveBase::recovery_index_ [private]

Definition at line 185 of file move_base.h.

pluginlib::ClassLoader<nav_core::RecoveryBehavior> move_base::MoveBase::recovery_loader_ [private]

Definition at line 204 of file move_base.h.

Definition at line 198 of file move_base.h.

Definition at line 182 of file move_base.h.

Definition at line 194 of file move_base.h.

Definition at line 197 of file move_base.h.

nav_core::BaseLocalPlanner* move_base::MoveBase::tc_ [private]

Definition at line 178 of file move_base.h.

tf::TransformListener& move_base::MoveBase::tf_ [private]

Definition at line 174 of file move_base.h.

ros::Publisher move_base::MoveBase::vel_pub_ [private]

Definition at line 191 of file move_base.h.


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


move_base
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Jan 11 10:00:55 2013