43 #ifndef COSTMAP_TO_DYNAMIC_OBSTACLES_H_ 44 #define COSTMAP_TO_DYNAMIC_OBSTACLES_H_ 48 #include <nav_msgs/Odometry.h> 54 #include <opencv2/features2d/features2d.hpp> 55 #include <opencv2/video/tracking.hpp> 58 #include <costmap_converter/CostmapToDynamicObstaclesConfig.h> 59 #include <dynamic_reconfigure/server.h> 142 void visualize(
const std::string& name,
const cv::Mat& image);
161 void getContour(
unsigned int idx, std::vector<Point_t>& contour);
177 std::unique_ptr<BackgroundSubtractor>
bg_sub_;
187 dynamic_reconfigure::Server<CostmapToDynamicObstaclesConfig>*
197 void odomCallback(
const nav_msgs::Odometry::ConstPtr &msg);
207 void reconfigureCB(CostmapToDynamicObstaclesConfig &config, uint32_t level);
dynamic_reconfigure::Server< CostmapToDynamicObstaclesConfig > * dynamic_recfg_
std::unique_ptr< CTracker > tracker_
ObstacleArrayPtr obstacles_
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
modifications at runtime
cv::Point3_< track_t > Point_t
virtual void setOdomTopic(const std::string &odom_topic)
Set name of robot's odometry topic.
virtual void setCostmap2D(costmap_2d::Costmap2D *costmap)
Pass a pointer to the costmap to the plugin.
virtual void updateCostmap2D()
Get updated data from the previously set Costmap2D.
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
CostmapToDynamicObstacles()
Constructor.
void updateObstacleContainer(ObstacleArrayPtr obstacles)
Thread-safe update of the internal obstacle container (that is shared using getObstacles() from outsi...
Point_t getEstimatedVelocityOfObject(unsigned int idx)
Converts the estimated velocity of a tracked object to m/s and returns it.
virtual void compute()
This method performs the actual work (conversion of the costmap to obstacles)
virtual ~CostmapToDynamicObstacles()
Destructor.
This class converts the costmap_2d into dynamic obstacles.
ros::Subscriber odom_sub_
bool publish_static_obstacles_
ObstacleArrayConstPtr getObstacles()
Get a shared instance of the current obstacle container.
costmap_2d::Costmap2D * costmap_
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].
std::vector< cv::KeyPoint > keypoints_
cv::Ptr< BlobDetector > blob_det_
void reconfigureCB(CostmapToDynamicObstaclesConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
void visualize(const std::string &name, const cv::Mat &image)
OpenCV Visualization.
std::unique_ptr< BackgroundSubtractor > bg_sub_