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. | |
| MoveBase (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. | |
| 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 | planThread () |
| void | publishZeroVelocity () |
| Publishes a velocity command of zero to the base. | |
| 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. | |
| void | wakePlanner (const ros::TimerEvent &event) |
| This is used to wake the planner at periodic intervals. | |
Private Attributes | |
| ros::Publisher | action_goal_pub_ |
| MoveBaseActionServer * | as_ |
| pluginlib::ClassLoader < nav_core::BaseGlobalPlanner > | bgp_loader_ |
| pluginlib::ClassLoader < nav_core::BaseLocalPlanner > | blp_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::Costmap2DROS * | controller_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::Pose > | 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_ |
| ros::ServiceServer | make_plan_srv_ |
| bool | new_global_plan_ |
| double | oscillation_distance_ |
| geometry_msgs::PoseStamped | oscillation_pose_ |
| double | oscillation_timeout_ |
| bool | p_freq_change_ |
| boost::shared_ptr < nav_core::BaseGlobalPlanner > | planner_ |
| boost::condition_variable | planner_cond_ |
| costmap_2d::Costmap2DROS * | planner_costmap_ros_ |
| double | planner_frequency_ |
| geometry_msgs::PoseStamped | planner_goal_ |
| boost::mutex | planner_mutex_ |
| double | planner_patience_ |
| std::vector < geometry_msgs::PoseStamped > * | planner_plan_ |
| boost::thread * | planner_thread_ |
| 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 | runPlanner_ |
| bool | setup_ |
| bool | shutdown_costmaps_ |
| MoveBaseState | state_ |
| boost::shared_ptr < nav_core::BaseLocalPlanner > | tc_ |
| tf::TransformListener & | tf_ |
| ros::Publisher | vel_pub_ |
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.
| 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] |
Destructor - Cleans up.
Definition at line 480 of file move_base.cpp.
| 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.
| req | The service request |
| resp | The service response |
Definition at line 384 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.
| size_x | The x size of the window |
| size_y | The y size of the window |
Definition at line 329 of file move_base.cpp.
| double move_base::MoveBase::distance | ( | const geometry_msgs::PoseStamped & | p1, |
| const geometry_msgs::PoseStamped & | p2 | ||
| ) | [private] |
Definition at line 821 of file move_base.cpp.
| void move_base::MoveBase::executeCb | ( | const move_base_msgs::MoveBaseGoalConstPtr & | move_base_goal | ) | [private] |
Definition at line 678 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.
| goal | A reference to the goal to pursue |
| global_plan | A reference to the global plan being used |
Definition at line 826 of file move_base.cpp.
| void move_base::MoveBase::goalCB | ( | const geometry_msgs::PoseStamped::ConstPtr & | goal | ) | [private] |
Definition at line 320 of file move_base.cpp.
| geometry_msgs::PoseStamped move_base::MoveBase::goalToGlobalFrame | ( | const geometry_msgs::PoseStamped & | goal_pose_msg | ) | [private] |
Definition at line 574 of file move_base.cpp.
| bool move_base::MoveBase::isQuaternionValid | ( | const geometry_msgs::Quaternion & | q | ) | [private] |
Definition at line 544 of file move_base.cpp.
| void move_base::MoveBase::loadDefaultRecoveryBehaviors | ( | ) | [private] |
Loads the default recovery behaviors for the navigation stack.
Definition at line 1117 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.
| node | The ros::NodeHandle to be used for loading parameters |
Definition at line 1032 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.
| goal | The goal to plan to |
| plan | Will be filled in with the plan made by the planner |
Definition at line 505 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.
| req | The goal request |
| resp | The plan request |
Definition at line 392 of file move_base.cpp.
| void move_base::MoveBase::planThread | ( | ) | [private] |
Definition at line 603 of file move_base.cpp.
| void move_base::MoveBase::publishZeroVelocity | ( | ) | [private] |
Publishes a velocity command of zero to the base.
Definition at line 536 of file move_base.cpp.
| void move_base::MoveBase::reconfigureCB | ( | move_base::MoveBaseConfig & | config, |
| uint32_t | level | ||
| ) | [private] |
Definition at line 203 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 1153 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 597 of file move_base.cpp.
Definition at line 193 of file move_base.h.
MoveBaseActionServer* move_base::MoveBase::as_ [private] |
Definition at line 178 of file move_base.h.
Definition at line 204 of file move_base.h.
Definition at line 205 of file move_base.h.
bool move_base::MoveBase::c_freq_change_ [private] |
Definition at line 228 of file move_base.h.
double move_base::MoveBase::circumscribed_radius_ [private] |
Definition at line 190 of file move_base.h.
Definition at line 195 of file move_base.h.
double move_base::MoveBase::clearing_radius_ [private] |
Definition at line 192 of file move_base.h.
bool move_base::MoveBase::clearing_rotation_allowed_ [private] |
Definition at line 196 of file move_base.h.
boost::recursive_mutex move_base::MoveBase::configuration_mutex_ [private] |
Definition at line 221 of file move_base.h.
double move_base::MoveBase::conservative_reset_dist_ [private] |
Definition at line 192 of file move_base.h.
Definition at line 181 of file move_base.h.
double move_base::MoveBase::controller_frequency_ [private] |
Definition at line 190 of file move_base.h.
double move_base::MoveBase::controller_patience_ [private] |
Definition at line 191 of file move_base.h.
std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::controller_plan_ [private] |
Definition at line 211 of file move_base.h.
Definition at line 193 of file move_base.h.
move_base::MoveBaseConfig move_base::MoveBase::default_config_ [private] |
Definition at line 227 of file move_base.h.
dynamic_reconfigure::Server<move_base::MoveBaseConfig>* move_base::MoveBase::dsrv_ [private] |
Definition at line 222 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 189 of file move_base.h.
Definition at line 194 of file move_base.h.
double move_base::MoveBase::inscribed_radius_ [private] |
Definition at line 190 of file move_base.h.
move_base::MoveBaseConfig move_base::MoveBase::last_config_ [private] |
Definition at line 226 of file move_base.h.
Definition at line 202 of file move_base.h.
Definition at line 202 of file move_base.h.
Definition at line 202 of file move_base.h.
std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::latest_plan_ [private] |
Definition at line 210 of file move_base.h.
Definition at line 195 of file move_base.h.
bool move_base::MoveBase::new_global_plan_ [private] |
Definition at line 229 of file move_base.h.
double move_base::MoveBase::oscillation_distance_ [private] |
Definition at line 197 of file move_base.h.
geometry_msgs::PoseStamped move_base::MoveBase::oscillation_pose_ [private] |
Definition at line 203 of file move_base.h.
double move_base::MoveBase::oscillation_timeout_ [private] |
Definition at line 197 of file move_base.h.
bool move_base::MoveBase::p_freq_change_ [private] |
Definition at line 228 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 move_base::MoveBase::planner_cond_ [private] |
Definition at line 216 of file move_base.h.
Definition at line 181 of file move_base.h.
double move_base::MoveBase::planner_frequency_ [private] |
Definition at line 190 of file move_base.h.
geometry_msgs::PoseStamped move_base::MoveBase::planner_goal_ [private] |
Definition at line 217 of file move_base.h.
boost::mutex move_base::MoveBase::planner_mutex_ [private] |
Definition at line 215 of file move_base.h.
double move_base::MoveBase::planner_patience_ [private] |
Definition at line 191 of file move_base.h.
std::vector<geometry_msgs::PoseStamped>* move_base::MoveBase::planner_plan_ [private] |
Definition at line 209 of file move_base.h.
boost::thread* move_base::MoveBase::planner_thread_ [private] |
Definition at line 218 of file move_base.h.
bool move_base::MoveBase::recovery_behavior_enabled_ [private] |
Definition at line 196 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 187 of file move_base.h.
Definition at line 206 of file move_base.h.
Definition at line 200 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 214 of file move_base.h.
bool move_base::MoveBase::setup_ [private] |
Definition at line 228 of file move_base.h.
bool move_base::MoveBase::shutdown_costmaps_ [private] |
Definition at line 196 of file move_base.h.
MoveBaseState move_base::MoveBase::state_ [private] |
Definition at line 199 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 193 of file move_base.h.