Go to the documentation of this file.
37 #ifndef NAV_MOVE_BASE_ACTION_H_
38 #define NAV_MOVE_BASE_ACTION_H_
46 #include <move_base_msgs/MoveBaseAction.h>
51 #include <geometry_msgs/PoseStamped.h>
54 #include <nav_msgs/GetPlan.h>
57 #include <std_srvs/Empty.h>
59 #include <dynamic_reconfigure/server.h>
60 #include "move_base/MoveBaseConfig.h"
119 bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
127 bool makePlan(
const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
158 void goalCB(
const geometry_msgs::PoseStamped::ConstPtr& goal);
162 void executeCb(
const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal);
168 double distance(
const geometry_msgs::PoseStamped& p1,
const geometry_msgs::PoseStamped& p2);
170 geometry_msgs::PoseStamped
goalToGlobalFrame(
const geometry_msgs::PoseStamped& goal_pose_msg);
227 dynamic_reconfigure::Server<move_base::MoveBaseConfig> *
dsrv_;
int32_t max_planning_retries_
ros::Time last_valid_control_
ros::ServiceServer make_plan_srv_
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > blp_loader_
double circumscribed_radius_
std::string global_frame_
void resetState()
Reset the state of the move_base action and send a zero velocity command to the base.
RecoveryTrigger recovery_trigger_
bool getRobotPose(geometry_msgs::PoseStamped &global_pose, costmap_2d::Costmap2DROS *costmap)
dynamic_reconfigure::Server< move_base::MoveBaseConfig > * dsrv_
boost::recursive_mutex planner_mutex_
std::vector< geometry_msgs::PoseStamped > * controller_plan_
bool make_plan_clear_costmap_
bool executeCycle(geometry_msgs::PoseStamped &goal)
Performs a control cycle.
boost::recursive_mutex configuration_mutex_
double controller_patience_
boost::thread * planner_thread_
bool isQuaternionValid(const geometry_msgs::Quaternion &q)
double planner_frequency_
double conservative_reset_dist_
void executeCb(const move_base_msgs::MoveBaseGoalConstPtr &move_base_goal)
geometry_msgs::PoseStamped oscillation_pose_
ros::Time last_oscillation_reset_
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > MoveBaseActionServer
virtual ~MoveBase()
Destructor - Cleans up.
ros::Publisher action_goal_pub_
bool make_plan_add_unreachable_goal_
boost::condition_variable_any planner_cond_
ros::Publisher current_goal_pub_
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > bgp_loader_
unsigned int recovery_index_
std::vector< std::string > recovery_behavior_names_
ros::Publisher recovery_status_pub_
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server.
double oscillation_timeout_
void publishZeroVelocity()
Publishes a velocity command of zero to the base.
double controller_frequency_
bool recovery_behavior_enabled_
move_base::MoveBaseConfig last_config_
void wakePlanner(const ros::TimerEvent &event)
This is used to wake the planner at periodic intervals.
boost::shared_ptr< nav_core::BaseGlobalPlanner > planner_
costmap_2d::Costmap2DROS * planner_costmap_ros_
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
std::vector< geometry_msgs::PoseStamped > * planner_plan_
MoveBase(tf2_ros::Buffer &tf)
Constructor for the actions.
ros::Time last_valid_plan_
geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped &goal_pose_msg)
std::vector< geometry_msgs::PoseStamped > * latest_plan_
costmap_2d::Costmap2DROS * controller_costmap_ros_
bool clearing_rotation_allowed_
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
geometry_msgs::PoseStamped global_pose_
std::string robot_base_frame_
double oscillation_distance_
geometry_msgs::PoseStamped planner_goal_
move_base::MoveBaseConfig default_config_
uint32_t planning_retries_
boost::shared_ptr< nav_core::BaseLocalPlanner > tc_
ros::Subscriber goal_sub_
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.
MoveBaseActionServer * as_
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack.
double distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
ros::ServiceServer clear_costmaps_srv_
A class that uses the actionlib::ActionServer interface that moves the robot base to a goal location.
void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level)
bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
A service call that clears the costmaps of obstacles.
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
void clearCostmapWindows(double size_x, double size_y)
Clears obstacles within a window around the robot.
bool makePlan(const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Make a new global plan.
move_base
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:45