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 118 of file move_base.h.
◆ MoveBase()
Constructor for the actions.
- Parameters
-
name | The name of the action |
tf | A reference to a TransformListener |
Definition at line 87 of file move_base.cpp.
◆ ~MoveBase()
move_base::MoveBase::~MoveBase |
( |
| ) |
|
|
virtual |
◆ 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
-
req | The service request |
resp | The 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_x | The x size of the window |
size_y | The 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 |
◆ executeCb()
void move_base::MoveBase::executeCb |
( |
const move_base_msgs::MoveBaseGoalConstPtr & |
move_base_goal | ) |
|
|
private |
◆ executeCycle()
bool move_base::MoveBase::executeCycle |
( |
geometry_msgs::PoseStamped & |
goal | ) |
|
Performs a control cycle.
- Parameters
-
goal | A 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()
◆ goalCB()
void move_base::MoveBase::goalCB |
( |
const geometry_msgs::PoseStamped::ConstPtr & |
goal | ) |
|
|
private |
◆ goalToGlobalFrame()
geometry_msgs::PoseStamped move_base::MoveBase::goalToGlobalFrame |
( |
const geometry_msgs::PoseStamped & |
goal_pose_msg | ) |
|
|
private |
◆ isQuaternionValid()
bool move_base::MoveBase::isQuaternionValid |
( |
const geometry_msgs::Quaternion & |
q | ) |
|
|
private |
◆ 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()
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 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
-
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 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
-
req | The goal request |
resp | The 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 |
◆ 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 |
◆ 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()
This is used to wake the planner at periodic intervals.
Definition at line 599 of file move_base.cpp.
◆ action_goal_pub_
◆ as_
◆ bgp_loader_
◆ blp_loader_
◆ c_freq_change_
bool move_base::MoveBase::c_freq_change_ |
|
private |
◆ circumscribed_radius_
double move_base::MoveBase::circumscribed_radius_ |
|
private |
◆ clear_costmaps_srv_
◆ clearing_radius_
double move_base::MoveBase::clearing_radius_ |
|
private |
◆ clearing_rotation_allowed_
bool move_base::MoveBase::clearing_rotation_allowed_ |
|
private |
◆ configuration_mutex_
boost::recursive_mutex move_base::MoveBase::configuration_mutex_ |
|
private |
◆ conservative_reset_dist_
double move_base::MoveBase::conservative_reset_dist_ |
|
private |
◆ controller_costmap_ros_
◆ controller_frequency_
double move_base::MoveBase::controller_frequency_ |
|
private |
◆ controller_patience_
double move_base::MoveBase::controller_patience_ |
|
private |
◆ controller_plan_
std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::controller_plan_ |
|
private |
◆ current_goal_pub_
◆ default_config_
move_base::MoveBaseConfig move_base::MoveBase::default_config_ |
|
private |
◆ dsrv_
dynamic_reconfigure::Server<move_base::MoveBaseConfig>* move_base::MoveBase::dsrv_ |
|
private |
◆ global_frame_
std::string move_base::MoveBase::global_frame_ |
|
private |
◆ global_pose_
geometry_msgs::PoseStamped move_base::MoveBase::global_pose_ |
|
private |
◆ goal_sub_
◆ inscribed_radius_
double move_base::MoveBase::inscribed_radius_ |
|
private |
◆ last_config_
move_base::MoveBaseConfig move_base::MoveBase::last_config_ |
|
private |
◆ last_oscillation_reset_
ros::Time move_base::MoveBase::last_oscillation_reset_ |
|
private |
◆ last_valid_control_
ros::Time move_base::MoveBase::last_valid_control_ |
|
private |
◆ last_valid_plan_
ros::Time move_base::MoveBase::last_valid_plan_ |
|
private |
◆ latest_plan_
std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::latest_plan_ |
|
private |
◆ make_plan_add_unreachable_goal_
bool move_base::MoveBase::make_plan_add_unreachable_goal_ |
|
private |
◆ make_plan_clear_costmap_
bool move_base::MoveBase::make_plan_clear_costmap_ |
|
private |
◆ make_plan_srv_
◆ max_planning_retries_
int32_t move_base::MoveBase::max_planning_retries_ |
|
private |
◆ new_global_plan_
bool move_base::MoveBase::new_global_plan_ |
|
private |
◆ oscillation_distance_
double move_base::MoveBase::oscillation_distance_ |
|
private |
◆ oscillation_pose_
geometry_msgs::PoseStamped move_base::MoveBase::oscillation_pose_ |
|
private |
◆ oscillation_timeout_
double move_base::MoveBase::oscillation_timeout_ |
|
private |
◆ p_freq_change_
bool move_base::MoveBase::p_freq_change_ |
|
private |
◆ planner_
◆ planner_cond_
boost::condition_variable_any move_base::MoveBase::planner_cond_ |
|
private |
◆ planner_costmap_ros_
◆ planner_frequency_
double move_base::MoveBase::planner_frequency_ |
|
private |
◆ planner_goal_
geometry_msgs::PoseStamped move_base::MoveBase::planner_goal_ |
|
private |
◆ planner_mutex_
boost::recursive_mutex move_base::MoveBase::planner_mutex_ |
|
private |
◆ planner_patience_
double move_base::MoveBase::planner_patience_ |
|
private |
◆ planner_plan_
std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::planner_plan_ |
|
private |
◆ planner_thread_
boost::thread* move_base::MoveBase::planner_thread_ |
|
private |
◆ planning_retries_
uint32_t move_base::MoveBase::planning_retries_ |
|
private |
◆ recovery_behavior_enabled_
bool move_base::MoveBase::recovery_behavior_enabled_ |
|
private |
◆ recovery_behavior_names_
std::vector<std::string> move_base::MoveBase::recovery_behavior_names_ |
|
private |
◆ recovery_behaviors_
◆ recovery_index_
unsigned int move_base::MoveBase::recovery_index_ |
|
private |
◆ recovery_loader_
◆ recovery_status_pub_
◆ recovery_trigger_
◆ robot_base_frame_
std::string move_base::MoveBase::robot_base_frame_ |
|
private |
◆ runPlanner_
bool move_base::MoveBase::runPlanner_ |
|
private |
◆ setup_
bool move_base::MoveBase::setup_ |
|
private |
◆ shutdown_costmaps_
bool move_base::MoveBase::shutdown_costmaps_ |
|
private |
◆ state_
◆ tc_
◆ tf_
◆ vel_pub_
The documentation for this class was generated from the following files: