Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
costmap_converter::CostmapToDynamicObstacles Class Reference

This class converts the costmap_2d into dynamic obstacles. More...

#include <costmap_to_dynamic_obstacles.h>

Inheritance diagram for costmap_converter::CostmapToDynamicObstacles:
Inheritance graph
[legend]

List of all members.

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< BlobDetectorblob_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< CTrackertracker_

Detailed Description

This class converts the costmap_2d into dynamic obstacles.

Static obstacles are treated as point obstacles.

Todo:
allow different plugins for both static and dynamic obstacles (arbitrary combinations)

Definition at line 77 of file costmap_to_dynamic_obstacles.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 11 of file costmap_to_dynamic_obstacles.cpp.

Destructor.

Definition at line 18 of file costmap_to_dynamic_obstacles.cpp.


Member Function Documentation

This method performs the actual work (conversion of the costmap to obstacles)

Implements costmap_converter::BaseCostmapToPolygons.

Definition at line 136 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].

Parameters:
[in]idxIndex of the tracked object in the tracker
[out]contourvector of Point_t, which represents the last observed contour in [m] in x,y,z coordinates

Definition at line 402 of file costmap_to_dynamic_obstacles.cpp.

Converts the estimated velocity of a tracked object to m/s and returns it.

Parameters:
idxIndex of the tracked object in the tracker
Returns:
Point_t, which represents velocity in [m/s] of object(idx) in x,y,z coordinates

Definition at line 327 of file costmap_to_dynamic_obstacles.cpp.

Get a shared instance of the current obstacle container.

Remarks:
If compute() or startWorker() has not been called before, this method returns an empty instance!
Returns:
Shared instance of the current obstacle container

Reimplemented from costmap_converter::BaseCostmapToPolygons.

Definition at line 315 of file costmap_to_dynamic_obstacles.cpp.

void costmap_converter::CostmapToDynamicObstacles::initialize ( ros::NodeHandle  nh) [virtual]

Initialize the plugin.

Parameters:
nhNodehandle 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.

Parameters:
msgThe Pointer to the nav_msgs::Odometry of the observing robot

Definition at line 337 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

Parameters:
configReference to the dynamic reconfigure config
levelDynamic reconfigure level

Definition at line 354 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.

See also:
updateCostmap2D
Parameters:
costmapPointer to the costmap2d source

Implements costmap_converter::BaseCostmapToPolygons.

Definition at line 289 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.

Warning:
The method must be called before initialize()

Some plugins might require odometry information to compensate the robot's ego motion

Parameters:
odom_topictopic name

Reimplemented from costmap_converter::BaseCostmapToPolygons.

Definition at line 132 of file costmap_to_dynamic_obstacles.h.

Get updated data from the previously set Costmap2D.

See also:
setCostmap2D

Implements costmap_converter::BaseCostmapToPolygons.

Definition at line 299 of file costmap_to_dynamic_obstacles.cpp.

Thread-safe update of the internal obstacle container (that is shared using getObstacles() from outside this class)

Parameters:
obstaclesUpdated obstacle container

Definition at line 321 of file costmap_to_dynamic_obstacles.cpp.

void costmap_converter::CostmapToDynamicObstacles::visualize ( const std::string &  name,
const cv::Mat &  image 
)

OpenCV Visualization.

Parameters:
nameId/name of the opencv window
imageImage to be visualized

Definition at line 423 of file costmap_to_dynamic_obstacles.cpp.


Member Data Documentation

Definition at line 177 of file costmap_to_dynamic_obstacles.h.

Definition at line 178 of file costmap_to_dynamic_obstacles.h.

Definition at line 173 of file costmap_to_dynamic_obstacles.h.

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.

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.

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.

Definition at line 184 of file costmap_to_dynamic_obstacles.h.

Definition at line 185 of file costmap_to_dynamic_obstacles.h.

Definition at line 180 of file costmap_to_dynamic_obstacles.h.


The documentation for this class was generated from the following files:


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Wed Sep 20 2017 03:00:37