ROS1 Interface
The demos page features several examples of how to run wavemap on existing datasets. In the sections that follow, we start by providing an overview of the packages that are included in wavemap’s ROS1 interface. We then discuss how they can be configured to process your own sensor data. Finally, we explain how you can interact with wavemap in your own ROS nodes to enable new, custom use cases.
Overview of packages
Wavemap’s ROS1 interface consists of the following packages:
wavemap
: A catkin wrapper for wavemap’s C++ Librarywavemap_msgs
: Message types to transmit wavemap maps over ROSwavemap_ros_conversions
: Conversions between ROS and internal wavemap typeswavemap_ros
: The ROS server, rosbag processor, and example config and launch fileswavemap_rviz_plugin
: Rviz plugin to efficiently visualize and inspect wavemap mapswavemap_all
: A meta package that builds all of the above packages
Your own data
The only requirements to run wavemap on your own dataset or robot are:
a source of depth measurements,
sensor pose (estimates) for each measurement.
We usually use depth measurements from depth cameras or 3D LiDARs, but any source would work as long as a sufficiently good projection and measurement model is available. Wavemap’s ROS1 interface natively supports depth image and pointcloud inputs, and automatically queries the sensor poses from the TF tree.
To help you get started quickly, we provide example config and ROS launch files for various sensor setups and use cases. An overview of all the available settings is provided on the parameters page.
Publishing maps
Wavemap’s ROS server offers multiple ways to publish its maps to ROS topics, enabling visualization and usage by other ROS nodes. Please refer to the documentation on ROS1 map operations for an overview of the available options.
Saving maps
The server’s map can also be written to disk by calling its save_map
service as follows:
rosservice call /wavemap/save_map "file_path: '/path/to/your/map.wvmp'"
Saved maps can subsequently be used in C++ (with or without ROS) and in Python.
Your own code
We now briefly discuss how to set up your own ROS1 package to use wavemap, before proceeding to code examples.
Tip
An example package that combines the setup steps and code examples that follow can be found here.
Build configuration
In order to use wavemap’s ROS1 packages in your own code, you need to add them as dependencies and configure your CMake targets to use them.
Declare dependencies
For illustration purposes, we will assume your package uses wavemap
, wavemap_msgs
and wavemap_ros_conversions
.
First, declare them as dependencies in your package’s package.xml:
<depend>wavemap</depend>
<depend>wavemap_msgs</depend>
<depend>wavemap_ros_conversions</depend>
Next, import them as catkin COMPONENTS in your package’s CMakeLists.txt:
# Find dependencies
find_package(catkin REQUIRED
COMPONENTS wavemap wavemap_msgs wavemap_ros_conversions)
Finally, include them in CATKIN_DEPENDS when calling catkin_package
in your CMakeLists.txt:
# Register catkin package
catkin_package(
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS wavemap wavemap_msgs wavemap_ros_conversions)
CMake target setup
The libraries and executables generated by your code are referred to as CMake targets. They have to be linked to the libraries provided by wavemap’s ROS1 packages in order to use them. Furthermore, they must know where to find each library’s header files.
Importing ROS1 packages as catkin COMPONENTS conveniently appends their respective libraries to catkin_LIBRARIES and headers to catkin_INCLUDE_DIRS. To configure your target, you can therefore simply add:
target_link_libraries(your_target PUBLIC ${catkin_LIBRARIES})
target_include_directories(your_target PUBLIC ${catkin_INCLUDE_DIRS})
We strongly recommend to also call the set_wavemap_target_properties
function to ensure your target’s compilation options are compatible with those of wavemap:
set_wavemap_target_properties(your_target)
Code examples
Since wavemap’s ROS1 interface extends its C++ API, all of the C++ API’s code examples can directly be used in ROS.
Additionally, the following code can be used to receive maps over a ROS topic
#include <ros/ros.h>
#include <wavemap_ros_conversions/map_msg_conversions.h>
// Create a smart pointer that will own the received map
wavemap::MapBase::Ptr loaded_map;
// Define the map callback
void mapCallback(const wavemap_msgs::Map& msg) {
// Load the received map
wavemap::convert::rosMsgToMap(msg, loaded_map);
}
// NOTE: We only define loaded_map and mapCallback globally for illustration
// purposes. In practice, we recommend defining them as class members.
int main(int argc, char** argv) {
// Register your node with ROS
ros::init(argc, argv, "your_node");
ros::NodeHandle nh;
ros::NodeHandle nh_private("~");
// Subscribe to the ROS topic
ros::Subscriber map_sub = nh.subscribe("map", 1, &mapCallback);
}
and maps can be sent over ROS with
#include <string>
#include <ros/ros.h>
#include <wavemap_ros_conversions/map_msg_conversions.h>
int main(int argc, char** argv) {
// Register your node with ROS
ros::init(argc, argv, "your_node");
ros::NodeHandle nh;
ros::NodeHandle nh_private("~");
// Create an empty map for illustration
wavemap::HashedWaveletOctreeConfig config;
wavemap::HashedWaveletOctree map(config);
// Advertise the ROS topic
const std::string ros_topic = "map";
const int queue_size = 1;
ros::Publisher map_pub =
nh_private.advertise<wavemap_msgs::Map>(ros_topic, queue_size);
// Convert the map to a ROS msg
wavemap_msgs::Map map_msg;
const std::string map_frame = "odom";
const ros::Time stamp = ros::Time::now();
wavemap::convert::mapToRosMsg(map, map_frame, stamp, map_msg);
// Publish the ROS message
map_pub.publish(map_msg);
}