Public Member Functions | Private Member Functions | Private Attributes | List of all members
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>

Public Member Functions

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

Private Member Functions

bool clearCostmapsService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
 A service call that clears the costmaps of obstacles. More...
 
void clearCostmapWindows (double size_x, double size_y)
 Clears obstacles within a window around the robot. More...
 
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. More...
 
bool loadRecoveryBehaviors (ros::NodeHandle node)
 Load the recovery behaviors for the navigation stack from the parameter server. More...
 
bool makePlan (const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
 Make a new global plan. More...
 
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. More...
 
void planThread ()
 
void publishZeroVelocity ()
 Publishes a velocity command of zero to the base. More...
 
void reconfigureCB (move_base::MoveBaseConfig &config, uint32_t level)
 
void resetState ()
 Reset the state of the move_base action and send a zero velocity command to the base. More...
 
void wakePlanner (const ros::TimerEvent &event)
 This is used to wake the planner at periodic intervals. More...
 

Private Attributes

ros::Publisher action_goal_pub_
 
MoveBaseActionServeras_
 
pluginlib::ClassLoader< nav_core::BaseGlobalPlannerbgp_loader_
 
pluginlib::ClassLoader< nav_core::BaseLocalPlannerblp_loader_
 
bool c_freq_change_
 
double circumscribed_radius_
 
ros::ServiceServer clear_costmaps_srv_
 
double clearing_radius_
 
bool clearing_rotation_allowed_
 
boost::recursive_mutex configuration_mutex_
 
double conservative_reset_dist_
 
costmap_2d::Costmap2DROScontroller_costmap_ros_
 
double controller_frequency_
 
double controller_patience_
 
std::vector< geometry_msgs::PoseStamped > * controller_plan_
 
ros::Publisher current_goal_pub_
 
move_base::MoveBaseConfig default_config_
 
dynamic_reconfigure::Server< move_base::MoveBaseConfig > * dsrv_
 
std::string global_frame_
 
tf::Stamped< tf::Poseglobal_pose_
 
ros::Subscriber goal_sub_
 
double inscribed_radius_
 
move_base::MoveBaseConfig last_config_
 
ros::Time last_oscillation_reset_
 
ros::Time last_valid_control_
 
ros::Time last_valid_plan_
 
std::vector< geometry_msgs::PoseStamped > * latest_plan_
 
ros::ServiceServer make_plan_srv_
 
int32_t max_planning_retries_
 
bool new_global_plan_
 
double oscillation_distance_
 
geometry_msgs::PoseStamped oscillation_pose_
 
double oscillation_timeout_
 
bool p_freq_change_
 
boost::shared_ptr< nav_core::BaseGlobalPlannerplanner_
 
boost::condition_variable_any planner_cond_
 
costmap_2d::Costmap2DROSplanner_costmap_ros_
 
double planner_frequency_
 
geometry_msgs::PoseStamped planner_goal_
 
boost::recursive_mutex planner_mutex_
 
double planner_patience_
 
std::vector< geometry_msgs::PoseStamped > * planner_plan_
 
boost::thread * planner_thread_
 
uint32_t planning_retries_
 
bool recovery_behavior_enabled_
 
std::vector< std::string > recovery_behavior_names_
 
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
 
unsigned int recovery_index_
 
pluginlib::ClassLoader< nav_core::RecoveryBehaviorrecovery_loader_
 
ros::Publisher recovery_status_pub_
 
RecoveryTrigger recovery_trigger_
 
std::string robot_base_frame_
 
bool runPlanner_
 
bool setup_
 
bool shutdown_costmaps_
 
MoveBaseState state_
 
boost::shared_ptr< nav_core::BaseLocalPlannertc_
 
tf::TransformListenertf_
 
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 83 of file move_base.h.

Constructor & Destructor Documentation

move_base::MoveBase::MoveBase ( tf::TransformListener tf)

Constructor for the actions.

Parameters
nameThe name of the action
tfA reference to a TransformListener

Definition at line 49 of file move_base.cpp.

move_base::MoveBase::~MoveBase ( )
virtual

Destructor - Cleans up.

Definition at line 434 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
reqThe service request
respThe service response
Returns
True if the service call succeeds, false otherwise

Definition at line 330 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_xThe x size of the window
size_yThe y size of the window

Definition at line 275 of file move_base.cpp.

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

Definition at line 787 of file move_base.cpp.

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

Definition at line 641 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
goalA reference to the goal to pursue
global_planA reference to the global plan being used
Returns
True if processing of the goal is done, false otherwise

Definition at line 792 of file move_base.cpp.

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

Definition at line 266 of file move_base.cpp.

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

Definition at line 530 of file move_base.cpp.

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

Definition at line 500 of file move_base.cpp.

void move_base::MoveBase::loadDefaultRecoveryBehaviors ( )
private

Loads the default recovery behaviors for the navigation stack.

Definition at line 1096 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
nodeThe ros::NodeHandle to be used for loading parameters
Returns
True if the recovery behaviors were loaded successfully, false otherwise

Definition at line 1010 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
goalThe goal to plan to
planWill be filled in with the plan made by the planner
Returns
True if planning succeeds, false otherwise

Definition at line 461 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
reqThe goal request
respThe plan request
Returns
True if planning succeeded, false otherwise

Definition at line 341 of file move_base.cpp.

void move_base::MoveBase::planThread ( )
private

Definition at line 559 of file move_base.cpp.

void move_base::MoveBase::publishZeroVelocity ( )
private

Publishes a velocity command of zero to the base.

Definition at line 492 of file move_base.cpp.

void move_base::MoveBase::reconfigureCB ( move_base::MoveBaseConfig &  config,
uint32_t  level 
)
private

Definition at line 176 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 1137 of file move_base.cpp.

void move_base::MoveBase::wakePlanner ( const ros::TimerEvent event)
private

This is used to wake the planner at periodic intervals.

Definition at line 553 of file move_base.cpp.

Member Data Documentation

ros::Publisher move_base::MoveBase::action_goal_pub_
private

Definition at line 196 of file move_base.h.

MoveBaseActionServer* move_base::MoveBase::as_
private

Definition at line 178 of file move_base.h.

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

Definition at line 207 of file move_base.h.

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

Definition at line 208 of file move_base.h.

bool move_base::MoveBase::c_freq_change_
private

Definition at line 231 of file move_base.h.

double move_base::MoveBase::circumscribed_radius_
private

Definition at line 191 of file move_base.h.

ros::ServiceServer move_base::MoveBase::clear_costmaps_srv_
private

Definition at line 198 of file move_base.h.

double move_base::MoveBase::clearing_radius_
private

Definition at line 195 of file move_base.h.

bool move_base::MoveBase::clearing_rotation_allowed_
private

Definition at line 199 of file move_base.h.

boost::recursive_mutex move_base::MoveBase::configuration_mutex_
private

Definition at line 224 of file move_base.h.

double move_base::MoveBase::conservative_reset_dist_
private

Definition at line 195 of file move_base.h.

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

Definition at line 181 of file move_base.h.

double move_base::MoveBase::controller_frequency_
private

Definition at line 191 of file move_base.h.

double move_base::MoveBase::controller_patience_
private

Definition at line 192 of file move_base.h.

std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::controller_plan_
private

Definition at line 214 of file move_base.h.

ros::Publisher move_base::MoveBase::current_goal_pub_
private

Definition at line 196 of file move_base.h.

move_base::MoveBaseConfig move_base::MoveBase::default_config_
private

Definition at line 230 of file move_base.h.

dynamic_reconfigure::Server<move_base::MoveBaseConfig>* move_base::MoveBase::dsrv_
private

Definition at line 225 of file move_base.h.

std::string move_base::MoveBase::global_frame_
private

Definition at line 184 of file move_base.h.

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

Definition at line 190 of file move_base.h.

ros::Subscriber move_base::MoveBase::goal_sub_
private

Definition at line 197 of file move_base.h.

double move_base::MoveBase::inscribed_radius_
private

Definition at line 191 of file move_base.h.

move_base::MoveBaseConfig move_base::MoveBase::last_config_
private

Definition at line 229 of file move_base.h.

ros::Time move_base::MoveBase::last_oscillation_reset_
private

Definition at line 205 of file move_base.h.

ros::Time move_base::MoveBase::last_valid_control_
private

Definition at line 205 of file move_base.h.

ros::Time move_base::MoveBase::last_valid_plan_
private

Definition at line 205 of file move_base.h.

std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::latest_plan_
private

Definition at line 213 of file move_base.h.

ros::ServiceServer move_base::MoveBase::make_plan_srv_
private

Definition at line 198 of file move_base.h.

int32_t move_base::MoveBase::max_planning_retries_
private

Definition at line 193 of file move_base.h.

bool move_base::MoveBase::new_global_plan_
private

Definition at line 232 of file move_base.h.

double move_base::MoveBase::oscillation_distance_
private

Definition at line 200 of file move_base.h.

geometry_msgs::PoseStamped move_base::MoveBase::oscillation_pose_
private

Definition at line 206 of file move_base.h.

double move_base::MoveBase::oscillation_timeout_
private

Definition at line 200 of file move_base.h.

bool move_base::MoveBase::p_freq_change_
private

Definition at line 231 of file move_base.h.

boost::shared_ptr<nav_core::BaseGlobalPlanner> move_base::MoveBase::planner_
private

Definition at line 183 of file move_base.h.

boost::condition_variable_any move_base::MoveBase::planner_cond_
private

Definition at line 219 of file move_base.h.

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

Definition at line 181 of file move_base.h.

double move_base::MoveBase::planner_frequency_
private

Definition at line 191 of file move_base.h.

geometry_msgs::PoseStamped move_base::MoveBase::planner_goal_
private

Definition at line 220 of file move_base.h.

boost::recursive_mutex move_base::MoveBase::planner_mutex_
private

Definition at line 218 of file move_base.h.

double move_base::MoveBase::planner_patience_
private

Definition at line 192 of file move_base.h.

std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::planner_plan_
private

Definition at line 212 of file move_base.h.

boost::thread* move_base::MoveBase::planner_thread_
private

Definition at line 221 of file move_base.h.

uint32_t move_base::MoveBase::planning_retries_
private

Definition at line 194 of file move_base.h.

bool move_base::MoveBase::recovery_behavior_enabled_
private

Definition at line 199 of file move_base.h.

std::vector<std::string> move_base::MoveBase::recovery_behavior_names_
private

Definition at line 187 of file move_base.h.

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

Definition at line 186 of file move_base.h.

unsigned int move_base::MoveBase::recovery_index_
private

Definition at line 188 of file move_base.h.

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

Definition at line 209 of file move_base.h.

ros::Publisher move_base::MoveBase::recovery_status_pub_
private

Definition at line 196 of file move_base.h.

RecoveryTrigger move_base::MoveBase::recovery_trigger_
private

Definition at line 203 of file move_base.h.

std::string move_base::MoveBase::robot_base_frame_
private

Definition at line 184 of file move_base.h.

bool move_base::MoveBase::runPlanner_
private

Definition at line 217 of file move_base.h.

bool move_base::MoveBase::setup_
private

Definition at line 231 of file move_base.h.

bool move_base::MoveBase::shutdown_costmaps_
private

Definition at line 199 of file move_base.h.

MoveBaseState move_base::MoveBase::state_
private

Definition at line 202 of file move_base.h.

boost::shared_ptr<nav_core::BaseLocalPlanner> move_base::MoveBase::tc_
private

Definition at line 180 of file move_base.h.

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

Definition at line 176 of file move_base.h.

ros::Publisher move_base::MoveBase::vel_pub_
private

Definition at line 196 of file move_base.h.


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


move_base
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:06:13