Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include <cmath>
00018 #include <string>
00019 #include <vector>
00020
00021 #include "Eigen/Core"
00022 #include "Eigen/Geometry"
00023 #include "absl/synchronization/mutex.h"
00024 #include "cairo/cairo.h"
00025 #include "cartographer/common/port.h"
00026 #include "cartographer/io/image.h"
00027 #include "cartographer/io/submap_painter.h"
00028 #include "cartographer/mapping/id.h"
00029 #include "cartographer/transform/rigid_transform.h"
00030 #include "cartographer_ros/msg_conversion.h"
00031 #include "cartographer_ros/node_constants.h"
00032 #include "cartographer_ros/ros_log_sink.h"
00033 #include "cartographer_ros/submap.h"
00034 #include "cartographer_ros_msgs/SubmapList.h"
00035 #include "cartographer_ros_msgs/SubmapQuery.h"
00036 #include "gflags/gflags.h"
00037 #include "nav_msgs/OccupancyGrid.h"
00038 #include "ros/ros.h"
00039
00040 DEFINE_double(resolution, 0.05,
00041 "Resolution of a grid cell in the published occupancy grid.");
00042 DEFINE_double(publish_period_sec, 1.0, "OccupancyGrid publishing period.");
00043 DEFINE_bool(include_frozen_submaps, true,
00044 "Include frozen submaps in the occupancy grid.");
00045 DEFINE_bool(include_unfrozen_submaps, true,
00046 "Include unfrozen submaps in the occupancy grid.");
00047 DEFINE_string(occupancy_grid_topic, cartographer_ros::kOccupancyGridTopic,
00048 "Name of the topic on which the occupancy grid is published.");
00049
00050 namespace cartographer_ros {
00051 namespace {
00052
00053 using ::cartographer::io::PaintSubmapSlicesResult;
00054 using ::cartographer::io::SubmapSlice;
00055 using ::cartographer::mapping::SubmapId;
00056
00057 class Node {
00058 public:
00059 explicit Node(double resolution, double publish_period_sec);
00060 ~Node() {}
00061
00062 Node(const Node&) = delete;
00063 Node& operator=(const Node&) = delete;
00064
00065 private:
00066 void HandleSubmapList(const cartographer_ros_msgs::SubmapList::ConstPtr& msg);
00067 void DrawAndPublish(const ::ros::WallTimerEvent& timer_event);
00068
00069 ::ros::NodeHandle node_handle_;
00070 const double resolution_;
00071
00072 absl::Mutex mutex_;
00073 ::ros::ServiceClient client_ GUARDED_BY(mutex_);
00074 ::ros::Subscriber submap_list_subscriber_ GUARDED_BY(mutex_);
00075 ::ros::Publisher occupancy_grid_publisher_ GUARDED_BY(mutex_);
00076 std::map<SubmapId, SubmapSlice> submap_slices_ GUARDED_BY(mutex_);
00077 ::ros::WallTimer occupancy_grid_publisher_timer_;
00078 std::string last_frame_id_;
00079 ros::Time last_timestamp_;
00080 };
00081
00082 Node::Node(const double resolution, const double publish_period_sec)
00083 : resolution_(resolution),
00084 client_(node_handle_.serviceClient<::cartographer_ros_msgs::SubmapQuery>(
00085 kSubmapQueryServiceName)),
00086 submap_list_subscriber_(node_handle_.subscribe(
00087 kSubmapListTopic, kLatestOnlyPublisherQueueSize,
00088 boost::function<void(
00089 const cartographer_ros_msgs::SubmapList::ConstPtr&)>(
00090 [this](const cartographer_ros_msgs::SubmapList::ConstPtr& msg) {
00091 HandleSubmapList(msg);
00092 }))),
00093 occupancy_grid_publisher_(
00094 node_handle_.advertise<::nav_msgs::OccupancyGrid>(
00095 FLAGS_occupancy_grid_topic, kLatestOnlyPublisherQueueSize,
00096 true )),
00097 occupancy_grid_publisher_timer_(
00098 node_handle_.createWallTimer(::ros::WallDuration(publish_period_sec),
00099 &Node::DrawAndPublish, this)) {}
00100
00101 void Node::HandleSubmapList(
00102 const cartographer_ros_msgs::SubmapList::ConstPtr& msg) {
00103 absl::MutexLock locker(&mutex_);
00104
00105
00106 if (occupancy_grid_publisher_.getNumSubscribers() == 0) {
00107 return;
00108 }
00109
00110
00111 std::set<SubmapId> submap_ids_to_delete;
00112 for (const auto& pair : submap_slices_) {
00113 submap_ids_to_delete.insert(pair.first);
00114 }
00115
00116 for (const auto& submap_msg : msg->submap) {
00117 const SubmapId id{submap_msg.trajectory_id, submap_msg.submap_index};
00118 submap_ids_to_delete.erase(id);
00119 if ((submap_msg.is_frozen && !FLAGS_include_frozen_submaps) ||
00120 (!submap_msg.is_frozen && !FLAGS_include_unfrozen_submaps)) {
00121 continue;
00122 }
00123 SubmapSlice& submap_slice = submap_slices_[id];
00124 submap_slice.pose = ToRigid3d(submap_msg.pose);
00125 submap_slice.metadata_version = submap_msg.submap_version;
00126 if (submap_slice.surface != nullptr &&
00127 submap_slice.version == submap_msg.submap_version) {
00128 continue;
00129 }
00130
00131 auto fetched_textures =
00132 ::cartographer_ros::FetchSubmapTextures(id, &client_);
00133 if (fetched_textures == nullptr) {
00134 continue;
00135 }
00136 CHECK(!fetched_textures->textures.empty());
00137 submap_slice.version = fetched_textures->version;
00138
00139
00140
00141
00142 const auto fetched_texture = fetched_textures->textures.begin();
00143 submap_slice.width = fetched_texture->width;
00144 submap_slice.height = fetched_texture->height;
00145 submap_slice.slice_pose = fetched_texture->slice_pose;
00146 submap_slice.resolution = fetched_texture->resolution;
00147 submap_slice.cairo_data.clear();
00148 submap_slice.surface = ::cartographer::io::DrawTexture(
00149 fetched_texture->pixels.intensity, fetched_texture->pixels.alpha,
00150 fetched_texture->width, fetched_texture->height,
00151 &submap_slice.cairo_data);
00152 }
00153
00154
00155 for (const auto& id : submap_ids_to_delete) {
00156 submap_slices_.erase(id);
00157 }
00158
00159 last_timestamp_ = msg->header.stamp;
00160 last_frame_id_ = msg->header.frame_id;
00161 }
00162
00163 void Node::DrawAndPublish(const ::ros::WallTimerEvent& unused_timer_event) {
00164 absl::MutexLock locker(&mutex_);
00165 if (submap_slices_.empty() || last_frame_id_.empty()) {
00166 return;
00167 }
00168 auto painted_slices = PaintSubmapSlices(submap_slices_, resolution_);
00169 std::unique_ptr<nav_msgs::OccupancyGrid> msg_ptr = CreateOccupancyGridMsg(
00170 painted_slices, resolution_, last_frame_id_, last_timestamp_);
00171 occupancy_grid_publisher_.publish(*msg_ptr);
00172 }
00173
00174 }
00175 }
00176
00177 int main(int argc, char** argv) {
00178 google::InitGoogleLogging(argv[0]);
00179 google::ParseCommandLineFlags(&argc, &argv, true);
00180
00181 CHECK(FLAGS_include_frozen_submaps || FLAGS_include_unfrozen_submaps)
00182 << "Ignoring both frozen and unfrozen submaps makes no sense.";
00183
00184 ::ros::init(argc, argv, "cartographer_occupancy_grid_node");
00185 ::ros::start();
00186
00187 cartographer_ros::ScopedRosLogSink ros_log_sink;
00188 ::cartographer_ros::Node node(FLAGS_resolution, FLAGS_publish_period_sec);
00189
00190 ::ros::spin();
00191 ::ros::shutdown();
00192 }