diff --git a/igvc_msgs/CMakeLists.txt b/igvc_msgs/CMakeLists.txt
index 9e4a14b94..b87e7e335 100644
--- a/igvc_msgs/CMakeLists.txt
+++ b/igvc_msgs/CMakeLists.txt
@@ -17,7 +17,6 @@ add_message_files(
velocity_quad.msg
velocity_pair.msg
lights.msg
- action_path.msg
system_stats.msg
map.msg
igvc_path.msg
diff --git a/igvc_navigation/src/mapper/traversability_layer.cpp b/igvc_navigation/src/mapper/traversability_layer.cpp
index 4959dcce9..00a0744aa 100644
--- a/igvc_navigation/src/mapper/traversability_layer.cpp
+++ b/igvc_navigation/src/mapper/traversability_layer.cpp
@@ -82,7 +82,7 @@ void TraversabilityLayer::slopeMapCallback(const grid_map_msgs::GridMap &slope_m
{
grid_map::Position pos;
slope_map.getPosition((*it), pos);
- if (map_.isInside(pos))
+ if (map_.isInside(pos) && slope_map.get("mask_dilated")((*it)[0], (*it)[1]) > 0)
{
float slope = slope_map.get("slope")((*it)[0], (*it)[1]);
grid_map::Index map_index;
diff --git a/igvc_perception/CMakeLists.txt b/igvc_perception/CMakeLists.txt
index b1a49812a..8ea62b168 100644
--- a/igvc_perception/CMakeLists.txt
+++ b/igvc_perception/CMakeLists.txt
@@ -25,6 +25,7 @@ find_package(catkin REQUIRED COMPONENTS
grid_map_core
grid_map_ros
grid_map_msgs
+ grid_map_cv
)
set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake)
diff --git a/igvc_perception/config/elevation_mapping.yaml b/igvc_perception/config/elevation_mapping.yaml
index f067c5085..926e91526 100644
--- a/igvc_perception/config/elevation_mapping.yaml
+++ b/igvc_perception/config/elevation_mapping.yaml
@@ -19,7 +19,7 @@ min_variance: 0.000009
max_variance: 0.01
mahalanobis_distance_threshold: 2.5
multi_height_noise: 0.0000009
-fused_map_publishing_rate: 0
+fused_map_publishing_rate: 1.0
enable_visibility_cleanup: false
# SENSOR PARAMETERS
diff --git a/igvc_perception/config/slope_filter.yaml b/igvc_perception/config/slope_filter.yaml
index f20e777ac..ad96525d3 100644
--- a/igvc_perception/config/slope_filter.yaml
+++ b/igvc_perception/config/slope_filter.yaml
@@ -4,11 +4,11 @@ slope_map_filters:
type: gridMapFilters/BufferNormalizerFilter
# Delete unneeded layers.
- - name: delete_original_layers
- type: gridMapFilters/DeletionFilter
- params:
- layers: [horizontal_variance_x, horizontal_variance_y, horizontal_variance_xy,
- color, time, standard_deviation, horizontal_standard_deviation, two_sigma_bound] # List of layers.
+ # - name: delete_original_layers
+ # type: gridMapFilters/DeletionFilter
+ # params:
+ # layers: [horizontal_variance_x, horizontal_variance_y, horizontal_variance_xy,
+ # color, time, standard_deviation, horizontal_standard_deviation, two_sigma_bound] # List of layers.
# Boxblur as an alternative to the inpaint and radial blurring filter above.
- name: boxblur
@@ -36,3 +36,6 @@ slope_map_filters:
params:
output_layer: slope
expression: acos(normal_vectors_z)
+
+erode_radius: 7
+dilate_radius: 6
\ No newline at end of file
diff --git a/igvc_perception/package.xml b/igvc_perception/package.xml
index 0d189c4ad..958b84294 100644
--- a/igvc_perception/package.xml
+++ b/igvc_perception/package.xml
@@ -46,6 +46,7 @@
grid_map_core
grid_map_ros
grid_map_msgs
+ grid_map_cv
image_transport
cv_bridge
diff --git a/igvc_perception/src/slope_filter/slope_filter.cpp b/igvc_perception/src/slope_filter/slope_filter.cpp
index 065fca83b..54f5baf73 100644
--- a/igvc_perception/src/slope_filter/slope_filter.cpp
+++ b/igvc_perception/src/slope_filter/slope_filter.cpp
@@ -1,13 +1,19 @@
#include "slope_filter.h"
#include
+#include
+#include
TraversabilityFilter::TraversabilityFilter() : filter_chain_("grid_map::GridMap")
{
+ ROS_INFO_STREAM("RAW INFO RECEIVED");
private_nh_ = ros::NodeHandle("~");
- elevation_map_sub_ = private_nh_.subscribe("/elevation_mapping/elevation_map_raw", 1,
- &TraversabilityFilter::elevationMapCallback, this);
+ elevation_map_sub_ =
+ private_nh_.subscribe("/elevation_mapping/elevation_map", 1, &TraversabilityFilter::elevationMapCallback, this);
traversability_map_pub_ = private_nh_.advertise("/slope/gridmap", 1);
+ assertions::getParam(private_nh_, "erode_radius", erode_radius);
+ assertions::getParam(private_nh_, "dilate_radius", dilate_radius);
+
// setup filter chain
if (!filter_chain_.configure("/slope_filter/slope_map_filters", private_nh_))
{
@@ -21,15 +27,32 @@ void TraversabilityFilter::elevationMapCallback(const grid_map_msgs::GridMap& me
grid_map::GridMap input_map;
grid_map::GridMapRosConverter::fromMessage(message, input_map);
- grid_map::GridMap output_map;
- if (!filter_chain_.update(input_map, output_map))
+ grid_map::GridMap slope_map;
+ if (!filter_chain_.update(input_map, slope_map))
{
ROS_ERROR_STREAM("Could not update the grid map filter chain!");
return;
}
+ cv::Mat elevation_data_mask;
+ grid_map::GridMapCvConverter::toImage(input_map, "elevation", CV_8U, -1.0, 0.0, elevation_data_mask);
+ grid_map::GridMapCvConverter::addLayerFromImage(elevation_data_mask, "mask_original", slope_map, 0,
+ 255, 0);
+
+ cv::erode(elevation_data_mask, elevation_data_mask,
+ cv::getStructuringElement(cv::MORPH_RECT, cv::Size(2 * erode_radius + 1, 2 * erode_radius + 1),
+ cv::Point(erode_radius, erode_radius)));
+ grid_map::GridMapCvConverter::addLayerFromImage(elevation_data_mask, "mask_eroded", slope_map, 0, 255,
+ 0);
+
+ cv::dilate(elevation_data_mask, elevation_data_mask,
+ cv::getStructuringElement(cv::MORPH_RECT, cv::Size(2 * dilate_radius + 1, 2 * dilate_radius + 1),
+ cv::Point(dilate_radius, dilate_radius)));
+ grid_map::GridMapCvConverter::addLayerFromImage(elevation_data_mask, "mask_dilated", slope_map, 0,
+ 255, 0);
+
grid_map_msgs::GridMap output_message;
- grid_map::GridMapRosConverter::toMessage(output_map, output_message);
+ grid_map::GridMapRosConverter::toMessage(slope_map, output_message);
traversability_map_pub_.publish(output_message);
}
diff --git a/igvc_perception/src/slope_filter/slope_filter.h b/igvc_perception/src/slope_filter/slope_filter.h
index 61a72bfc2..760ed1de2 100644
--- a/igvc_perception/src/slope_filter/slope_filter.h
+++ b/igvc_perception/src/slope_filter/slope_filter.h
@@ -2,7 +2,7 @@
#define SRC_SLOPE_FILTER_H
#include
-#include
+#include
#include
#include
@@ -17,6 +17,9 @@ class TraversabilityFilter
ros::Publisher traversability_map_pub_;
filters::FilterChain filter_chain_;
+ int erode_radius;
+ int dilate_radius;
+
void elevationMapCallback(const grid_map_msgs::GridMap& message);
};