// place the new obstacles into a priority queue // each with a priority of zero to begin with for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it) { const Observation& obs = *it; const pcl::PointCloud<pcl::PointXYZ>& cloud = *(obs.cloud_); // obstacle_range_ 其实就是参数 obstacle_range double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_; // 遍历点云中的每一个点 for (unsignedint i = 0; i < cloud.points.size(); ++i) { double px = cloud.points[i].x, py = cloud.points[i].y, pz = cloud.points[i].z; // if the obstacle is too high or too far away from the robot we won't add it if (pz > max_obstacle_height_) { ROS_DEBUG("The point is too high"); continue; } // compute the squared distance from the hitpoint to the pointcloud's origin double sq_dist = (px - obs.origin_.x) * (px - obs.origin_.x) + (py - obs.origin_.y) * (py - obs.origin_.y) + (pz - obs.origin_.z) * (pz - obs.origin_.z);
// if the point is far enough away... we won't consider it if (sq_dist >= sq_obstacle_range) { ROS_DEBUG("The point is too far away"); continue; } // now we need to compute the map coordinates for the observation unsignedint mx, my; if (!worldToMap(px, py, mx, my)) { ROS_DEBUG("Computing map coords failed"); continue; } unsignedint index = getIndex(mx, my); costmap_[index] = LETHAL_OBSTACLE; touch(px, py, min_x, min_y, max_x, max_y); } } updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
ros::Time now = ros::Time::now(); if (last_publish_ + publish_cycle < now) { publisher_->publishCostmap(); last_publish_ = now; } } r.sleep(); // make sure to sleep for the remainder of our cycle time if (r.cycleTime() > ros::Duration(1 / frequency)) ROS_WARN("Map update loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", frequency, r.cycleTime().toSec()); } }
for (size_t i = 0; i < message.ranges.size(); i++) { float range = message.ranges[ i ]; if ( (!std::isfinite(range) && range > 0) ) { message.ranges[ i ] = message.range_max - epsilon; } }
if(!planner_->makePlan(start, goal, plan) || plan.empty()) { ROS_DEBUG_NAMED("move_base","Failed to find a plan to point (%.2f, %.2f)", goal.pose.position.x, goal.pose.position.y);
for (unsignedint i = 0; i < clearing_observations.size(); ++i) { raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y); }
清理传感器到障碍物间的cell,会首先处理测量值越界的问题,然后调用
1 2 3 4
MarkCell marker(costmap_, FREE_SPACE); // and finally... we can execute our trace to clear obstacles along that line raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range); updateRaytraceBounds(ox, oy, wx, wy, clearing_observation.raytrace_range_, min_x, min_y, max_x, max_y);
/* * @brief Given distance in the world, convert it to cells * @param world_dist: The world distance * @return The equivalent cell distance */ unsignedintCostmap2D::cellDistance(double world_dist) { double cells_dist = max(0.0, ceil(world_dist / resolution_)); return (unsignedint)cells_dist; }
可能是Bresenham2D的round off error(舍入误差)造成的. It marks a particular cell as obstacle but the next time when the sensor reading changes instantaneously, it no longer traces it through the same path and hence, the blob seem remains in the costmap.
added 2 lines of code to the Bresenham2D algorithm. This basically clears the cell to the left and right of the grid through which the Line segment constructed by the algorithm passes. This results in loosing some resolution of the map, but the solution works pretty well in real life application
<nodepkg="octomap_server"type="octomap_server_node"name="octomap_server"> <!-- resolution in meters per pixel --> <paramname="resolution"value="0.05"/> <!-- name of the fixed frame, needs to be "/map" for SLAM --> <paramname="frame_id"type="string"value="$(arg frame_id)"/> <paramname="sensor_model/max_range"value="150.0"/> <paramname="latch"value="true"/> <!-- 需要和 publish_pointcloud 的frame_id相同,否则会导致Octomap没有发布数据 --> <!-- topic from where pointcloud2 messages are subscribed,改为自己的点云话题 --> <remapfrom="/cloud_in"to="$(arg cloud_topic)"/> <remapfrom="/projected_map"to="$(arg map_topic)"/> </node>
octomap topics are 3D occupancy maps, which would be used by some other 3D planning approach (e.g., move_it). They are not the same as /grid_map or /proj_map from rtabmap_ros. For 3D trajectories (having to move in Z, e.g., quadcopter), then using OctoMap with OMPL/move_it can be another approach, though not sure if there is one most popular approach for the 3D case.