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" 103 bool executeCycle(geometry_msgs::PoseStamped&
goal, std::vector<geometry_msgs::PoseStamped>& global_plan);
120 bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
128 bool makePlan(
const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
159 void goalCB(
const geometry_msgs::PoseStamped::ConstPtr& goal);
163 void executeCb(
const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal);
169 double distance(
const geometry_msgs::PoseStamped& p1,
const geometry_msgs::PoseStamped& p2);
171 geometry_msgs::PoseStamped
goalToGlobalFrame(
const geometry_msgs::PoseStamped& goal_pose_msg);
180 MoveBaseActionServer*
as_;
226 dynamic_reconfigure::Server<move_base::MoveBaseConfig> *
dsrv_;
228 void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level);
void executeCb(const move_base_msgs::MoveBaseGoalConstPtr &move_base_goal)
boost::condition_variable_any planner_cond_
boost::thread * planner_thread_
void wakePlanner(const ros::TimerEvent &event)
This is used to wake the planner at periodic intervals.
ros::ServiceServer make_plan_srv_
double distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > blp_loader_
MoveBaseActionServer * as_
bool isQuaternionValid(const geometry_msgs::Quaternion &q)
costmap_2d::Costmap2DROS * controller_costmap_ros_
int32_t max_planning_retries_
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.
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > bgp_loader_
boost::recursive_mutex configuration_mutex_
double planner_frequency_
ros::Publisher action_goal_pub_
virtual ~MoveBase()
Destructor - Cleans up.
ros::Time last_oscillation_reset_
bool getRobotPose(tf::Stamped< tf::Pose > &global_posee, costmap_2d::Costmap2DROS *costmap)
bool recovery_behavior_enabled_
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > MoveBaseActionServer
std::string global_frame_
tf::Stamped< tf::Pose > global_pose_
std::vector< geometry_msgs::PoseStamped > * planner_plan_
boost::shared_ptr< nav_core::BaseGlobalPlanner > planner_
bool clearing_rotation_allowed_
unsigned int recovery_index_
dynamic_reconfigure::Server< move_base::MoveBaseConfig > * dsrv_
RecoveryTrigger recovery_trigger_
ros::ServiceServer clear_costmaps_srv_
move_base::MoveBaseConfig default_config_
ros::Time last_valid_plan_
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack.
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server.
void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level)
double controller_patience_
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
A class that uses the actionlib::ActionServer interface that moves the robot base to a goal location...
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
double controller_frequency_
costmap_2d::Costmap2DROS * planner_costmap_ros_
boost::recursive_mutex planner_mutex_
void publishZeroVelocity()
Publishes a velocity command of zero to the base.
geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped &goal_pose_msg)
double oscillation_distance_
boost::shared_ptr< nav_core::BaseLocalPlanner > tc_
void resetState()
Reset the state of the move_base action and send a zero velocity command to the base.
ros::Publisher current_goal_pub_
geometry_msgs::PoseStamped planner_goal_
ros::Subscriber goal_sub_
tf::TransformListener & tf_
std::vector< geometry_msgs::PoseStamped > * latest_plan_
move_base::MoveBaseConfig last_config_
MoveBase(tf::TransformListener &tf)
Constructor for the actions.
bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
A service call that clears the costmaps of obstacles.
uint32_t planning_retries_
double circumscribed_radius_
std::string robot_base_frame_
bool makePlan(const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Make a new global plan.
double conservative_reset_dist_
bool executeCycle(geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &global_plan)
Performs a control cycle.
ros::Time last_valid_control_
double oscillation_timeout_
geometry_msgs::PoseStamped oscillation_pose_
void clearCostmapWindows(double size_x, double size_y)
Clears obstacles within a window around the robot.
std::vector< geometry_msgs::PoseStamped > * controller_plan_