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/version.h>
50#if RCLCPP_VERSION_GTE(20, 0, 0)
51#include <rclcpp/event_handler.hpp>
53#include <rclcpp/qos_event.hpp>
55#include <rclcpp/time.hpp>
56#include <rclcpp/utilities.hpp>
60static void publishOctomap(
const rclcpp::Publisher<octomap_msgs::msg::Octomap>::SharedPtr& octree_binary_pub,
63 octomap_msgs::msg::Octomap map;
67 map.header.stamp = rclcpp::Clock().now();
70 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
73 if (!octomap_msgs::binaryMapToMsgData(*server.
getOcTreePtr(), map.data))
75#pragma GCC diagnostic push
76#pragma GCC diagnostic ignored "-Wold-style-cast"
77 RCLCPP_ERROR_THROTTLE(logger, steady_clock, 1000,
"Could not generate OctoMap message");
78#pragma GCC diagnostic pop
83#pragma GCC diagnostic push
84#pragma GCC diagnostic ignored "-Wold-style-cast"
85 RCLCPP_ERROR_THROTTLE(logger, steady_clock, 1000,
"Exception thrown while generating OctoMap message");
86#pragma GCC diagnostic pop
90 octree_binary_pub->publish(map);
93int main(
int argc,
char** argv)
95 rclcpp::init(argc, argv);
96 auto node = rclcpp::Node::make_shared(
"occupancy_map_server");
98 auto octree_binary_pub =
99 node->create_publisher<octomap_msgs::msg::Octomap>(
"octomap_binary", RMW_QOS_POLICY_HISTORY_KEEP_LAST);
100 auto clock_ptr = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
101 std::shared_ptr<tf2_ros::Buffer> buffer = std::make_shared<tf2_ros::Buffer>(clock_ptr, tf2::durationFromSec(5.0));
102 tf2_ros::TransformListener listener(*buffer, node,
false );
105 [&octree_binary_pub, &server, logger = node->get_logger()] { return publishOctomap(octree_binary_pub, server); });
const collision_detection::OccMapTreePtr & getOcTreePtr()
Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing usin...
void startMonitor()
start the monitor (will begin updating the octomap
const std::string & getMapFrame() const
Gets the map frame (this is set either by the constor or a parameter).
void setUpdateCallback(const std::function< void()> &update_callback)
Set the callback to trigger when updates to the maintained octomap are received.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
int main(int argc, char **argv)