From 08dff098dc5615768967bbe37b8d60cefb526ef6 Mon Sep 17 00:00:00 2001 From: Jorge Santos Date: Mon, 2 May 2016 09:01:31 +0200 Subject: [PATCH] Issue #28: buffer range messages for each incoming topic and with a maximum, configurable, buffer size --- range_sensor_layer/CMakeLists.txt | 3 ++ range_sensor_layer/cfg/RangeSensorLayer.cfg | 1 + .../range_sensor_layer/range_sensor_layer.h | 2 +- range_sensor_layer/src/range_sensor_layer.cpp | 38 +++++++++++++++++-- 4 files changed, 39 insertions(+), 5 deletions(-) diff --git a/range_sensor_layer/CMakeLists.txt b/range_sensor_layer/CMakeLists.txt index f90a565..d56645a 100644 --- a/range_sensor_layer/CMakeLists.txt +++ b/range_sensor_layer/CMakeLists.txt @@ -2,6 +2,9 @@ cmake_minimum_required(VERSION 2.8.3) project(range_sensor_layer) set_directory_properties(PROPERTIES COMPILE_OPTIONS "-Wall;-Werror") +# Required to use unordered maps +add_definitions("-std=c++11") + find_package(catkin REQUIRED COMPONENTS angles costmap_2d diff --git a/range_sensor_layer/cfg/RangeSensorLayer.cfg b/range_sensor_layer/cfg/RangeSensorLayer.cfg index 58dcc96..82c4fdb 100755 --- a/range_sensor_layer/cfg/RangeSensorLayer.cfg +++ b/range_sensor_layer/cfg/RangeSensorLayer.cfg @@ -9,6 +9,7 @@ gen.add('enabled', bool_t, 0, 'Whether to apply this plugin or not gen.add('phi', double_t, 0, 'Phi value', 1.2) gen.add('inflate_cone', double_t, 0, 'Inflate the triangular area covered by the sensor (percentage)', 1, 0, 1) gen.add('no_readings_timeout', double_t, 0, 'No Readings Timeout', 0.0, 0.0) +gen.add('ranges_buffer_size', int_t, 0, 'Maximum number of ranges per topic to buffer until processing', 1, 1, 50) gen.add('clear_threshold', double_t, 0, 'Probability below which cells are marked as free', 0.2, 0.0, 1.0) gen.add('mark_threshold', double_t, 0, 'Probability above which cells are marked as occupied', 0.8, 0.0, 1.0) gen.add('clear_on_max_reading', bool_t, 0, 'Clear on max reading', False) diff --git a/range_sensor_layer/include/range_sensor_layer/range_sensor_layer.h b/range_sensor_layer/include/range_sensor_layer/range_sensor_layer.h index 11db46d..bf44ed4 100644 --- a/range_sensor_layer/include/range_sensor_layer/range_sensor_layer.h +++ b/range_sensor_layer/include/range_sensor_layer/range_sensor_layer.h @@ -40,7 +40,7 @@ class RangeSensorLayer : public costmap_2d::CostmapLayer private: void reconfigureCB(range_sensor_layer::RangeSensorLayerConfig &config, uint32_t level); - void bufferIncomingRangeMsg(const sensor_msgs::RangeConstPtr& range_message); + void bufferIncomingRangeMsg(const sensor_msgs::RangeConstPtr& range_message, const std::string& topic); void processRangeMsg(sensor_msgs::Range& range_message); void processFixedRangeMsg(sensor_msgs::Range& range_message); void processVariableRangeMsg(sensor_msgs::Range& range_message); diff --git a/range_sensor_layer/src/range_sensor_layer.cpp b/range_sensor_layer/src/range_sensor_layer.cpp index 35c6bc6..12e87ac 100644 --- a/range_sensor_layer/src/range_sensor_layer.cpp +++ b/range_sensor_layer/src/range_sensor_layer.cpp @@ -41,6 +41,10 @@ void RangeSensorLayer::onInitialize() nh.param("ns", topics_ns, std::string()); nh.param("topics", topic_names, topic_names); + int size; + nh.param("ranges_buffer_size", size, 1); + range_msgs_buffer_size_ = size; + InputSensorType input_sensor_type = ALL; std::string sensor_type_name; nh.param("input_sensor_type", sensor_type_name, std::string("ALL")); @@ -103,7 +107,9 @@ void RangeSensorLayer::onInitialize() name_.c_str(), sensor_type_name.c_str()); } - range_subs_.push_back(nh.subscribe(topic_name, 100, &RangeSensorLayer::bufferIncomingRangeMsg, this)); + range_subs_.push_back(nh.subscribe(topic_name, 100, + boost::bind(&RangeSensorLayer::bufferIncomingRangeMsg, + this, _1, topic_name))); ROS_INFO("RangeSensorLayer: subscribed to topic %s", range_subs_.back().getTopic().c_str()); } @@ -176,12 +182,27 @@ void RangeSensorLayer::reconfigureCB(range_sensor_layer::RangeSensorLayerConfig enabled_ = config.enabled; current_ = false; } + + if (config.ranges_buffer_size < range_msgs_buffer_size_) + { + boost::mutex::scoped_lock lock(range_message_mutex_); + std::unordered_map>::iterator buffer_it; + for(buffer_it = range_msgs_buffers_.begin(); buffer_it != range_msgs_buffers_.end(); buffer_it++) + { + while (buffer_it->second.size() > config.ranges_buffer_size) + buffer_it->second.pop_front(); + } + } + range_msgs_buffer_size_ = config.ranges_buffer_size; } -void RangeSensorLayer::bufferIncomingRangeMsg(const sensor_msgs::RangeConstPtr& range_message) +void RangeSensorLayer::bufferIncomingRangeMsg(const sensor_msgs::RangeConstPtr& range_message, + const std::string& topic) { boost::mutex::scoped_lock lock(range_message_mutex_); - range_msgs_buffer_.push_back(*range_message); + range_msgs_buffers_[topic].push_back(*range_message); + if (range_msgs_buffers_[topic].size() > range_msgs_buffer_size_) + range_msgs_buffers_[topic].pop_front(); } void RangeSensorLayer::updateCostmap() @@ -196,7 +217,16 @@ void RangeSensorLayer::updateCostmap() for (std::list::iterator range_msgs_it = range_msgs_buffer_copy.begin(); range_msgs_it != range_msgs_buffer_copy.end(); range_msgs_it++) { - processRangeMessageFunc_(*range_msgs_it); + range_message_mutex_.lock(); + std::list range_msgs_buffer_copy = std::list(buffer_it->second); + buffer_it->second.clear(); + range_message_mutex_.unlock(); + + for (std::list::iterator range_msgs_it = range_msgs_buffer_copy.begin(); + range_msgs_it != range_msgs_buffer_copy.end(); range_msgs_it++) + { + processRangeMessageFunc_(*range_msgs_it); + } } }