Skip to content

Commit 1fe530c

Browse files
committed
add patch
Signed-off-by: wep21 <[email protected]>
1 parent 8e98e87 commit 1fe530c

File tree

1 file changed

+82
-0
lines changed

1 file changed

+82
-0
lines changed
Lines changed: 82 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
diff --git a/include/cartographer_ros/map_builder_bridge.h b/include/cartographer_ros/map_builder_bridge.h
2+
index b2c00b7..bd91894 100644
3+
--- a/include/cartographer_ros/map_builder_bridge.h
4+
+++ b/include/cartographer_ros/map_builder_bridge.h
5+
@@ -113,7 +113,7 @@ class MapBuilderBridge {
6+
const NodeOptions node_options_;
7+
std::unordered_map<int,
8+
std::shared_ptr<const LocalTrajectoryData::LocalSlamData>>
9+
- local_slam_data_ GUARDED_BY(mutex_);
10+
+ local_slam_data_ ABSL_GUARDED_BY(mutex_);
11+
std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder_;
12+
tf2_ros::Buffer* const tf_buffer_;
13+
14+
diff --git a/include/cartographer_ros/metrics/internal/gauge.h b/include/cartographer_ros/metrics/internal/gauge.h
15+
index f311ab1..26d0caf 100644
16+
--- a/include/cartographer_ros/metrics/internal/gauge.h
17+
+++ b/include/cartographer_ros/metrics/internal/gauge.h
18+
@@ -71,7 +71,7 @@ class Gauge : public ::cartographer::metrics::Gauge {
19+
20+
absl::Mutex mutex_;
21+
const std::map<std::string, std::string> labels_;
22+
- double value_ GUARDED_BY(mutex_);
23+
+ double value_ ABSL_GUARDED_BY(mutex_);
24+
};
25+
26+
} // namespace metrics
27+
diff --git a/include/cartographer_ros/metrics/internal/histogram.h b/include/cartographer_ros/metrics/internal/histogram.h
28+
index b5d8404..e47f99b 100644
29+
--- a/include/cartographer_ros/metrics/internal/histogram.h
30+
+++ b/include/cartographer_ros/metrics/internal/histogram.h
31+
@@ -50,8 +50,8 @@ class Histogram : public ::cartographer::metrics::Histogram {
32+
absl::Mutex mutex_;
33+
const std::map<std::string, std::string> labels_;
34+
const BucketBoundaries bucket_boundaries_;
35+
- std::vector<double> bucket_counts_ GUARDED_BY(mutex_);
36+
- double sum_ GUARDED_BY(mutex_);
37+
+ std::vector<double> bucket_counts_ ABSL_GUARDED_BY(mutex_);
38+
+ double sum_ ABSL_GUARDED_BY(mutex_);
39+
};
40+
41+
} // namespace metrics
42+
diff --git a/include/cartographer_ros/node.h b/include/cartographer_ros/node.h
43+
index f3527ca..f9fb9fb 100644
44+
--- a/include/cartographer_ros/node.h
45+
+++ b/include/cartographer_ros/node.h
46+
@@ -168,7 +168,7 @@ class Node {
47+
bool ValidateTrajectoryOptions(const TrajectoryOptions& options);
48+
bool ValidateTopicNames(const TrajectoryOptions& options);
49+
cartographer_ros_msgs::msg::StatusResponse FinishTrajectoryUnderLock(
50+
- int trajectory_id) EXCLUSIVE_LOCKS_REQUIRED(mutex_);
51+
+ int trajectory_id) ABSL_EXCLUSIVE_LOCKS_REQUIRED(mutex_);
52+
void MaybeWarnAboutTopicMismatch();
53+
54+
// Helper function for service handlers that need to check trajectory states.
55+
@@ -183,7 +183,7 @@ class Node {
56+
57+
absl::Mutex mutex_;
58+
std::unique_ptr<cartographer_ros::metrics::FamilyFactory> metrics_registry_;
59+
- std::shared_ptr<MapBuilderBridge> map_builder_bridge_ GUARDED_BY(mutex_);
60+
+ std::shared_ptr<MapBuilderBridge> map_builder_bridge_ ABSL_GUARDED_BY(mutex_);
61+
62+
rclcpp::Node::SharedPtr node_;
63+
::rclcpp::Publisher<::cartographer_ros_msgs::msg::SubmapList>::SharedPtr submap_list_publisher_;
64+
diff --git a/src/occupancy_grid_node_main.cpp b/src/occupancy_grid_node_main.cpp
65+
index 282b890..6139979 100644
66+
--- a/src/occupancy_grid_node_main.cpp
67+
+++ b/src/occupancy_grid_node_main.cpp
68+
@@ -74,10 +74,10 @@ class Node : public rclcpp::Node
69+
absl::Mutex mutex_;
70+
rclcpp::CallbackGroup::SharedPtr callback_group_;
71+
rclcpp::executors::SingleThreadedExecutor::SharedPtr callback_group_executor_;
72+
- ::rclcpp::Client<cartographer_ros_msgs::srv::SubmapQuery>::SharedPtr client_ GUARDED_BY(mutex_);
73+
- ::rclcpp::Subscription<cartographer_ros_msgs::msg::SubmapList>::SharedPtr submap_list_subscriber_ GUARDED_BY(mutex_);
74+
- ::rclcpp::Publisher<::nav_msgs::msg::OccupancyGrid>::SharedPtr occupancy_grid_publisher_ GUARDED_BY(mutex_);
75+
- std::map<SubmapId, SubmapSlice> submap_slices_ GUARDED_BY(mutex_);
76+
+ ::rclcpp::Client<cartographer_ros_msgs::srv::SubmapQuery>::SharedPtr client_ ABSL_GUARDED_BY(mutex_);
77+
+ ::rclcpp::Subscription<cartographer_ros_msgs::msg::SubmapList>::SharedPtr submap_list_subscriber_ ABSL_GUARDED_BY(mutex_);
78+
+ ::rclcpp::Publisher<::nav_msgs::msg::OccupancyGrid>::SharedPtr occupancy_grid_publisher_ ABSL_GUARDED_BY(mutex_);
79+
+ std::map<SubmapId, SubmapSlice> submap_slices_ ABSL_GUARDED_BY(mutex_);
80+
rclcpp::TimerBase::SharedPtr occupancy_grid_publisher_timer_;
81+
std::string last_frame_id_;
82+
rclcpp::Time last_timestamp_;

0 commit comments

Comments
 (0)