moveit2
The MoveIt Motion Planning Framework for ROS 2.
occupancy_map_server.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Jon Binney, Ioan Sucan */
36 
38 
39 #include <octomap_msgs/conversions.h>
40 #include <tf2_ros/transform_listener.h>
41 #include <rclcpp/clock.hpp>
42 #include <rclcpp/executors.hpp>
43 #include <rclcpp/experimental/buffers/intra_process_buffer.hpp>
44 #include <rclcpp/logger.hpp>
45 #include <rclcpp/logging.hpp>
46 #include <rclcpp/node.hpp>
47 #include <rclcpp/publisher.hpp>
48 #include <rclcpp/qos_event.hpp>
49 #include <rclcpp/time.hpp>
50 #include <rclcpp/utilities.hpp>
51 #include <memory>
52 #include <sstream>
53 
54 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.occupancy_map_server");
55 
56 static void publishOctomap(const rclcpp::Publisher<octomap_msgs::msg::Octomap>::SharedPtr& octree_binary_pub,
58 {
59  octomap_msgs::msg::Octomap map;
60 
61  map.header.frame_id = server.getMapFrame();
62  map.header.stamp = rclcpp::Clock().now();
63 
64  server.getOcTreePtr()->lockRead();
65  rclcpp::Clock steady_clock(RCL_STEADY_TIME);
66  try
67  {
68  if (!octomap_msgs::binaryMapToMsgData(*server.getOcTreePtr(), map.data))
69  RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000, "Could not generate OctoMap message");
70  }
71  catch (...)
72  {
73  RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000, "Exception thrown while generating OctoMap message");
74  }
75  server.getOcTreePtr()->unlockRead();
76 
77  octree_binary_pub->publish(map);
78 }
79 
80 int main(int argc, char** argv)
81 {
82  rclcpp::init(argc, argv);
83  auto node = rclcpp::Node::make_shared("occupancy_map_server");
84  auto octree_binary_pub =
85  node->create_publisher<octomap_msgs::msg::Octomap>("octomap_binary", RMW_QOS_POLICY_HISTORY_KEEP_LAST);
86  auto clock_ptr = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
87  std::shared_ptr<tf2_ros::Buffer> buffer = std::make_shared<tf2_ros::Buffer>(clock_ptr, tf2::durationFromSec(5.0));
88  tf2_ros::TransformListener listener(*buffer, node, false /* spin_thread - disables executor */);
89  occupancy_map_monitor::OccupancyMapMonitor server(node, buffer);
90  server.setUpdateCallback([&octree_binary_pub, &server] { return publishOctomap(octree_binary_pub, server); });
91  server.startMonitor();
92 
93  rclcpp::spin(node);
94  return 0;
95 }
const std::string & getMapFrame() const
Gets the map frame (this is set either by the constor or a parameter).
void startMonitor()
start the monitor (will begin updating the octomap
const collision_detection::OccMapTreePtr & getOcTreePtr()
Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing usin...
void setUpdateCallback(const std::function< void()> &update_callback)
Set the callback to trigger when updates to the maintained octomap are received.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
int main(int argc, char **argv)