Skip to content

Commit

Permalink
Merge branch 'feature/multiple_inputs_in_elevation_mapping' into 'mas…
Browse files Browse the repository at this point in the history
…ter'

[elevation_mapping] Support multiple inputs

GitOrigin-RevId: 7a4b30f9874825bdcb7078ce887e32eb097460eb
  • Loading branch information
mgaertneratanybotics authored and anybotics-sync-runner committed Oct 19, 2020
1 parent c162ec4 commit f8455a2
Show file tree
Hide file tree
Showing 18 changed files with 763 additions and 61 deletions.
40 changes: 33 additions & 7 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -82,10 +82,15 @@ In order to install the Robot-Centric Elevation Mapping, clone the latest versio

### Unit Tests

Run the unit tests with

catkin_make run_tests_elevation_map_msg run_tests_elevation_mapping

Build tests with

roscd elevation_mapping
catkin build --catkin-make-args run_tests -- --this

Run the tests with

rostest elevation_mapping elevation_mapping.test -t


## Basic Usage

Expand Down Expand Up @@ -229,10 +234,28 @@ This is the main Robot-Centric Elevation Mapping node. It uses the distance sens

#### Parameters

* **`point_cloud_topic`** (string, default: "/points")
* **`DEPRECATED point_cloud_topic`** (string, default: "/points")

The name of the distance measurements topic.
The name of the distance measurements topic. Use input_sources instead.

* **`input_sources`** (list of input sources, default: none)

Here you specify your inputs to elevation mapping, currently "pointcloud" inputs are supported.

Example configuration:
```
input_sources:
- name: front # A name to identify the input source
type: pointcloud # Supported types: pointcloud
topic: /lidar_front/depth/points
queue_size: 1
publish_on_update: true # Wheter to publish the elevation map after a callback from this source.
- name: rear
type: pointcloud
topic: /lidar_rear/depth/points
queue_size: 5
publish_on_update: false
```
* **`robot_pose_topic`** (string, default: "/robot_state/pose")
The name of the robot pose and covariance topic.
Expand Down Expand Up @@ -344,12 +367,15 @@ This is the main Robot-Centric Elevation Mapping node. It uses the distance sens
The data for the sensor noise model.
## Changelog
See [Changelog]
## Bugs & Feature Requests
Please report bugs and request features using the [Issue Tracker](https://github.com/anybotics/elevation_mapping/issues).
[Changelog]: CHANGELOG.rst
[ROS]: http://www.ros.org
[rviz]: http://wiki.ros.org/rviz
[grid_map_msgs/GridMap]: https://github.com/anybotics/grid_map/blob/master/grid_map_msgs/msg/GridMap.msg
Expand Down
75 changes: 54 additions & 21 deletions elevation_mapping/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -58,9 +58,11 @@ include_directories(
add_library(${PROJECT_NAME}_library
src/ElevationMapping.cpp
src/ElevationMap.cpp
src/RobotMotionMapUpdater.cpp
src/input_sources/Input.cpp
src/input_sources/InputSourceManager.cpp
src/postprocessing/PostprocessorPool.cpp
src/postprocessing/PostprocessingPipelineFunctor.cpp
src/RobotMotionMapUpdater.cpp
src/sensor_processors/SensorProcessorBase.cpp
src/sensor_processors/StructuredLightSensorProcessor.cpp
src/sensor_processors/StereoSensorProcessor.cpp
Expand Down Expand Up @@ -93,9 +95,12 @@ install(
TARGETS
${PROJECT_NAME}
${PROJECT_NAME}_library
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
ARCHIVE DESTINATION
${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION
${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION
${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(
Expand All @@ -119,54 +124,82 @@ install(
if(CATKIN_ENABLE_TESTING)
find_package(catkin REQUIRED
COMPONENTS
${CATKIN_PACKAGE_DEPENDENCIES}
roslaunch
rostest
${CATKIN_PACKAGE_DEPENDENCIES}
grid_map_filters
roslaunch
rostest
)

catkin_add_gtest(test_${PROJECT_NAME}
# Cummulative distribution
catkin_add_gtest(test_${PROJECT_NAME}_cumulative_distribution
test/ElevationMapTest.cpp
test/test_elevation_mapping.cpp
test/WeightedEmpiricalCumulativeDistributionFunctionTest.cpp
)

target_link_libraries(test_${PROJECT_NAME}
target_link_libraries(test_${PROJECT_NAME}_cumulative_distribution
${PROJECT_NAME}_library
)

target_include_directories(test_${PROJECT_NAME} PRIVATE
include
target_include_directories(test_${PROJECT_NAME}_cumulative_distribution
PRIVATE
include
SYSTEM
${catkin_INCLUDE_DIRS}
)

# Input sources
add_rostest_gtest(test_${PROJECT_NAME}_input_sources
test/input_sources/input_sources.test
test/input_sources/test_input_sources.cpp
test/input_sources/InputSourcesTest.cpp
)

target_link_libraries(test_${PROJECT_NAME}_input_sources
${PROJECT_NAME}_library
)

target_include_directories(test_${PROJECT_NAME}_input_sources
PRIVATE
include
SYSTEM
${Boost_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
${Eigen_INCLUDE_DIRS}
)

add_rostest_gtest(test_postprocessor
# Postprocessor
add_rostest_gtest(test_${PROJECT_NAME}_postprocessor
test/postprocessing/postprocessor.test
test/postprocessing/main.cpp
test/postprocessing/PostprocessorTest.cpp
)
target_include_directories(test_postprocessor PRIVATE

target_include_directories(test_${PROJECT_NAME}_postprocessor PRIVATE
include
)
target_include_directories(test_postprocessor SYSTEM PUBLIC

target_include_directories(test_${PROJECT_NAME}_postprocessor SYSTEM PUBLIC
${catkin_INCLUDE_DIRS}
)
target_link_libraries(test_postprocessor

target_link_libraries(test_${PROJECT_NAME}_postprocessor
${GTEST_LIBRARIES}
${PROJECT_NAME}_library
${catkin_LIBRARIES}
)

find_package(cmake_code_coverage QUIET)
if(cmake_code_coverage_FOUND)
add_gtest_coverage(
TEST_BUILD_TARGETS
test_${PROJECT_NAME}
add_gtest_coverage(TEST_BUILD_TARGETS
test_${PROJECT_NAME}_cumulative_distribution
)
add_rostest_coverage(TEST_BUILD_TARGETS
test_${PROJECT_NAME}_input_sources
)

add_rostest_coverage(
TEST_BUILD_TARGETS
test_postprocessor
add_rostest_coverage(TEST_BUILD_TARGETS
test_${PROJECT_NAME}_postprocessor
)
endif()
endif()
Expand Down
20 changes: 15 additions & 5 deletions elevation_mapping/include/elevation_mapping/ElevationMapping.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
#include "elevation_mapping/ElevationMap.hpp"
#include "elevation_mapping/RobotMotionMapUpdater.hpp"
#include "elevation_mapping/WeightedEmpiricalCumulativeDistributionFunction.hpp"
#include "elevation_mapping/input_sources/InputSourceManager.hpp"
#include "elevation_mapping/sensor_processors/SensorProcessorBase.hpp"

// Grid Map
Expand Down Expand Up @@ -64,9 +65,10 @@ class ElevationMapping {
/*!
* Callback function for new data to be added to the elevation map.
*
* @param pointCloud The point cloud to be fused with the existing data.
* @param pointCloudMsg The point cloud to be fused with the existing data.
* @param publishPointCloud If true, publishes the pointcloud after updating the map.
*/
void pointCloudCallback(const sensor_msgs::PointCloud2& pointCloud);
void pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr& pointCloudMsg, bool publishPointCloud);

/*!
* Callback function for the update timer. Forces an update of the map from
Expand Down Expand Up @@ -193,6 +195,11 @@ class ElevationMapping {
*/
bool initialize();

/**
* Sets up the subscribers for both robot poses and input data.
*/
void setupSubscribers();

/*!
* Separate thread for all fusion service calls.
*/
Expand Down Expand Up @@ -235,10 +242,13 @@ class ElevationMapping {
bool initializeElevationMap();

//! ROS nodehandle.
ros::NodeHandle& nodeHandle_;
ros::NodeHandle nodeHandle_;

protected:
//! Input sources.
InputSourceManager inputSources_;
//! ROS subscribers.
ros::Subscriber pointCloudSubscriber_;
ros::Subscriber pointCloudSubscriber_; //!< Deprecated, use input_source instead.
message_filters::Subscriber<geometry_msgs::PoseWithCovarianceStamped> robotPoseSubscriber_;

//! ROS service servers.
Expand Down Expand Up @@ -275,7 +285,7 @@ class ElevationMapping {
std::string trackPointFrameId_;

//! ROS topics for subscriptions.
std::string pointCloudTopic_;
std::string pointCloudTopic_; //!< Deprecated, use input_source instead.
std::string robotPoseTopic_;

//! Elevation map.
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
/*
* Input.hpp
*
* Created on: Oct 06, 2020
* Author: Magnus Gärtner
* Institute: ETH Zurich, ANYbotics
*/

#pragma once

#include <XmlRpc.h>
#include <ros/ros.h>
#include <string>

namespace elevation_mapping {
class ElevationMapping; // Forward declare to avoid cyclic import dependency.

/**
* @brief An Input feeds data to ElevationMapping callbacks. E.g it holds a subscription to an sensor source and registered an appropriate
* ElevationMapping callback.
*/
class Input {
public:
template <typename MsgT>
using CallbackT = void (ElevationMapping::*)(const boost::shared_ptr<const MsgT>&, bool);

/**
* @brief Constructor.
* @param nh Reference to the nodeHandle of the manager. Used to subscribe
* to inputs.
*/
explicit Input(ros::NodeHandle& nh);

/**
* @brief Configure the input source.
* @param parameters The configuration parameters.
* @return True if configuring was successful.
*/
bool configure(const XmlRpc::XmlRpcValue& parameters);

/**
* @brief Registers the corresponding callback in the elevationMap.
* @param map The map we want to link this input source to.
* @param callback The callback to use for incoming data.
* @tparam MsgT The message types of the callback.
*/
template <typename MsgT>
void registerCallback(ElevationMapping& map, CallbackT<MsgT> callback);

/**
* @return The topic (as absolute path, with renames) that this input
* subscribes to.
*/
std::string getSubscribedTopic() const;

/**
* @return The type of this input source.
*/
std::string getType() { return type_; }

private:
// Parameters.
std::string name_;
std::string type_;
uint32_t queueSize_;
std::string topic_;
bool publishOnUpdate_;

// ROS connection.
ros::Subscriber subscriber_;
ros::NodeHandle& nodeHandle_;
};

template <typename MsgT>
void Input::registerCallback(ElevationMapping& map, CallbackT<MsgT> callback) {
subscriber_ =
nodeHandle_.subscribe<MsgT>(topic_, queueSize_, std::bind(callback, std::ref(map), std::placeholders::_1, publishOnUpdate_));
ROS_INFO("Subscribing to %s: %s, queue_size: %i.", type_.c_str(), topic_.c_str(), queueSize_);
}

} // namespace elevation_mapping
Loading

0 comments on commit f8455a2

Please sign in to comment.