原创文章,转载请注明: 转载自慢慢的回味
本文链接地址: ROS导航-MoveBase
MoveBase包通过全局规划器和局部规划器,利用代价地图costmap来实现当前地点到目标地点的导航。其中,costmap由map和小车传感器共同决定。现在通过对其的源码解读来了解这个框架是怎么完成这个任务的。
1 调用流程
–> MoveBase Node创建:MoveBase::MoveBase(tf2_ros::Buffer& tf)
–> Action server(as_)接收导航目标:void MoveBase::executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal)
–> runPlanner_值改变为true,导航线程void MoveBase::planThread()开始调用全局规划器planner_规划全局路径bool MoveBase::makePlan(const geometry_msgs::PoseStamped& goal, std::vector
–> 一旦进入到控制状态CONTROLLING,MoveBase::executeCycle负责调用局部规划器tc_进行局部导航控制
2 MoveBase Node创建
构造方法MoveBase::MoveBase:
初始化类加载器,全局规划器加载器bgp_loader_,局部规划器加载器blp_loader_,已经初始化一些全局变量。
MoveBase::MoveBase(tf2_ros::Buffer& tf) : tf_(tf), as_(NULL), planner_costmap_ros_(NULL), controller_costmap_ros_(NULL), bgp_loader_("nav_core", "nav_core::BaseGlobalPlanner"), blp_loader_("nav_core", "nav_core::BaseLocalPlanner"), recovery_loader_("nav_core", "nav_core::RecoveryBehavior"), planner_plan_(NULL), latest_plan_(NULL), controller_plan_(NULL), runPlanner_(false), setup_(false), p_freq_change_(false), c_freq_change_(false), new_global_plan_(false) { |
创建一个Action Server,回调函数为executeCb:
as_ = new MoveBaseActionServer(ros::NodeHandle(), "move_base", boost::bind(&MoveBase::executeCb, this, _1), false); |
获取node的参数,默认全局规划器为NavfnROS,局部规划器为TrajectoryPlannerROS:
ros::NodeHandle private_nh("~"); ros::NodeHandle nh; recovery_trigger_ = PLANNING_R; //get some parameters that will be global to the move base node std::string global_planner, local_planner; private_nh.param("base_global_planner", global_planner, std::string("navfn/NavfnROS")); private_nh.param("base_local_planner", local_planner, std::string("base_local_planner/TrajectoryPlannerROS")); private_nh.param("global_costmap/robot_base_frame", robot_base_frame_, std::string("base_link")); private_nh.param("global_costmap/global_frame", global_frame_, std::string("map")); private_nh.param("planner_frequency", planner_frequency_, 0.0); private_nh.param("controller_frequency", controller_frequency_, 20.0); private_nh.param("planner_patience", planner_patience_, 5.0); private_nh.param("controller_patience", controller_patience_, 15.0); private_nh.param("max_planning_retries", max_planning_retries_, -1); // disabled by default private_nh.param("oscillation_timeout", oscillation_timeout_, 0.0); private_nh.param("oscillation_distance", oscillation_distance_, 0.5); |
设置3个plan,全局规划plan planner_plan_ ,最新的plan latest_plan_和局部控制plan controller_plan_,开启规划线程:
//set up plan triple buffer planner_plan_ = new std::vector<geometry_msgs::PoseStamped>(); latest_plan_ = new std::vector<geometry_msgs::PoseStamped>(); controller_plan_ = new std::vector<geometry_msgs::PoseStamped>(); //set up the planner's thread planner_thread_ = new boost::thread(boost::bind(&MoveBase::planThread, this)); |
publish 2个服务,cmd_vel发布速度,下位机收到后控制小车运动,action_goal_pub_发布当前目标到action server,goal_sub_订阅goal比如来自rviz里的,回调函数MoveBase::goalCB把goal封装成MoveBaseActionGoal发送给action server,而后引起回调MoveBase::executeCb:
//for commanding the base vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1); //current_goal_pub_发布当前的goal current_goal_pub_ = private_nh.advertise<geometry_msgs::PoseStamped>("current_goal", 0 ); ros::NodeHandle action_nh("move_base"); action_goal_pub_ = action_nh.advertise<move_base_msgs::MoveBaseActionGoal>("goal", 1); //提供一个goal的回调机制来支持比如rviz动态设置目标goal。 //we'll provide a mechanism for some people to send goals as PoseStamped messages over a topic //they won't get any useful information back about its status, but this is useful for tools //like nav_view and rviz ros::NodeHandle simple_nh("move_base_simple"); //goal_sub_订阅goal后可以开始规划。 goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&MoveBase::goalCB, this, _1)); //局部规划器会使用inscribed_radius和circumscribed_radius来检查是否碰到障碍物。 //we'll assume the radius of the robot to be consistent with what's specified for the costmaps private_nh.param("local_costmap/inscribed_radius", inscribed_radius_, 0.325); private_nh.param("local_costmap/circumscribed_radius", circumscribed_radius_, 0.46); private_nh.param("clearing_radius", clearing_radius_, circumscribed_radius_); private_nh.param("conservative_reset_dist", conservative_reset_dist_, 3.0); private_nh.param("shutdown_costmaps", shutdown_costmaps_, false); private_nh.param("clearing_rotation_allowed", clearing_rotation_allowed_, true); private_nh.param("recovery_behavior_enabled", recovery_behavior_enabled_, true); |
初始化全局规划器planner_ 和局部规划器tc_:
//初始化全局规划器代价地图planner_costmap_ros_ //create the ros wrapper for the planner's costmap... and initializer a pointer we'll use with the underlying map planner_costmap_ros_ = new costmap_2d::Costmap2DROS("global_costmap", tf_); planner_costmap_ros_->pause(); //initialize the global planner try { planner_ = bgp_loader_.createInstance(global_planner); planner_->initialize(bgp_loader_.getName(global_planner), planner_costmap_ros_); } catch (const pluginlib::PluginlibException& ex) { ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the containing library is built? Exception: %s", global_planner.c_str(), ex.what()); exit(1); } //初始化局部规划器代价地图controller_costmap_ros_ //create the ros wrapper for the controller's costmap... and initializer a pointer we'll use with the underlying map controller_costmap_ros_ = new costmap_2d::Costmap2DROS("local_costmap", tf_); controller_costmap_ros_->pause(); //create a local planner try { tc_ = blp_loader_.createInstance(local_planner); ROS_INFO("Created local_planner %s", local_planner.c_str()); tc_->initialize(blp_loader_.getName(local_planner), &tf_, controller_costmap_ros_); } catch (const pluginlib::PluginlibException& ex) { ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the containing library is built? Exception: %s", local_planner.c_str(), ex.what()); exit(1); } |
根据自己的传感器数据更新全局和局部代价地图,以及发布2个服务:
//让代价地图开始接受传感器的数据以更新地图 // Start actively updating costmaps based on sensor data planner_costmap_ros_->start(); controller_costmap_ros_->start(); //发布全局规划服务 //advertise a service for getting a plan make_plan_srv_ = private_nh.advertiseService("make_plan", &MoveBase::planService, this); //advertise a service for clearing the costmaps clear_costmaps_srv_ = private_nh.advertiseService("clear_costmaps", &MoveBase::clearCostmapsService, this); //if we shutdown our costmaps when we're deactivated... we'll do that now if(shutdown_costmaps_){ ROS_DEBUG_NAMED("move_base","Stopping costmaps initially"); planner_costmap_ros_->stop(); controller_costmap_ros_->stop(); } //加载默认错误恢复行为 //load any user specified recovery behaviors, and if that fails load the defaults if(!loadRecoveryBehaviors(private_nh)){ loadDefaultRecoveryBehaviors(); } |
初始化为PLANNING状态,开启action server(as_),开启动态参数配置服务:
//initially, we'll need to make a plan state_ = PLANNING; //we'll start executing recovery behaviors at the beginning of our list recovery_index_ = 0; //we're all set up now so we can start the action server as_->start(); //开启Move_base的参数动态配置 dsrv_ = new dynamic_reconfigure::Server<move_base::MoveBaseConfig>(ros::NodeHandle("~")); dynamic_reconfigure::Server<move_base::MoveBaseConfig>::CallbackType cb = boost::bind(&MoveBase::reconfigureCB, this, _1, _2); dsrv_->setCallback(cb); } |
3 Action server(as_)接收导航目标
此回调函数的主要逻辑就是:一直循环,当收到新的goal后,设置runPlanner_ = true使全局规划线程可以进行全局规划。循环中调用executeCycle,一旦全局规划成功,其局部规划便会启用并返回小车的目标速度和方向,从而发布速度控制指令给下位机(下位机可以根据速度命令控制电动机驱动小车达到要求的速度)。
void MoveBase::executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal) { if(!isQuaternionValid(move_base_goal->target_pose.pose.orientation)){ as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion"); return; } geometry_msgs::PoseStamped goal = goalToGlobalFrame(move_base_goal->target_pose); publishZeroVelocity(); //we have a goal so start the planner boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_); planner_goal_ = goal; runPlanner_ = true; planner_cond_.notify_one(); lock.unlock(); current_goal_pub_.publish(goal); std::vector<geometry_msgs::PoseStamped> global_plan; ros::Rate r(controller_frequency_); if(shutdown_costmaps_){ ROS_DEBUG_NAMED("move_base","Starting up costmaps that were shut down previously"); planner_costmap_ros_->start(); controller_costmap_ros_->start(); } //we want to make sure that we reset the last time we had a valid plan and control last_valid_control_ = ros::Time::now(); last_valid_plan_ = ros::Time::now(); last_oscillation_reset_ = ros::Time::now(); planning_retries_ = 0; ros::NodeHandle n; while(n.ok()) { if(c_freq_change_) { ROS_INFO("Setting controller frequency to %.2f", controller_frequency_); r = ros::Rate(controller_frequency_); c_freq_change_ = false; } if(as_->isPreemptRequested()){ if(as_->isNewGoalAvailable()){ //if we're active and a new goal is available, we'll accept it, but we won't shut anything down move_base_msgs::MoveBaseGoal new_goal = *as_->acceptNewGoal(); if(!isQuaternionValid(new_goal.target_pose.pose.orientation)){ as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion"); return; } goal = goalToGlobalFrame(new_goal.target_pose); //we'll make sure that we reset our state for the next execution cycle recovery_index_ = 0; state_ = PLANNING; //we have a new goal so make sure the planner is awake lock.lock(); planner_goal_ = goal; runPlanner_ = true; planner_cond_.notify_one(); lock.unlock(); //发布当前的目标goal,其它订阅的节点就可以更新其对应的机制。 //publish the goal point to the visualizer ROS_DEBUG_NAMED("move_base","move_base has received a goal of x: %.2f, y: %.2f", goal.pose.position.x, goal.pose.position.y); current_goal_pub_.publish(goal); //make sure to reset our timeouts and counters last_valid_control_ = ros::Time::now(); last_valid_plan_ = ros::Time::now(); last_oscillation_reset_ = ros::Time::now(); planning_retries_ = 0; } else { //if we've been preempted explicitly we need to shut things down resetState(); //notify the ActionServer that we've successfully preempted ROS_DEBUG_NAMED("move_base","Move base preempting the current goal"); as_->setPreempted(); //we'll actually return from execute after preempting return; } } //we also want to check if we've changed global frames because we need to transform our goal pose if(goal.header.frame_id != planner_costmap_ros_->getGlobalFrameID()){ goal = goalToGlobalFrame(goal); //we want to go back to the planning state for the next execution cycle recovery_index_ = 0; state_ = PLANNING; //we have a new goal so make sure the planner is awake lock.lock(); planner_goal_ = goal; //设置runPlanner_为true,线程可以开始全局规划。 runPlanner_ = true; planner_cond_.notify_one(); lock.unlock(); //publish the goal point to the visualizer ROS_DEBUG_NAMED("move_base","The global frame for move_base has changed, new frame: %s, new goal position x: %.2f, y: %.2f", goal.header.frame_id.c_str(), goal.pose.position.x, goal.pose.position.y); current_goal_pub_.publish(goal); //make sure to reset our timeouts and counters last_valid_control_ = ros::Time::now(); last_valid_plan_ = ros::Time::now(); last_oscillation_reset_ = ros::Time::now(); planning_retries_ = 0; } //for timing that gives real time even in simulation ros::WallTime start = ros::WallTime::now(); //the real work on pursuing a goal is done here bool done = executeCycle(goal, global_plan); //if we're done, then we'll return from execute if(done) return; //check if execution of the goal has completed in some way ros::WallDuration t_diff = ros::WallTime::now() - start; ROS_DEBUG_NAMED("move_base","Full control cycle time: %.9f\n", t_diff.toSec()); r.sleep(); //make sure to sleep for the remainder of our cycle time if(r.cycleTime() > ros::Duration(1 / controller_frequency_) && state_ == CONTROLLING) ROS_WARN("Control loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", controller_frequency_, r.cycleTime().toSec()); } //wake up the planner thread so that it can exit cleanly lock.lock(); runPlanner_ = true; planner_cond_.notify_one(); lock.unlock(); //if the node is killed then we'll abort and return as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed"); return; } |
4 规划全局路径
线程的主要逻辑为:当runPlanner_为true时,调用makePlan进行全局规划,成功后进入控制状态state_ = CONTROLLING,供后续的局部规划使用。
void MoveBase::planThread(){ ROS_DEBUG_NAMED("move_base_plan_thread","Starting planner thread..."); ros::NodeHandle n; ros::Timer timer; bool wait_for_wake = false; boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_); while(n.ok()){ //参数runPlanner_为true,表示可以开始全局规划,否则继续循环。 //check if we should run the planner (the mutex is locked) while(wait_for_wake || !runPlanner_){ //if we should not be running the planner then suspend this thread ROS_DEBUG_NAMED("move_base_plan_thread","Planner thread is suspending"); planner_cond_.wait(lock); wait_for_wake = false; } ros::Time start_time = ros::Time::now(); //time to plan! get a copy of the goal and unlock the mutex geometry_msgs::PoseStamped temp_goal = planner_goal_; lock.unlock(); ROS_DEBUG_NAMED("move_base_plan_thread","Planning..."); //调用makePlan进行全局规划 //run planner planner_plan_->clear(); bool gotPlan = n.ok() && makePlan(temp_goal, *planner_plan_); if(gotPlan){ ROS_DEBUG_NAMED("move_base_plan_thread","Got Plan with %zu points!", planner_plan_->size()); //pointer swap the plans under mutex (the controller will pull from latest_plan_) std::vector<geometry_msgs::PoseStamped>* temp_plan = planner_plan_; //planner_plan_是上一次的plan,latest_plan_是这一次的plan lock.lock(); planner_plan_ = latest_plan_; latest_plan_ = temp_plan; last_valid_plan_ = ros::Time::now(); planning_retries_ = 0; new_global_plan_ = true; ROS_DEBUG_NAMED("move_base_plan_thread","Generated a plan from the base_global_planner"); //开始启动局部规划器state_ = CONTROLLING //make sure we only start the controller if we still haven't reached the goal if(runPlanner_) state_ = CONTROLLING; if(planner_frequency_ <= 0) runPlanner_ = false; lock.unlock(); } //if we didn't get a plan and we are in the planning state (the robot isn't moving) else if(state_==PLANNING){ ROS_DEBUG_NAMED("move_base_plan_thread","No Plan..."); ros::Time attempt_end = last_valid_plan_ + ros::Duration(planner_patience_); //check if we've tried to make a plan for over our time limit or our maximum number of retries //issue #496: we stop planning when one of the conditions is true, but if max_planning_retries_ //is negative (the default), it is just ignored and we have the same behavior as ever lock.lock(); planning_retries_++; if(runPlanner_ && (ros::Time::now() > attempt_end || planning_retries_ > uint32_t(max_planning_retries_))){ //we'll move into our obstacle clearing mode state_ = CLEARING; runPlanner_ = false; // proper solution for issue #523 publishZeroVelocity(); recovery_trigger_ = PLANNING_R; } lock.unlock(); } //take the mutex for the next iteration lock.lock(); //setup sleep interface if needed if(planner_frequency_ > 0){ ros::Duration sleep_time = (start_time + ros::Duration(1.0/planner_frequency_)) - ros::Time::now(); if (sleep_time > ros::Duration(0.0)){ wait_for_wake = true; timer = n.createTimer(sleep_time, &MoveBase::wakePlanner, this); } } } } |
5 局部导航控制
当获取到全局规划new_global_plan_后,赋值给局部规划器tc_->setPlan(*controller_plan_),如果进入控制状态后CONTROLLING,就调用局部规划器计算目标速度tc_->computeVelocityCommands(cmd_vel)。
bool MoveBase::executeCycle(geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& global_plan){ boost::recursive_mutex::scoped_lock ecl(configuration_mutex_); //we need to be able to publish velocity commands geometry_msgs::Twist cmd_vel; //update feedback to correspond to our curent position geometry_msgs::PoseStamped global_pose; getRobotPose(global_pose, planner_costmap_ros_); const geometry_msgs::PoseStamped& current_position = global_pose; //push the feedback out move_base_msgs::MoveBaseFeedback feedback; feedback.base_position = current_position; as_->publishFeedback(feedback); //check to see if we've moved far enough to reset our oscillation timeout if(distance(current_position, oscillation_pose_) >= oscillation_distance_) { last_oscillation_reset_ = ros::Time::now(); oscillation_pose_ = current_position; //if our last recovery was caused by oscillation, we want to reset the recovery index if(recovery_trigger_ == OSCILLATION_R) recovery_index_ = 0; } //check that the observation buffers for the costmap are current, we don't want to drive blind if(!controller_costmap_ros_->isCurrent()){ ROS_WARN("[%s]:Sensor data is out of date, we're not going to allow commanding of the base for safety",ros::this_node::getName().c_str()); publishZeroVelocity(); return false; } //if we have a new plan then grab it and give it to the controller if(new_global_plan_){ //make sure to set the new plan flag to false new_global_plan_ = false; ROS_DEBUG_NAMED("move_base","Got a new plan...swap pointers"); //do a pointer swap under mutex std::vector<geometry_msgs::PoseStamped>* temp_plan = controller_plan_; boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_); controller_plan_ = latest_plan_; latest_plan_ = temp_plan; lock.unlock(); ROS_DEBUG_NAMED("move_base","pointers swapped!"); if(!tc_->setPlan(*controller_plan_)){ //ABORT and SHUTDOWN COSTMAPS ROS_ERROR("Failed to pass global plan to the controller, aborting."); resetState(); //disable the planner thread lock.lock(); runPlanner_ = false; lock.unlock(); as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to pass global plan to the controller."); return true; } //make sure to reset recovery_index_ since we were able to find a valid plan if(recovery_trigger_ == PLANNING_R) recovery_index_ = 0; } //the move_base state machine, handles the control logic for navigation switch(state_){ //if we are in a planning state, then we'll attempt to make a plan case PLANNING: { boost::recursive_mutex::scoped_lock lock(planner_mutex_); runPlanner_ = true; planner_cond_.notify_one(); } ROS_DEBUG_NAMED("move_base","Waiting for plan, in the planning state."); break; //if we're controlling, we'll attempt to find valid velocity commands case CONTROLLING: ROS_DEBUG_NAMED("move_base","In controlling state."); //check to see if we've reached our goal if(tc_->isGoalReached()){ ROS_DEBUG_NAMED("move_base","Goal reached!"); resetState(); //disable the planner thread boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_); runPlanner_ = false; lock.unlock(); as_->setSucceeded(move_base_msgs::MoveBaseResult(), "Goal reached."); return true; } //check for an oscillation condition if(oscillation_timeout_ > 0.0 && last_oscillation_reset_ + ros::Duration(oscillation_timeout_) < ros::Time::now()) { publishZeroVelocity(); state_ = CLEARING; recovery_trigger_ = OSCILLATION_R; } { boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(controller_costmap_ros_->getCostmap()->getMutex())); //调用computeVelocityCommands进行局部规划 if(tc_->computeVelocityCommands(cmd_vel)){ ROS_DEBUG_NAMED( "move_base", "Got a valid command from the local planner: %.3lf, %.3lf, %.3lf", cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z ); last_valid_control_ = ros::Time::now(); //make sure that we send the velocity command to the base vel_pub_.publish(cmd_vel); if(recovery_trigger_ == CONTROLLING_R) recovery_index_ = 0; } else { ROS_DEBUG_NAMED("move_base", "The local planner could not find a valid plan."); ros::Time attempt_end = last_valid_control_ + ros::Duration(controller_patience_); //check if we've tried to find a valid control for longer than our time limit if(ros::Time::now() > attempt_end){ //we'll move into our obstacle clearing mode publishZeroVelocity(); state_ = CLEARING; recovery_trigger_ = CONTROLLING_R; } else{ //otherwise, if we can't find a valid control, we'll go back to planning last_valid_plan_ = ros::Time::now(); planning_retries_ = 0; state_ = PLANNING; publishZeroVelocity(); //enable the planner thread in case it isn't running on a clock boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_); runPlanner_ = true; planner_cond_.notify_one(); lock.unlock(); } } } break; //we'll try to clear out space with any user-provided recovery behaviors case CLEARING: ROS_DEBUG_NAMED("move_base","In clearing/recovery state"); //we'll invoke whatever recovery behavior we're currently on if they're enabled if(recovery_behavior_enabled_ && recovery_index_ < recovery_behaviors_.size()){ ROS_DEBUG_NAMED("move_base_recovery","Executing behavior %u of %zu", recovery_index_, recovery_behaviors_.size()); recovery_behaviors_[recovery_index_]->runBehavior(); //we at least want to give the robot some time to stop oscillating after executing the behavior last_oscillation_reset_ = ros::Time::now(); //we'll check if the recovery behavior actually worked ROS_DEBUG_NAMED("move_base_recovery","Going back to planning state"); last_valid_plan_ = ros::Time::now(); planning_retries_ = 0; state_ = PLANNING; //update the index of the next recovery behavior that we'll try recovery_index_++; } else{ ROS_DEBUG_NAMED("move_base_recovery","All recovery behaviors have failed, locking the planner and disabling it."); //disable the planner thread boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_); runPlanner_ = false; lock.unlock(); ROS_DEBUG_NAMED("move_base_recovery","Something should abort after this."); if(recovery_trigger_ == CONTROLLING_R){ ROS_ERROR("Aborting because a valid control could not be found. Even after executing all recovery behaviors"); as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid control. Even after executing recovery behaviors."); } else if(recovery_trigger_ == PLANNING_R){ ROS_ERROR("Aborting because a valid plan could not be found. Even after executing all recovery behaviors"); as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid plan. Even after executing recovery behaviors."); } else if(recovery_trigger_ == OSCILLATION_R){ ROS_ERROR("Aborting because the robot appears to be oscillating over and over. Even after executing all recovery behaviors"); as_->setAborted(move_base_msgs::MoveBaseResult(), "Robot is oscillating. Even after executing recovery behaviors."); } resetState(); return true; } break; default: ROS_ERROR("This case should never be reached, something is wrong, aborting"); resetState(); //disable the planner thread boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_); runPlanner_ = false; lock.unlock(); as_->setAborted(move_base_msgs::MoveBaseResult(), "Reached a case that should not be hit in move_base. This is a bug, please report it."); return true; } //we aren't done yet return false; } |
本作品采用知识共享署名 4.0 国际许可协议进行许可。