62 bool track_unknown_space;
64 if (track_unknown_space)
73 double transform_tolerance;
74 nh.param(
"transform_tolerance", transform_tolerance, 0.2);
76 std::string topics_string;
78 nh.param(
"observation_sources", topics_string, std::string(
""));
79 ROS_INFO(
" Subscribed to Topics: %s", topics_string.c_str());
82 std::stringstream ss(topics_string);
90 double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
91 std::string topic, sensor_frame, data_type;
92 bool inf_is_valid, clearing, marking;
94 source_node.
param(
"topic", topic, source);
95 source_node.
param(
"sensor_frame", sensor_frame, std::string(
""));
96 source_node.
param(
"observation_persistence", observation_keep_time, 0.0);
97 source_node.
param(
"expected_update_rate", expected_update_rate, 0.0);
98 source_node.
param(
"data_type", data_type, std::string(
"PointCloud"));
99 source_node.
param(
"min_obstacle_height", min_obstacle_height, 0.0);
100 source_node.
param(
"max_obstacle_height", max_obstacle_height, 2.0);
101 source_node.
param(
"inf_is_valid", inf_is_valid,
false);
102 source_node.
param(
"clearing", clearing,
false);
103 source_node.
param(
"marking", marking,
true);
105 if (!(data_type ==
"PointCloud2" || data_type ==
"PointCloud" || data_type ==
"LaserScan"))
107 ROS_FATAL(
"Only topics that use point clouds or laser scans are currently supported");
108 throw std::runtime_error(
"Only topics that use point clouds or laser scans are currently supported");
111 std::string raytrace_range_param_name, obstacle_range_param_name;
114 double obstacle_range = 2.5;
115 if (source_node.
searchParam(
"obstacle_range", obstacle_range_param_name))
117 source_node.
getParam(obstacle_range_param_name, obstacle_range);
121 double raytrace_range = 3.0;
122 if (source_node.
searchParam(
"raytrace_range", raytrace_range_param_name))
124 source_node.
getParam(raytrace_range_param_name, raytrace_range);
127 ROS_DEBUG(
"Creating an observation buffer for source %s, topic %s, frame %s", source.c_str(), topic.c_str(),
128 sensor_frame.c_str());
133 > (
new ObservationBuffer(topic, observation_keep_time, expected_update_rate, min_obstacle_height,
135 sensor_frame, transform_tolerance)));
146 "Created an observation buffer for source %s, topic %s, global frame: %s, " 147 "expected update rate: %.2f, observation persistence: %.2f",
148 source.c_str(), topic.c_str(),
global_frame_.c_str(), expected_update_rate, observation_keep_time);
151 if (data_type ==
"LaserScan")
174 else if (data_type ==
"PointCloud")
181 ROS_WARN(
"obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
186 filter->registerCallback(
199 ROS_WARN(
"obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
204 filter->registerCallback(
211 if (sensor_frame !=
"")
213 std::vector < std::string > target_frames;
215 target_frames.push_back(sensor_frame);
226 dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>(nh);
227 dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>::CallbackType cb = boost::bind(
229 dsrv_->setCallback(cb);
249 sensor_msgs::PointCloud2 cloud;
250 cloud.header = message->header;
259 ROS_WARN(
"High fidelity enabled, but TF returned a transform exception to frame %s: %s",
global_frame_.c_str(),
266 buffer->bufferCloud(cloud);
275 sensor_msgs::LaserScan message = *raw_message;
276 for (
size_t i = 0; i < message.ranges.size(); i++)
278 float range = message.ranges[ i ];
279 if (!std::isfinite(range) && range > 0)
281 message.ranges[ i ] = message.range_max - epsilon;
286 sensor_msgs::PointCloud2 cloud;
287 cloud.header = message.header;
296 ROS_WARN(
"High fidelity enabled, but TF returned a transform exception to frame %s: %s",
303 buffer->bufferCloud(cloud);
310 sensor_msgs::PointCloud2 cloud2;
314 ROS_ERROR(
"Failed to convert a PointCloud to a PointCloud2, dropping message");
320 buffer->bufferCloud(cloud2);
329 buffer->bufferCloud(*message);
334 double* min_y,
double* max_x,
double* max_y)
343 std::vector<Observation> observations, clearing_observations;
355 for (
unsigned int i = 0; i < clearing_observations.size(); ++i)
361 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
365 const sensor_msgs::PointCloud2& cloud = *(obs.
cloud_);
373 for (; iter_x !=iter_x.
end(); ++iter_x, ++iter_y, ++iter_z)
375 double px = *iter_x, py = *iter_y, pz = *iter_z;
389 if (sq_dist >= sq_obstacle_range)
399 ROS_DEBUG(
"Computing map coords failed");
403 unsigned int index =
getIndex(mx, my);
405 touch(px, py, min_x, min_y, max_x, max_y);
409 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
413 double* max_x,
double* max_y)
474 marking_observations.insert(marking_observations.end(),
490 clearing_observations.insert(clearing_observations.end(),
496 double* max_x,
double* max_y)
498 double ox = clearing_observation.
origin_.x;
499 double oy = clearing_observation.
origin_.y;
500 const sensor_msgs::PointCloud2 &cloud = *(clearing_observation.
cloud_);
507 1.0,
"The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
518 touch(ox, oy, min_x, min_y, max_x, max_y);
524 for (; iter_x != iter_x.
end(); ++iter_x, ++iter_y)
537 double t = (origin_x - ox) / a;
543 double t = (origin_y - oy) / b;
551 double t = (map_end_x - ox) / a;
552 wx = map_end_x - .001;
557 double t = (map_end_y - oy) / b;
559 wy = map_end_y - .001;
572 raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range);
603 double* min_x,
double* min_y,
double* max_x,
double* max_y)
605 double dx = wx-ox, dy = wy-oy;
606 double full_distance =
hypot(dx, dy);
607 double scale = std::min(1.0, range / full_distance);
608 double ex = ox + dx * scale, ey = oy + dy * scale;
609 touch(ex, ey, min_x, min_y, max_x, max_y);
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
void projectLaser(const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
void laserScanValidInfCallback(const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages which need filtering to turn Inf values into range_...
geometry_msgs::Point origin_
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
LayeredCostmap * layered_costmap_
bool getMarkingObservations(std::vector< costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
void updateWithOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
virtual void deactivate()
Stop publishers.
std::vector< costmap_2d::Observation > static_clearing_observations_
void clearStaticObservations(bool marking, bool clearing)
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > marking_buffers_
Used to store observation buffers used for marking obstacles.
std::vector< geometry_msgs::Point > transformed_footprint_
std::string getGlobalFrameID() const
void updateRaytraceBounds(double ox, double oy, double wx, double wy, double range, double *min_x, double *min_y, double *max_x, double *max_y)
std::vector< costmap_2d::Observation > static_marking_observations_
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
INLINE Rall1d< T, V, S > hypot(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
laser_geometry::LaserProjection projector_
Used to project laser scans into point clouds.
void reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level)
Stores an observation in terms of a point cloud and the origin of the source.
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
static const unsigned char FREE_SPACE
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
geometry_msgs::TransformStamped t
void addStaticObservation(costmap_2d::Observation &obs, bool marking, bool clearing)
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
std::vector< boost::shared_ptr< tf2_ros::MessageFilterBase > > observation_notifiers_
Used to make sure that transforms are available for each sensor.
const std::vector< geometry_msgs::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
double max_obstacle_height_
Max Obstacle Height.
void raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX)
Raytrace a line and apply some action at each step.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
virtual void activate()
Restart publishers if they've been stopped.
Takes in point clouds from sensors, transforms them to the desired frame, and stores them...
#define ROS_WARN_THROTTLE(period,...)
PointCloud2ConstIterator< T > end() const
bool getParam(const std::string &key, std::string &s) const
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
std::vector< boost::shared_ptr< message_filters::SubscriberBase > > observation_subscribers_
Used for the observation message filters.
bool footprint_clearing_enabled_
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
bool setConvexPolygonCost(const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
Sets the cost of a convex polygon to a desired value.
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
dynamic_reconfigure::Server< costmap_2d::ObstaclePluginConfig > * dsrv_
virtual void raytraceFreespace(const costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Clear freespace based on one observation.
unsigned char default_value_
bool searchParam(const std::string &key, std::string &result) const
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > clearing_buffers_
Used to store observation buffers used for clearing obstacles.
bool enabled_
Currently this var is managed by subclasses. TODO: make this managed by this class and/or container c...
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization...
sensor_msgs::PointCloud2 * cloud_
static bool convertPointCloudToPointCloud2(const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
static const unsigned char LETHAL_OBSTACLE
static const unsigned char NO_INFORMATION
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
void pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud2 messages.
virtual void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
void updateWithMax(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
A 2D costmap provides a mapping between points in the world and their associated "costs".
void transformLaserScanToPointCloud(const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options=channel_option::Default)
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void laserScanCallback(const sensor_msgs::LaserScanConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages.
std::vector< boost::shared_ptr< costmap_2d::ObservationBuffer > > observation_buffers_
Used to store observations from various sensors.
bool getClearingObservations(std::vector< costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.
std::string global_frame_
The global frame for the costmap.
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, std::vector< geometry_msgs::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points) ...
void pointCloudCallback(const sensor_msgs::PointCloudConstPtr &message, const boost::shared_ptr< costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud messages.