A class that uses the actionlib::ActionServer interface that moves the robot base to a goal location.  
 More...
#include <move_base.h>
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 for the actions. 
- Parameters
- 
  
    | name | The name of the action |  | tf | A reference to a TransformListener |  
 
Definition at line 48 of file move_base.cpp.
 
 
  
  | 
        
          | move_base::MoveBase::~MoveBase | ( |  | ) |  |  | virtual | 
 
 
  
  | 
        
          | 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 328 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 273 of file move_base.cpp.
 
 
  
  | 
        
          | double move_base::MoveBase::distance | ( | const geometry_msgs::PoseStamped & | p1, |  
          |  |  | const geometry_msgs::PoseStamped & | p2 |  
          |  | ) |  |  |  | private | 
 
 
  
  | 
        
          | void move_base::MoveBase::executeCb | ( | const move_base_msgs::MoveBaseGoalConstPtr & | move_base_goal | ) |  |  | private | 
 
 
      
        
          | 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 790 of file move_base.cpp.
 
 
  
  | 
        
          | void move_base::MoveBase::goalCB | ( | const geometry_msgs::PoseStamped::ConstPtr & | goal | ) |  |  | private | 
 
 
  
  | 
        
          | geometry_msgs::PoseStamped move_base::MoveBase::goalToGlobalFrame | ( | const geometry_msgs::PoseStamped & | goal_pose_msg | ) |  |  | private | 
 
 
  
  | 
        
          | bool move_base::MoveBase::isQuaternionValid | ( | const geometry_msgs::Quaternion & | q | ) |  |  | private | 
 
 
  
  | 
        
          | void move_base::MoveBase::loadDefaultRecoveryBehaviors | ( |  | ) |  |  | private | 
 
Loads the default recovery behaviors for the navigation stack. 
Definition at line 1084 of file move_base.cpp.
 
 
Load the recovery behaviors for the navigation stack from the parameter server. 
- Parameters
- 
  
  
- Returns
- True if the recovery behaviors were loaded successfully, false otherwise 
Definition at line 999 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 459 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 339 of file move_base.cpp.
 
 
  
  | 
        
          | void move_base::MoveBase::planThread | ( |  | ) |  |  | private | 
 
 
  
  | 
        
          | void move_base::MoveBase::publishZeroVelocity | ( |  | ) |  |  | private | 
 
Publishes a velocity command of zero to the base. 
Definition at line 490 of file move_base.cpp.
 
 
  
  | 
        
          | void move_base::MoveBase::reconfigureCB | ( | move_base::MoveBaseConfig & | config, |  
          |  |  | uint32_t | level |  
          |  | ) |  |  |  | private | 
 
 
  
  | 
        
          | 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 1120 of file move_base.cpp.
 
 
This is used to wake the planner at periodic intervals. 
Definition at line 551 of file move_base.cpp.
 
 
  
  | 
        
          | bool move_base::MoveBase::c_freq_change_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::circumscribed_radius_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::clearing_radius_ |  | private | 
 
 
  
  | 
        
          | bool move_base::MoveBase::clearing_rotation_allowed_ |  | private | 
 
 
  
  | 
        
          | boost::recursive_mutex move_base::MoveBase::configuration_mutex_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::conservative_reset_dist_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::controller_frequency_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::controller_patience_ |  | private | 
 
 
  
  | 
        
          | std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::controller_plan_ |  | private | 
 
 
  
  | 
        
          | move_base::MoveBaseConfig move_base::MoveBase::default_config_ |  | private | 
 
 
  
  | 
        
          | dynamic_reconfigure::Server<move_base::MoveBaseConfig>* move_base::MoveBase::dsrv_ |  | private | 
 
 
  
  | 
        
          | std::string move_base::MoveBase::global_frame_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::inscribed_radius_ |  | private | 
 
 
  
  | 
        
          | move_base::MoveBaseConfig move_base::MoveBase::last_config_ |  | private | 
 
 
  
  | 
        
          | ros::Time move_base::MoveBase::last_oscillation_reset_ |  | private | 
 
 
  
  | 
        
          | ros::Time move_base::MoveBase::last_valid_control_ |  | private | 
 
 
  
  | 
        
          | ros::Time move_base::MoveBase::last_valid_plan_ |  | private | 
 
 
  
  | 
        
          | std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::latest_plan_ |  | private | 
 
 
  
  | 
        
          | int32_t move_base::MoveBase::max_planning_retries_ |  | private | 
 
 
  
  | 
        
          | bool move_base::MoveBase::new_global_plan_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::oscillation_distance_ |  | private | 
 
 
  
  | 
        
          | geometry_msgs::PoseStamped move_base::MoveBase::oscillation_pose_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::oscillation_timeout_ |  | private | 
 
 
  
  | 
        
          | bool move_base::MoveBase::p_freq_change_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::planner_frequency_ |  | private | 
 
 
  
  | 
        
          | geometry_msgs::PoseStamped move_base::MoveBase::planner_goal_ |  | private | 
 
 
  
  | 
        
          | boost::recursive_mutex move_base::MoveBase::planner_mutex_ |  | private | 
 
 
  
  | 
        
          | double move_base::MoveBase::planner_patience_ |  | private | 
 
 
  
  | 
        
          | std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::planner_plan_ |  | private | 
 
 
  
  | 
        
          | boost::thread* move_base::MoveBase::planner_thread_ |  | private | 
 
 
  
  | 
        
          | uint32_t move_base::MoveBase::planning_retries_ |  | private | 
 
 
  
  | 
        
          | bool move_base::MoveBase::recovery_behavior_enabled_ |  | private | 
 
 
  
  | 
        
          | unsigned int move_base::MoveBase::recovery_index_ |  | private | 
 
 
  
  | 
        
          | std::string move_base::MoveBase::robot_base_frame_ |  | private | 
 
 
  
  | 
        
          | bool move_base::MoveBase::runPlanner_ |  | private | 
 
 
  
  | 
        
          | bool move_base::MoveBase::setup_ |  | private | 
 
 
  
  | 
        
          | bool move_base::MoveBase::shutdown_costmaps_ |  | private | 
 
 
The documentation for this class was generated from the following files: