update
This commit is contained in:
@@ -527,8 +527,7 @@ void move_base::MoveBase::addLaserScan(const std::string &laser_scan_name, robot
|
||||
// for (size_t i = 0; i < laser_scan.intensities.size(); i++) {
|
||||
// intensities_str << laser_scan.intensities[i] << " ";
|
||||
// }
|
||||
// robot::log_info("intensities: %s", intensities_str.str().c_str());
|
||||
// robot::log_info("--------------------------------");
|
||||
// robot::log_error("intensities: %s", intensities_str.str().c_str());
|
||||
|
||||
updateLocalCostmap<robot_sensor_msgs::LaserScan>(laser_scan, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name);
|
||||
updateGlobalCostmap<robot_sensor_msgs::LaserScan>(laser_scan, robot_costmap_2d::LayerType::VOXEL_LAYER, laser_scan_name);
|
||||
@@ -2198,7 +2197,6 @@ void move_base::MoveBase::planThread()
|
||||
// if we didn't get a plan and we are in the planning state (the robot isn't moving)
|
||||
else if (state_ == move_base::PLANNING)
|
||||
{
|
||||
robot::log_info("No Plan...");
|
||||
robot::Time attempt_end = last_valid_plan_ + robot::Duration(planner_patience_);
|
||||
|
||||
// check if we've tried to make a plan for over our time limit or our maximum number of retries
|
||||
|
||||
Reference in New Issue
Block a user