00001 #include <costmap_converter/costmap_to_dynamic_obstacles/costmap_to_dynamic_obstacles.h>
00002
00003 #include <pluginlib/class_list_macros.h>
00004 #include <tf/tf.h>
00005
00006 PLUGINLIB_EXPORT_CLASS(costmap_converter::CostmapToDynamicObstacles, costmap_converter::BaseCostmapToPolygons)
00007
00008 namespace costmap_converter
00009 {
00010
00011 CostmapToDynamicObstacles::CostmapToDynamicObstacles() : BaseCostmapToPolygons()
00012 {
00013 ego_vel_.x = ego_vel_.y = ego_vel_.z = 0;
00014 costmap_ = nullptr;
00015 dynamic_recfg_ = nullptr;
00016 }
00017
00018 CostmapToDynamicObstacles::~CostmapToDynamicObstacles()
00019 {
00020 if(dynamic_recfg_ != nullptr)
00021 delete dynamic_recfg_;
00022 }
00023
00024 void CostmapToDynamicObstacles::initialize(ros::NodeHandle nh)
00025 {
00026 costmap_ = nullptr;
00027
00028
00029 ros::NodeHandle gn;
00030 odom_sub_ = gn.subscribe(odom_topic_, 1, &CostmapToDynamicObstacles::odomCallback, this);
00031
00032 nh.param("publish_static_obstacles", publish_static_obstacles_, publish_static_obstacles_);
00033
00035
00036 BackgroundSubtractor::Params bg_sub_params;
00037
00038 bg_sub_params.alpha_slow = 0.3;
00039 nh.param("alpha_slow", bg_sub_params.alpha_slow, bg_sub_params.alpha_slow);
00040
00041 bg_sub_params.alpha_fast = 0.85;
00042 nh.param("alpha_fast", bg_sub_params.alpha_fast, bg_sub_params.alpha_fast);
00043
00044 bg_sub_params.beta = 0.85;
00045 nh.param("beta", bg_sub_params.beta, bg_sub_params.beta);
00046
00047 bg_sub_params.min_occupancy_probability = 180;
00048 nh.param("min_occupancy_probability", bg_sub_params.min_occupancy_probability, bg_sub_params.min_occupancy_probability);
00049
00050 bg_sub_params.min_sep_between_fast_and_slow_filter = 80;
00051 nh.param("min_sep_between_slow_and_fast_filter", bg_sub_params.min_sep_between_fast_and_slow_filter, bg_sub_params.min_sep_between_fast_and_slow_filter);
00052
00053 bg_sub_params.max_occupancy_neighbors = 100;
00054 nh.param("max_occupancy_neighbors", bg_sub_params.max_occupancy_neighbors, bg_sub_params.max_occupancy_neighbors);
00055
00056 bg_sub_params.morph_size = 1;
00057 nh.param("morph_size", bg_sub_params.morph_size, bg_sub_params.morph_size);
00058
00059 bg_sub_ = std::unique_ptr<BackgroundSubtractor>(new BackgroundSubtractor(bg_sub_params));
00060
00062
00063 BlobDetector::Params blob_det_params;
00064
00065 blob_det_params.filterByColor = true;
00066 blob_det_params.blobColor = 255;
00067 blob_det_params.thresholdStep = 256;
00068 blob_det_params.minThreshold = 127;
00069 blob_det_params.maxThreshold = 255;
00070 blob_det_params.minRepeatability = 1;
00071
00072 blob_det_params.minDistBetweenBlobs = 10;
00073 nh.param("min_distance_between_blobs", blob_det_params.minDistBetweenBlobs, blob_det_params.minDistBetweenBlobs);
00074
00075 blob_det_params.filterByArea = true;
00076 nh.param("filter_by_area", blob_det_params.filterByArea, blob_det_params.filterByArea);
00077
00078 blob_det_params.minArea = 3;
00079 nh.param("min_area", blob_det_params.minArea, blob_det_params.minArea);
00080
00081 blob_det_params.maxArea = 300;
00082 nh.param("max_area", blob_det_params.maxArea, blob_det_params.maxArea);
00083
00084 blob_det_params.filterByCircularity = true;
00085 nh.param("filter_by_circularity", blob_det_params.filterByCircularity, blob_det_params.filterByCircularity);
00086
00087 blob_det_params.minCircularity = 0.2;
00088 nh.param("min_circularity", blob_det_params.minCircularity, blob_det_params.minCircularity);
00089
00090 blob_det_params.maxCircularity = 1;
00091 nh.param("max_circularity", blob_det_params.maxCircularity, blob_det_params.maxCircularity);
00092
00093 blob_det_params.filterByInertia = true;
00094 nh.param("filter_by_intertia", blob_det_params.filterByInertia, blob_det_params.filterByInertia);
00095
00096 blob_det_params.minInertiaRatio = 0.2;
00097 nh.param("min_inertia_ratio", blob_det_params.minInertiaRatio, blob_det_params.minInertiaRatio);
00098
00099 blob_det_params.maxInertiaRatio = 1;
00100 nh.param("max_intertia_ratio", blob_det_params.maxInertiaRatio, blob_det_params.maxInertiaRatio);
00101
00102 blob_det_params.filterByConvexity = false;
00103 nh.param("filter_by_convexity", blob_det_params.filterByConvexity, blob_det_params.filterByConvexity);
00104
00105 blob_det_params.minConvexity = 0;
00106 nh.param("min_convexity", blob_det_params.minConvexity, blob_det_params.minConvexity);
00107
00108 blob_det_params.maxConvexity = 1;
00109 nh.param("max_convexity", blob_det_params.maxConvexity, blob_det_params.maxConvexity);
00110
00111 blob_det_ = BlobDetector::create(blob_det_params);
00112
00114
00115 CTracker::Params tracker_params;
00116 tracker_params.dt = 0.2;
00117 nh.param("dt", tracker_params.dt, tracker_params.dt);
00118
00119 tracker_params.dist_thresh = 60.0;
00120 nh.param("dist_thresh", tracker_params.dist_thresh, tracker_params.dist_thresh);
00121
00122 tracker_params.max_allowed_skipped_frames = 3;
00123 nh.param("max_allowed_skipped_frames", tracker_params.max_allowed_skipped_frames, tracker_params.max_allowed_skipped_frames);
00124
00125 tracker_params.max_trace_length = 10;
00126 nh.param("max_trace_length", tracker_params.max_trace_length, tracker_params.max_trace_length);
00127
00128 tracker_ = std::unique_ptr<CTracker>(new CTracker(tracker_params));
00129
00130
00131 dynamic_recfg_ = new dynamic_reconfigure::Server<CostmapToDynamicObstaclesConfig>(nh);
00132 dynamic_reconfigure::Server<CostmapToDynamicObstaclesConfig>::CallbackType cb = boost::bind(&CostmapToDynamicObstacles::reconfigureCB, this, _1, _2);
00133 dynamic_recfg_->setCallback(cb);
00134 }
00135
00136 void CostmapToDynamicObstacles::compute()
00137 {
00138 if (costmap_mat_.empty())
00139 return;
00140
00142
00143 int origin_x = round(costmap_->getOriginX() / costmap_->getResolution());
00144 int origin_y = round(costmap_->getOriginY() / costmap_->getResolution());
00145
00146
00147
00148 bg_sub_->apply(costmap_mat_, fg_mask_, origin_x, origin_y);
00149
00150
00151 if (fg_mask_.empty())
00152 return;
00153
00154 cv::Mat bg_mat;
00155 if (publish_static_obstacles_)
00156 {
00157
00158 bg_mat = costmap_mat_ - fg_mask_;
00159
00160 }
00161
00162
00164
00165 blob_det_->detect(fg_mask_, keypoints_);
00166 std::vector<std::vector<cv::Point>> contours = blob_det_->getContours();
00167
00168
00170
00171
00172 std::vector<Point_t> detected_centers(keypoints_.size());
00173 for (int i = 0; i < keypoints_.size(); i++)
00174 {
00175 detected_centers.at(i).x = keypoints_.at(i).pt.x;
00176 detected_centers.at(i).y = keypoints_.at(i).pt.y;
00177 detected_centers.at(i).z = 0;
00178 }
00179
00180 tracker_->Update(detected_centers, contours);
00181
00182
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00198 ObstacleArrayPtr obstacles(new ObstacleArrayMsg);
00199
00200 obstacles->header.stamp = ros::Time::now();
00201 obstacles->header.frame_id = "/map";
00202
00203
00204 for (unsigned int i = 0; i < (unsigned int)tracker_->tracks.size(); ++i)
00205 {
00206 geometry_msgs::Polygon polygon;
00207
00208
00209 std::vector<Point_t> contour;
00210 getContour(i, contour);
00211
00212
00213 for (const Point_t& pt : contour)
00214 {
00215 polygon.points.emplace_back();
00216 polygon.points.back().x = pt.x;
00217 polygon.points.back().y = pt.y;
00218 polygon.points.back().z = 0;
00219 }
00220
00221 obstacles->obstacles.emplace_back();
00222 obstacles->obstacles.back().polygon = polygon;
00223
00224
00225 obstacles->obstacles.back().id = tracker_->tracks.at(i)->track_id;
00226
00227
00228 geometry_msgs::QuaternionStamped orientation;
00229
00230 Point_t vel = getEstimatedVelocityOfObject(i);
00231 double yaw = std::atan2(vel.y, vel.x);
00232
00233 obstacles->obstacles.back().orientation = tf::createQuaternionMsgFromYaw(yaw);
00234
00235
00236 geometry_msgs::TwistWithCovariance velocities;
00237
00238
00239 velocities.twist.linear.x = vel.x;
00240 velocities.twist.linear.y = vel.y;
00241 velocities.twist.linear.z = 0;
00242 velocities.twist.angular.x = 0;
00243 velocities.twist.angular.y = 0;
00244 velocities.twist.angular.z = 0;
00245
00246
00247 velocities.covariance = {1, 0, 0, 0, 0, 0,
00248 0, 1, 0, 0, 0, 0,
00249 0, 0, 1, 0, 0, 0,
00250 0, 0, 0, 1, 0, 0,
00251 0, 0, 0, 0, 1, 0,
00252 0, 0, 0, 0, 0, 1};
00253
00254 obstacles->obstacles.back().velocities = velocities;
00255 }
00256
00258 if (publish_static_obstacles_)
00259 {
00260 uchar* img_data = bg_mat.data;
00261 int width = bg_mat.cols;
00262 int height = bg_mat.rows;
00263 int stride = bg_mat.step;
00264
00265 for(int i = 0; i < height; i++)
00266 {
00267 for(int j = 0; j < width; j++)
00268 {
00269 uchar value = img_data[i * stride + j];
00270 if (value > 0)
00271 {
00272
00273 obstacles->obstacles.emplace_back();
00274 geometry_msgs::Point32 pt;
00275 pt.x = (double)j*costmap_->getResolution() + costmap_->getOriginX();
00276 pt.y = (double)i*costmap_->getResolution() + costmap_->getOriginY();
00277 obstacles->obstacles.back().polygon.points.push_back(pt);
00278 obstacles->obstacles.back().velocities.twist.linear.x = 0;
00279 obstacles->obstacles.back().velocities.twist.linear.y = 0;
00280 obstacles->obstacles.back().id = -1;
00281 }
00282 }
00283 }
00284 }
00285
00286 updateObstacleContainer(obstacles);
00287 }
00288
00289 void CostmapToDynamicObstacles::setCostmap2D(costmap_2d::Costmap2D* costmap)
00290 {
00291 if (!costmap)
00292 return;
00293
00294 costmap_ = costmap;
00295
00296 updateCostmap2D();
00297 }
00298
00299 void CostmapToDynamicObstacles::updateCostmap2D()
00300 {
00301 if (!costmap_->getMutex())
00302 {
00303 ROS_ERROR("Cannot update costmap since the mutex pointer is null");
00304 return;
00305 }
00306 costmap_2d::Costmap2D::mutex_t::scoped_lock lock(*costmap_->getMutex());
00307
00308
00309
00310
00311 costmap_mat_ = cv::Mat(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY(), CV_8UC1,
00312 costmap_->getCharMap());
00313 }
00314
00315 ObstacleArrayConstPtr CostmapToDynamicObstacles::getObstacles()
00316 {
00317 boost::mutex::scoped_lock lock(mutex_);
00318 return obstacles_;
00319 }
00320
00321 void CostmapToDynamicObstacles::updateObstacleContainer(ObstacleArrayPtr obstacles)
00322 {
00323 boost::mutex::scoped_lock lock(mutex_);
00324 obstacles_ = obstacles;
00325 }
00326
00327 Point_t CostmapToDynamicObstacles::getEstimatedVelocityOfObject(unsigned int idx)
00328 {
00329
00330 Point_t vel = tracker_->tracks.at(idx)->getEstimatedVelocity() * costmap_->getResolution() + ego_vel_;
00331
00332
00333
00334 return vel;
00335 }
00336
00337 void CostmapToDynamicObstacles::odomCallback(const nav_msgs::Odometry::ConstPtr& msg)
00338 {
00339 ROS_INFO_ONCE("CostmapToDynamicObstacles: odom received.");
00340
00341 tf::Quaternion pose;
00342 tf::quaternionMsgToTF(msg->pose.pose.orientation, pose);
00343
00344 tf::Vector3 twistLinear;
00345 tf::vector3MsgToTF(msg->twist.twist.linear, twistLinear);
00346
00347
00348 tf::Vector3 vel = tf::quatRotate(pose, twistLinear);
00349 ego_vel_.x = vel.x();
00350 ego_vel_.y = vel.y();
00351 ego_vel_.z = vel.z();
00352 }
00353
00354 void CostmapToDynamicObstacles::reconfigureCB(CostmapToDynamicObstaclesConfig& config, uint32_t level)
00355 {
00356 publish_static_obstacles_ = config.publish_static_obstacles;
00357
00358
00359 BackgroundSubtractor::Params bg_sub_params;
00360 bg_sub_params.alpha_slow = config.alpha_slow;
00361 bg_sub_params.alpha_fast = config.alpha_fast;
00362 bg_sub_params.beta = config.beta;
00363 bg_sub_params.min_sep_between_fast_and_slow_filter = config.min_sep_between_slow_and_fast_filter;
00364 bg_sub_params.min_occupancy_probability = config.min_occupancy_probability;
00365 bg_sub_params.max_occupancy_neighbors = config.max_occupancy_neighbors;
00366 bg_sub_params.morph_size = config.morph_size;
00367 bg_sub_->updateParameters(bg_sub_params);
00368
00369
00370 BlobDetector::Params blob_det_params;
00371
00372 blob_det_params.filterByColor = true;
00373 blob_det_params.blobColor = 255;
00374 blob_det_params.thresholdStep = 256;
00375 blob_det_params.minThreshold = 127;
00376 blob_det_params.maxThreshold = 255;
00377 blob_det_params.minRepeatability = 1;
00378 blob_det_params.minDistBetweenBlobs = config.min_distance_between_blobs;
00379 blob_det_params.filterByArea = config.filter_by_area;
00380 blob_det_params.minArea = config.min_area;
00381 blob_det_params.maxArea = config.max_area;
00382 blob_det_params.filterByCircularity = config.filter_by_circularity;
00383 blob_det_params.minCircularity = config.min_circularity;
00384 blob_det_params.maxCircularity = config.max_circularity;
00385 blob_det_params.filterByInertia = config.filter_by_inertia;
00386 blob_det_params.minInertiaRatio = config.min_inertia_ratio;
00387 blob_det_params.maxInertiaRatio = config.max_inertia_ratio;
00388 blob_det_params.filterByConvexity = config.filter_by_convexity;
00389 blob_det_params.minConvexity = config.min_convexity;
00390 blob_det_params.maxConvexity = config.max_convexity;
00391 blob_det_->updateParameters(blob_det_params);
00392
00393
00394 CTracker::Params tracking_params;
00395 tracking_params.dt = config.dt;
00396 tracking_params.dist_thresh = config.dist_thresh;
00397 tracking_params.max_allowed_skipped_frames = config.max_allowed_skipped_frames;
00398 tracking_params.max_trace_length = config.max_trace_length;
00399 tracker_->updateParameters(tracking_params);
00400 }
00401
00402 void CostmapToDynamicObstacles::getContour(unsigned int idx, std::vector<Point_t>& contour)
00403 {
00404 assert(!tracker_->tracks.empty() && idx < tracker_->tracks.size());
00405
00406 contour.clear();
00407
00408
00409 std::vector<cv::Point> contour2i = tracker_->tracks.at(idx)->getLastContour();
00410
00411 contour.reserve(contour2i.size());
00412
00413 Point_t costmap_origin(costmap_->getOriginX(), costmap_->getOriginY(), 0);
00414
00415 for (std::size_t i = 0; i < contour2i.size(); ++i)
00416 {
00417 contour.push_back((Point_t(contour2i.at(i).x, contour2i.at(i).y, 0.0)*costmap_->getResolution())
00418 + costmap_origin);
00419 }
00420
00421 }
00422
00423 void CostmapToDynamicObstacles::visualize(const std::string& name, const cv::Mat& image)
00424 {
00425 if (!image.empty())
00426 {
00427 cv::Mat im = image.clone();
00428 cv::flip(im, im, 0);
00429 cv::imshow(name, im);
00430 cv::waitKey(1);
00431 }
00432 }
00433 }