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>
54 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.occupancy_map_server");
56 static void publishOctomap(
const rclcpp::Publisher<octomap_msgs::msg::Octomap>::SharedPtr& octree_binary_pub,
59 octomap_msgs::msg::Octomap map;
62 map.header.stamp = rclcpp::Clock().now();
65 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
68 if (!octomap_msgs::binaryMapToMsgData(*server.
getOcTreePtr(), map.data))
69 RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000,
"Could not generate OctoMap message");
73 RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000,
"Exception thrown while generating OctoMap message");
77 octree_binary_pub->publish(map);
80 int main(
int argc,
char** argv)
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 );
90 server.
setUpdateCallback([&octree_binary_pub, &server] {
return publishOctomap(octree_binary_pub, server); });
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
int main(int argc, char **argv)