occupancy_grid_node_main.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <cmath>
18 #include <string>
19 #include <vector>
20 
21 #include "Eigen/Core"
22 #include "Eigen/Geometry"
23 #include "cairo/cairo.h"
26 #include "cartographer/io/image.h"
34 #include "cartographer_ros_msgs/SubmapList.h"
35 #include "cartographer_ros_msgs/SubmapQuery.h"
36 #include "gflags/gflags.h"
37 #include "nav_msgs/OccupancyGrid.h"
38 #include "ros/ros.h"
39 
40 DEFINE_double(resolution, 0.05,
41  "Resolution of a grid cell in the published occupancy grid.");
42 DEFINE_double(publish_period_sec, 1.0, "OccupancyGrid publishing period.");
43 
44 namespace cartographer_ros {
45 namespace {
46 
47 using ::cartographer::io::PaintSubmapSlicesResult;
48 using ::cartographer::io::SubmapSlice;
49 using ::cartographer::mapping::SubmapId;
50 
51 class Node {
52  public:
53  explicit Node(double resolution, double publish_period_sec);
54  ~Node() {}
55 
56  Node(const Node&) = delete;
57  Node& operator=(const Node&) = delete;
58 
59  private:
60  void HandleSubmapList(const cartographer_ros_msgs::SubmapList::ConstPtr& msg);
61  void DrawAndPublish(const ::ros::WallTimerEvent& timer_event);
62  void PublishOccupancyGrid(const std::string& frame_id, const ros::Time& time,
63  const Eigen::Array2f& origin,
64  cairo_surface_t* surface);
65 
67  const double resolution_;
68 
69  ::cartographer::common::Mutex mutex_;
70  ::ros::ServiceClient client_ GUARDED_BY(mutex_);
71  ::ros::Subscriber submap_list_subscriber_ GUARDED_BY(mutex_);
72  ::ros::Publisher occupancy_grid_publisher_ GUARDED_BY(mutex_);
73  std::map<SubmapId, SubmapSlice> submap_slices_ GUARDED_BY(mutex_);
75  std::string last_frame_id_;
77 };
78 
79 Node::Node(const double resolution, const double publish_period_sec)
80  : resolution_(resolution),
81  client_(node_handle_.serviceClient<::cartographer_ros_msgs::SubmapQuery>(
83  submap_list_subscriber_(node_handle_.subscribe(
85  boost::function<void(
86  const cartographer_ros_msgs::SubmapList::ConstPtr&)>(
87  [this](const cartographer_ros_msgs::SubmapList::ConstPtr& msg) {
88  HandleSubmapList(msg);
89  }))),
90  occupancy_grid_publisher_(
91  node_handle_.advertise<::nav_msgs::OccupancyGrid>(
93  true /* latched */)),
95  node_handle_.createWallTimer(::ros::WallDuration(publish_period_sec),
96  &Node::DrawAndPublish, this)) {}
97 
98 void Node::HandleSubmapList(
99  const cartographer_ros_msgs::SubmapList::ConstPtr& msg) {
101 
102  // We do not do any work if nobody listens.
103  if (occupancy_grid_publisher_.getNumSubscribers() == 0) {
104  return;
105  }
106 
107  // Keep track of submap IDs that don't appear in the message anymore.
108  std::set<SubmapId> submap_ids_to_delete;
109  for (const auto& pair : submap_slices_) {
110  submap_ids_to_delete.insert(pair.first);
111  }
112 
113  for (const auto& submap_msg : msg->submap) {
114  const SubmapId id{submap_msg.trajectory_id, submap_msg.submap_index};
115  submap_ids_to_delete.erase(id);
116  SubmapSlice& submap_slice = submap_slices_[id];
117  submap_slice.pose = ToRigid3d(submap_msg.pose);
118  submap_slice.metadata_version = submap_msg.submap_version;
119  if (submap_slice.surface != nullptr &&
120  submap_slice.version == submap_msg.submap_version) {
121  continue;
122  }
123 
124  auto fetched_textures =
126  if (fetched_textures == nullptr) {
127  continue;
128  }
129  CHECK(!fetched_textures->textures.empty());
130  submap_slice.version = fetched_textures->version;
131 
132  // We use the first texture only. By convention this is the highest
133  // resolution texture and that is the one we want to use to construct the
134  // map for ROS.
135  const auto fetched_texture = fetched_textures->textures.begin();
136  submap_slice.width = fetched_texture->width;
137  submap_slice.height = fetched_texture->height;
138  submap_slice.slice_pose = fetched_texture->slice_pose;
139  submap_slice.resolution = fetched_texture->resolution;
140  submap_slice.cairo_data.clear();
141  submap_slice.surface = ::cartographer::io::DrawTexture(
142  fetched_texture->pixels.intensity, fetched_texture->pixels.alpha,
143  fetched_texture->width, fetched_texture->height,
144  &submap_slice.cairo_data);
145  }
146 
147  // Delete all submaps that didn't appear in the message.
148  for (const auto& id : submap_ids_to_delete) {
149  submap_slices_.erase(id);
150  }
151 
152  last_timestamp_ = msg->header.stamp;
153  last_frame_id_ = msg->header.frame_id;
154 }
155 
156 void Node::DrawAndPublish(const ::ros::WallTimerEvent& unused_timer_event) {
157  if (submap_slices_.empty() || last_frame_id_.empty()) {
158  return;
159  }
160 
162  auto painted_slices = PaintSubmapSlices(submap_slices_, resolution_);
163  std::unique_ptr<nav_msgs::OccupancyGrid> msg_ptr = CreateOccupancyGridMsg(
164  painted_slices, resolution_, last_frame_id_, last_timestamp_);
165  occupancy_grid_publisher_.publish(*msg_ptr);
166 }
167 
168 } // namespace
169 } // namespace cartographer_ros
170 
171 int main(int argc, char** argv) {
172  google::InitGoogleLogging(argv[0]);
173  google::ParseCommandLineFlags(&argc, &argv, true);
174 
175  ::ros::init(argc, argv, "cartographer_occupancy_grid_node");
176  ::ros::start();
177 
179  ::cartographer_ros::Node node(FLAGS_resolution, FLAGS_publish_period_sec);
180 
181  ::ros::spin();
182  ::ros::shutdown();
183 }
Node & operator=(const Node &)=delete
std::unique_ptr< nav_msgs::OccupancyGrid > CreateOccupancyGridMsg(const cartographer::io::PaintSubmapSlicesResult &painted_slices, const double resolution, const std::string &frame_id, const ros::Time &time)
::ros::NodeHandle node_handle_
::cartographer::common::Mutex mutex_
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
Rigid3d ToRigid3d(const geometry_msgs::TransformStamped &transform)
constexpr int kLatestOnlyPublisherQueueSize
Node(const NodeOptions &node_options, std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder, tf2_ros::Buffer *tf_buffer)
Definition: node.cc:85
cartographer::common::Mutex mutex_
Definition: node.h:170
PaintSubmapSlicesResult PaintSubmapSlices(const std::map<::cartographer::mapping::SubmapId, SubmapSlice > &submaps, const double resolution)
std::unique_ptr<::cartographer::io::SubmapTextures > FetchSubmapTextures(const ::cartographer::mapping::SubmapId &submap_id, ros::ServiceClient *client)
Definition: submap.cc:28
::ros::WallTimer occupancy_grid_publisher_timer_
void subscribe()
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
DEFINE_double(resolution, 0.05, "Resolution of a grid cell in the published occupancy grid.")
::ros::NodeHandle node_handle_
Definition: node.h:173
const double resolution_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
MapBuilderBridge map_builder_bridge_ GUARDED_BY(mutex_)
int main(int argc, char **argv)
constexpr char kOccupancyGridTopic[]
constexpr char kSubmapQueryServiceName[]
std::string last_frame_id_
constexpr char kSubmapListTopic[]
ros::Time last_timestamp_
Mutex::Locker MutexLocker


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05