22 #include "Eigen/Geometry" 23 #include "cairo/cairo.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" 41 "Resolution of a grid cell in the published occupancy grid.");
42 DEFINE_double(publish_period_sec, 1.0,
"OccupancyGrid publishing period.");
47 using ::cartographer::io::PaintSubmapSlicesResult;
48 using ::cartographer::io::SubmapSlice;
49 using ::cartographer::mapping::SubmapId;
53 explicit Node(
double resolution,
double publish_period_sec);
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);
69 ::cartographer::common::Mutex
mutex_;
73 std::map<SubmapId, SubmapSlice> submap_slices_
GUARDED_BY(mutex_);
79 Node::Node(
const double resolution,
const double publish_period_sec)
86 const cartographer_ros_msgs::SubmapList::ConstPtr&)>(
87 [this](const cartographer_ros_msgs::SubmapList::ConstPtr& msg) {
88 HandleSubmapList(msg);
90 occupancy_grid_publisher_(
96 &Node::DrawAndPublish,
this)) {}
98 void Node::HandleSubmapList(
99 const cartographer_ros_msgs::SubmapList::ConstPtr& msg) {
103 if (occupancy_grid_publisher_.getNumSubscribers() == 0) {
108 std::set<SubmapId> submap_ids_to_delete;
109 for (
const auto& pair : submap_slices_) {
110 submap_ids_to_delete.insert(pair.first);
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) {
124 auto fetched_textures =
126 if (fetched_textures ==
nullptr) {
129 CHECK(!fetched_textures->textures.empty());
130 submap_slice.version = fetched_textures->version;
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);
148 for (
const auto&
id : submap_ids_to_delete) {
149 submap_slices_.erase(
id);
156 void Node::DrawAndPublish(const ::ros::WallTimerEvent& unused_timer_event) {
165 occupancy_grid_publisher_.publish(*msg_ptr);
171 int main(
int argc,
char** argv) {
172 google::InitGoogleLogging(argv[0]);
173 google::ParseCommandLineFlags(&argc, &argv,
true);
175 ::ros::init(argc, argv,
"cartographer_occupancy_grid_node");
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)
cartographer::common::Mutex mutex_
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)
::ros::WallTimer occupancy_grid_publisher_timer_
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_
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