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)
 Performs a control cycle. More...
 
 MoveBase (tf2_ros::Buffer &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)
 
bool getRobotPose (geometry_msgs::PoseStamped &global_pose, costmap_2d::Costmap2DROS *costmap)
 
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_
 
geometry_msgs::PoseStamped global_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_
 
bool make_plan_add_unreachable_goal_
 
bool make_plan_clear_costmap_
 
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_
 
tf2_ros::Buffertf_
 
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 118 of file move_base.h.

Constructor & Destructor Documentation

◆ MoveBase()

move_base::MoveBase::MoveBase ( tf2_ros::Buffer tf)

Constructor for the actions.

Parameters
nameThe name of the action
tfA reference to a TransformListener

Definition at line 87 of file move_base.cpp.

◆ ~MoveBase()

move_base::MoveBase::~MoveBase ( )
virtual

Destructor - Cleans up.

Definition at line 483 of file move_base.cpp.

Member Function Documentation

◆ clearCostmapsService()

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 375 of file move_base.cpp.

◆ clearCostmapWindows()

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 320 of file move_base.cpp.

◆ distance()

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

Definition at line 833 of file move_base.cpp.

◆ executeCb()

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

Definition at line 687 of file move_base.cpp.

◆ executeCycle()

bool move_base::MoveBase::executeCycle ( geometry_msgs::PoseStamped &  goal)

Performs a control cycle.

Parameters
goalA reference to the goal to pursue
Returns
True if processing of the goal is done, false otherwise

Definition at line 838 of file move_base.cpp.

◆ getRobotPose()

bool move_base::MoveBase::getRobotPose ( geometry_msgs::PoseStamped &  global_pose,
costmap_2d::Costmap2DROS costmap 
)
private

Definition at line 1202 of file move_base.cpp.

◆ goalCB()

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

Definition at line 311 of file move_base.cpp.

◆ goalToGlobalFrame()

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

Definition at line 578 of file move_base.cpp.

◆ isQuaternionValid()

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

Definition at line 548 of file move_base.cpp.

◆ loadDefaultRecoveryBehaviors()

void move_base::MoveBase::loadDefaultRecoveryBehaviors ( )
private

Loads the default recovery behaviors for the navigation stack.

Definition at line 1141 of file move_base.cpp.

◆ loadRecoveryBehaviors()

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 1055 of file move_base.cpp.

◆ makePlan()

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 510 of file move_base.cpp.

◆ planService()

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 386 of file move_base.cpp.

◆ planThread()

void move_base::MoveBase::planThread ( )
private

Definition at line 605 of file move_base.cpp.

◆ publishZeroVelocity()

void move_base::MoveBase::publishZeroVelocity ( )
private

Publishes a velocity command of zero to the base.

Definition at line 540 of file move_base.cpp.

◆ reconfigureCB()

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

Definition at line 218 of file move_base.cpp.

◆ resetState()

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 1182 of file move_base.cpp.

◆ wakePlanner()

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

This is used to wake the planner at periodic intervals.

Definition at line 599 of file move_base.cpp.

Member Data Documentation

◆ action_goal_pub_

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

Definition at line 232 of file move_base.h.

◆ as_

MoveBaseActionServer* move_base::MoveBase::as_
private

Definition at line 214 of file move_base.h.

◆ bgp_loader_

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

Definition at line 244 of file move_base.h.

◆ blp_loader_

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

Definition at line 245 of file move_base.h.

◆ c_freq_change_

bool move_base::MoveBase::c_freq_change_
private

Definition at line 268 of file move_base.h.

◆ circumscribed_radius_

double move_base::MoveBase::circumscribed_radius_
private

Definition at line 227 of file move_base.h.

◆ clear_costmaps_srv_

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

Definition at line 234 of file move_base.h.

◆ clearing_radius_

double move_base::MoveBase::clearing_radius_
private

Definition at line 231 of file move_base.h.

◆ clearing_rotation_allowed_

bool move_base::MoveBase::clearing_rotation_allowed_
private

Definition at line 235 of file move_base.h.

◆ configuration_mutex_

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

Definition at line 261 of file move_base.h.

◆ conservative_reset_dist_

double move_base::MoveBase::conservative_reset_dist_
private

Definition at line 231 of file move_base.h.

◆ controller_costmap_ros_

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

Definition at line 217 of file move_base.h.

◆ controller_frequency_

double move_base::MoveBase::controller_frequency_
private

Definition at line 227 of file move_base.h.

◆ controller_patience_

double move_base::MoveBase::controller_patience_
private

Definition at line 228 of file move_base.h.

◆ controller_plan_

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

Definition at line 251 of file move_base.h.

◆ current_goal_pub_

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

Definition at line 232 of file move_base.h.

◆ default_config_

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

Definition at line 267 of file move_base.h.

◆ dsrv_

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

Definition at line 262 of file move_base.h.

◆ global_frame_

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

Definition at line 220 of file move_base.h.

◆ global_pose_

geometry_msgs::PoseStamped move_base::MoveBase::global_pose_
private

Definition at line 226 of file move_base.h.

◆ goal_sub_

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

Definition at line 233 of file move_base.h.

◆ inscribed_radius_

double move_base::MoveBase::inscribed_radius_
private

Definition at line 227 of file move_base.h.

◆ last_config_

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

Definition at line 266 of file move_base.h.

◆ last_oscillation_reset_

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

Definition at line 242 of file move_base.h.

◆ last_valid_control_

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

Definition at line 242 of file move_base.h.

◆ last_valid_plan_

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

Definition at line 242 of file move_base.h.

◆ latest_plan_

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

Definition at line 250 of file move_base.h.

◆ make_plan_add_unreachable_goal_

bool move_base::MoveBase::make_plan_add_unreachable_goal_
private

Definition at line 236 of file move_base.h.

◆ make_plan_clear_costmap_

bool move_base::MoveBase::make_plan_clear_costmap_
private

Definition at line 236 of file move_base.h.

◆ make_plan_srv_

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

Definition at line 234 of file move_base.h.

◆ max_planning_retries_

int32_t move_base::MoveBase::max_planning_retries_
private

Definition at line 229 of file move_base.h.

◆ new_global_plan_

bool move_base::MoveBase::new_global_plan_
private

Definition at line 269 of file move_base.h.

◆ oscillation_distance_

double move_base::MoveBase::oscillation_distance_
private

Definition at line 237 of file move_base.h.

◆ oscillation_pose_

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

Definition at line 243 of file move_base.h.

◆ oscillation_timeout_

double move_base::MoveBase::oscillation_timeout_
private

Definition at line 237 of file move_base.h.

◆ p_freq_change_

bool move_base::MoveBase::p_freq_change_
private

Definition at line 268 of file move_base.h.

◆ planner_

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

Definition at line 219 of file move_base.h.

◆ planner_cond_

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

Definition at line 256 of file move_base.h.

◆ planner_costmap_ros_

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

Definition at line 217 of file move_base.h.

◆ planner_frequency_

double move_base::MoveBase::planner_frequency_
private

Definition at line 227 of file move_base.h.

◆ planner_goal_

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

Definition at line 257 of file move_base.h.

◆ planner_mutex_

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

Definition at line 255 of file move_base.h.

◆ planner_patience_

double move_base::MoveBase::planner_patience_
private

Definition at line 228 of file move_base.h.

◆ planner_plan_

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

Definition at line 249 of file move_base.h.

◆ planner_thread_

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

Definition at line 258 of file move_base.h.

◆ planning_retries_

uint32_t move_base::MoveBase::planning_retries_
private

Definition at line 230 of file move_base.h.

◆ recovery_behavior_enabled_

bool move_base::MoveBase::recovery_behavior_enabled_
private

Definition at line 235 of file move_base.h.

◆ recovery_behavior_names_

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

Definition at line 223 of file move_base.h.

◆ recovery_behaviors_

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

Definition at line 222 of file move_base.h.

◆ recovery_index_

unsigned int move_base::MoveBase::recovery_index_
private

Definition at line 224 of file move_base.h.

◆ recovery_loader_

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

Definition at line 246 of file move_base.h.

◆ recovery_status_pub_

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

Definition at line 232 of file move_base.h.

◆ recovery_trigger_

RecoveryTrigger move_base::MoveBase::recovery_trigger_
private

Definition at line 240 of file move_base.h.

◆ robot_base_frame_

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

Definition at line 220 of file move_base.h.

◆ runPlanner_

bool move_base::MoveBase::runPlanner_
private

Definition at line 254 of file move_base.h.

◆ setup_

bool move_base::MoveBase::setup_
private

Definition at line 268 of file move_base.h.

◆ shutdown_costmaps_

bool move_base::MoveBase::shutdown_costmaps_
private

Definition at line 235 of file move_base.h.

◆ state_

MoveBaseState move_base::MoveBase::state_
private

Definition at line 239 of file move_base.h.

◆ tc_

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

Definition at line 216 of file move_base.h.

◆ tf_

tf2_ros::Buffer& move_base::MoveBase::tf_
private

Definition at line 212 of file move_base.h.

◆ vel_pub_

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

Definition at line 232 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 Mon Mar 6 2023 03:50:45