This class converts the costmap_2d into dynamic obstacles. More...
#include <costmap_to_dynamic_obstacles.h>
Public Member Functions | |
virtual void | compute () |
This method performs the actual work (conversion of the costmap to obstacles) | |
CostmapToDynamicObstacles () | |
Constructor. | |
ObstacleArrayConstPtr | getObstacles () |
Get a shared instance of the current obstacle container. | |
virtual void | initialize (ros::NodeHandle nh) |
Initialize the plugin. | |
virtual void | setCostmap2D (costmap_2d::Costmap2D *costmap) |
Pass a pointer to the costmap to the plugin. | |
virtual void | setOdomTopic (const std::string &odom_topic) |
Set name of robot's odometry topic. | |
virtual void | updateCostmap2D () |
Get updated data from the previously set Costmap2D. | |
void | visualize (const std::string &name, const cv::Mat &image) |
OpenCV Visualization. | |
virtual | ~CostmapToDynamicObstacles () |
Destructor. | |
Protected Member Functions | |
void | getContour (unsigned int idx, std::vector< Point_t > &contour) |
Gets the last observed contour of a object and converts it from [px] to [m]. | |
Point_t | getEstimatedVelocityOfObject (unsigned int idx) |
Converts the estimated velocity of a tracked object to m/s and returns it. | |
void | updateObstacleContainer (ObstacleArrayPtr obstacles) |
Thread-safe update of the internal obstacle container (that is shared using getObstacles() from outside this class) | |
Private Member Functions | |
void | odomCallback (const nav_msgs::Odometry::ConstPtr &msg) |
modifications at runtime | |
void | reconfigureCB (CostmapToDynamicObstaclesConfig &config, uint32_t level) |
Callback for the dynamic_reconfigure node. | |
Private Attributes | |
std::unique_ptr < BackgroundSubtractor > | bg_sub_ |
cv::Ptr< BlobDetector > | blob_det_ |
costmap_2d::Costmap2D * | costmap_ |
cv::Mat | costmap_mat_ |
dynamic_reconfigure::Server < CostmapToDynamicObstaclesConfig > * | dynamic_recfg_ |
Point_t | ego_vel_ |
cv::Mat | fg_mask_ |
std::vector< cv::KeyPoint > | keypoints_ |
boost::mutex | mutex_ |
ObstacleArrayPtr | obstacles_ |
ros::Subscriber | odom_sub_ |
std::string | odom_topic_ = "/odom" |
bool | publish_static_obstacles_ = true |
std::unique_ptr< CTracker > | tracker_ |
This class converts the costmap_2d into dynamic obstacles.
Static obstacles are treated as point obstacles.
Definition at line 77 of file costmap_to_dynamic_obstacles.h.
Constructor.
Definition at line 11 of file costmap_to_dynamic_obstacles.cpp.
Destructor.
Definition at line 18 of file costmap_to_dynamic_obstacles.cpp.
void costmap_converter::CostmapToDynamicObstacles::compute | ( | ) | [virtual] |
This method performs the actual work (conversion of the costmap to obstacles)
Implements costmap_converter::BaseCostmapToPolygons.
Definition at line 144 of file costmap_to_dynamic_obstacles.cpp.
void costmap_converter::CostmapToDynamicObstacles::getContour | ( | unsigned int | idx, |
std::vector< Point_t > & | contour | ||
) | [protected] |
Gets the last observed contour of a object and converts it from [px] to [m].
[in] | idx | Index of the tracked object in the tracker |
[out] | contour | vector of Point_t, which represents the last observed contour in [m] in x,y,z coordinates |
Definition at line 445 of file costmap_to_dynamic_obstacles.cpp.
Point_t costmap_converter::CostmapToDynamicObstacles::getEstimatedVelocityOfObject | ( | unsigned int | idx | ) | [protected] |
Converts the estimated velocity of a tracked object to m/s and returns it.
idx | Index of the tracked object in the tracker |
Definition at line 370 of file costmap_to_dynamic_obstacles.cpp.
Get a shared instance of the current obstacle container.
Reimplemented from costmap_converter::BaseCostmapToPolygons.
Definition at line 358 of file costmap_to_dynamic_obstacles.cpp.
void costmap_converter::CostmapToDynamicObstacles::initialize | ( | ros::NodeHandle | nh | ) | [virtual] |
Initialize the plugin.
nh | Nodehandle that defines the namespace for parameters |
Implements costmap_converter::BaseCostmapToPolygons.
Definition at line 24 of file costmap_to_dynamic_obstacles.cpp.
void costmap_converter::CostmapToDynamicObstacles::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) | [private] |
modifications at runtime
Callback for the odometry messages of the observing robot.
Used to convert the velocity of obstacles to the /map frame.
msg | The Pointer to the nav_msgs::Odometry of the observing robot |
Definition at line 380 of file costmap_to_dynamic_obstacles.cpp.
void costmap_converter::CostmapToDynamicObstacles::reconfigureCB | ( | CostmapToDynamicObstaclesConfig & | config, |
uint32_t | level | ||
) | [private] |
Callback for the dynamic_reconfigure node.
This callback allows to modify parameters dynamically at runtime without restarting the node
config | Reference to the dynamic reconfigure config |
level | Dynamic reconfigure level |
Definition at line 397 of file costmap_to_dynamic_obstacles.cpp.
void costmap_converter::CostmapToDynamicObstacles::setCostmap2D | ( | costmap_2d::Costmap2D * | costmap | ) | [virtual] |
Pass a pointer to the costmap to the plugin.
costmap | Pointer to the costmap2d source |
Implements costmap_converter::BaseCostmapToPolygons.
Definition at line 332 of file costmap_to_dynamic_obstacles.cpp.
virtual void costmap_converter::CostmapToDynamicObstacles::setOdomTopic | ( | const std::string & | odom_topic | ) | [inline, virtual] |
Set name of robot's odometry topic.
Some plugins might require odometry information to compensate the robot's ego motion
odom_topic | topic name |
Reimplemented from costmap_converter::BaseCostmapToPolygons.
Definition at line 132 of file costmap_to_dynamic_obstacles.h.
void costmap_converter::CostmapToDynamicObstacles::updateCostmap2D | ( | ) | [virtual] |
Get updated data from the previously set Costmap2D.
Implements costmap_converter::BaseCostmapToPolygons.
Definition at line 342 of file costmap_to_dynamic_obstacles.cpp.
void costmap_converter::CostmapToDynamicObstacles::updateObstacleContainer | ( | ObstacleArrayPtr | obstacles | ) | [protected] |
Thread-safe update of the internal obstacle container (that is shared using getObstacles() from outside this class)
obstacles | Updated obstacle container |
Definition at line 364 of file costmap_to_dynamic_obstacles.cpp.
void costmap_converter::CostmapToDynamicObstacles::visualize | ( | const std::string & | name, |
const cv::Mat & | image | ||
) |
OpenCV Visualization.
name | Id/name of the opencv window |
image | Image to be visualized |
Definition at line 466 of file costmap_to_dynamic_obstacles.cpp.
std::unique_ptr<BackgroundSubtractor> costmap_converter::CostmapToDynamicObstacles::bg_sub_ [private] |
Definition at line 177 of file costmap_to_dynamic_obstacles.h.
cv::Ptr<BlobDetector> costmap_converter::CostmapToDynamicObstacles::blob_det_ [private] |
Definition at line 178 of file costmap_to_dynamic_obstacles.h.
Definition at line 173 of file costmap_to_dynamic_obstacles.h.
cv::Mat costmap_converter::CostmapToDynamicObstacles::costmap_mat_ [private] |
Definition at line 174 of file costmap_to_dynamic_obstacles.h.
dynamic_reconfigure::Server<CostmapToDynamicObstaclesConfig>* costmap_converter::CostmapToDynamicObstacles::dynamic_recfg_ [private] |
Dynamic reconfigure server to allow config
Definition at line 188 of file costmap_to_dynamic_obstacles.h.
Definition at line 182 of file costmap_to_dynamic_obstacles.h.
cv::Mat costmap_converter::CostmapToDynamicObstacles::fg_mask_ [private] |
Definition at line 176 of file costmap_to_dynamic_obstacles.h.
std::vector<cv::KeyPoint> costmap_converter::CostmapToDynamicObstacles::keypoints_ [private] |
Definition at line 179 of file costmap_to_dynamic_obstacles.h.
boost::mutex costmap_converter::CostmapToDynamicObstacles::mutex_ [private] |
Definition at line 172 of file costmap_to_dynamic_obstacles.h.
Definition at line 175 of file costmap_to_dynamic_obstacles.h.
Definition at line 181 of file costmap_to_dynamic_obstacles.h.
std::string costmap_converter::CostmapToDynamicObstacles::odom_topic_ = "/odom" [private] |
Definition at line 184 of file costmap_to_dynamic_obstacles.h.
bool costmap_converter::CostmapToDynamicObstacles::publish_static_obstacles_ = true [private] |
Definition at line 185 of file costmap_to_dynamic_obstacles.h.
std::unique_ptr<CTracker> costmap_converter::CostmapToDynamicObstacles::tracker_ [private] |
Definition at line 180 of file costmap_to_dynamic_obstacles.h.