Skip to content

Commit 9385646

Browse files
StepTurtleMehmet Dogru
authored and
Mehmet Dogru
committed
Add component interface for lanelet metadata msg
Signed-off-by: Barış Zeren <bzeren1819@gmail.com>
1 parent 30d4643 commit 9385646

File tree

7 files changed

+49
-20
lines changed

7 files changed

+49
-20
lines changed

common/component_interface_specs/CMakeLists.txt

+19
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,25 @@ project(component_interface_specs)
44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
66

7+
include_directories(
8+
include
9+
SYSTEM
10+
${rclcpp_INCLUDE_DIRS}
11+
${rosidl_runtime_cpp_INCLUDE_DIRS}
12+
${rcl_INCLUDE_DIRS}
13+
${autoware_adapi_v1_msgs_INCLUDE_DIRS}
14+
${autoware_auto_planning_msgs_INCLUDE_DIRS}
15+
${autoware_planning_msgs_INCLUDE_DIRS}
16+
${autoware_auto_vehicle_msgs_INCLUDE_DIRS}
17+
${tier4_control_msgs_INCLUDE_DIRS}
18+
${nav_msgs_INCLUDE_DIRS}
19+
${tier4_system_msgs_INCLUDE_DIRS}
20+
${tier4_vehicle_msgs_INCLUDE_DIRS}
21+
${autoware_auto_perception_msgs_INCLUDE_DIRS}
22+
${tier4_map_msgs_INCLUDE_DIRS}
23+
${autoware_map_msgs_INCLUDE_DIRS}
24+
)
25+
726
if(BUILD_TESTING)
827
ament_auto_add_gtest(gtest_${PROJECT_NAME}
928
test/gtest_main.cpp

common/component_interface_specs/include/component_interface_specs/map.hpp

+10
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <rclcpp/qos.hpp>
1919

20+
#include <autoware_map_msgs/msg/lanelet_map_meta_data.hpp>
2021
#include <tier4_map_msgs/msg/map_projector_info.hpp>
2122

2223
namespace map_interface
@@ -31,6 +32,15 @@ struct MapProjectorInfo
3132
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
3233
};
3334

35+
struct LaneletMapMetaData
36+
{
37+
using Message = autoware_map_msgs::msg::LaneletMapMetaData;
38+
static constexpr char name[] = "/map/lanelet_map_meta_data";
39+
static constexpr size_t depth = 1;
40+
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
41+
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
42+
};
43+
3444
} // namespace map_interface
3545

3646
#endif // COMPONENT_INTERFACE_SPECS__MAP_HPP_

common/component_interface_specs/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
<depend>autoware_auto_planning_msgs</depend>
1717
<depend>autoware_auto_vehicle_msgs</depend>
1818
<depend>autoware_planning_msgs</depend>
19+
<depend>autoware_map_msgs</depend>
1920
<depend>nav_msgs</depend>
2021
<depend>rcl</depend>
2122
<depend>rclcpp</depend>

map/autoware_dynamic_lanelet_provider/include/autoware/dynamic_lanelet_provider/dynamic_lanelet_provider.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ class DynamicLaneletProviderNode : public rclcpp::Node
5050
component_interface_utils::Subscription<map_interface::MapProjectorInfo>::SharedPtr
5151
sub_map_projector_info_;
5252

53-
rclcpp::Subscription<autoware_map_msgs::msg::LaneletMapMetaData>::SharedPtr
53+
component_interface_utils::Subscription<map_interface::LaneletMapMetaData>::SharedPtr
5454
lanelet_map_meta_data_sub_;
5555

5656
rclcpp::TimerBase::SharedPtr map_update_timer_;

map/autoware_dynamic_lanelet_provider/src/dynamic_lanelet_provider.cpp

+15-15
Original file line numberDiff line numberDiff line change
@@ -62,26 +62,26 @@ DynamicLaneletProviderNode::DynamicLaneletProviderNode(const rclcpp::NodeOptions
6262
"/localization/kinematic_state", 100,
6363
std::bind(&DynamicLaneletProviderNode::onOdometry, this, std::placeholders::_1));
6464

65-
const auto adaptor = component_interface_utils::NodeAdaptor(this);
66-
adaptor.init_sub(
65+
const auto projector_info_adaptor = component_interface_utils::NodeAdaptor(this);
66+
projector_info_adaptor.init_sub(
6767
sub_map_projector_info_,
6868
[this](const map_interface::MapProjectorInfo::Message::ConstSharedPtr msg) {
6969
projector_info_ = *msg;
7070
});
7171

72-
lanelet_map_meta_data_sub_ =
73-
this->create_subscription<autoware_map_msgs::msg::LaneletMapMetaData>(
74-
"/map/lanelet_map_meta_data", rclcpp::QoS{1}.transient_local(),
75-
[this](const autoware_map_msgs::msg::LaneletMapMetaData::SharedPtr msg) {
76-
for (const auto & data : msg->metadata_list) {
77-
Lanelet2FileMetaData metadata;
78-
metadata.id = data.tile_id;
79-
metadata.origin_lat = data.metadata.origin_lat;
80-
metadata.origin_lon = data.metadata.origin_lon;
81-
metadata.mgrs_code = data.metadata.mgrs_code;
82-
lanelet_map_meta_data_list_.push_back(metadata);
83-
}
84-
});
72+
const auto metadata_adaptor = component_interface_utils::NodeAdaptor(this);
73+
metadata_adaptor.init_sub(
74+
lanelet_map_meta_data_sub_,
75+
[this](const autoware_map_msgs::msg::LaneletMapMetaData::SharedPtr msg) {
76+
for (const auto & data : msg->metadata_list) {
77+
Lanelet2FileMetaData metadata;
78+
metadata.id = data.tile_id;
79+
metadata.origin_lat = data.metadata.origin_lat;
80+
metadata.origin_lon = data.metadata.origin_lon;
81+
metadata.mgrs_code = data.metadata.mgrs_code;
82+
lanelet_map_meta_data_list_.push_back(metadata);
83+
}
84+
});
8585

8686
double map_update_dt = 1.0;
8787
auto period_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(

map/map_loader/include/map_loader/lanelet2_differential_loader_module.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ class Lanelet2DifferentialLoaderModule
5858

5959
rclcpp::Service<GetDifferentialLanelet2Map>::SharedPtr get_differential_lanelet2_maps_service_;
6060

61-
rclcpp::Publisher<autoware_map_msgs::msg::LaneletMapMetaData>::SharedPtr
61+
component_interface_utils::Publisher<map_interface::LaneletMapMetaData>::SharedPtr
6262
pub_lanelet_map_meta_data_;
6363

6464
component_interface_utils::Subscription<map_interface::MapProjectorInfo>::SharedPtr

map/map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -26,11 +26,10 @@ Lanelet2DifferentialLoaderModule::Lanelet2DifferentialLoaderModule(
2626
{
2727
// Publish lanelet2 map meta data
2828
{
29-
pub_lanelet_map_meta_data_ = node->create_publisher<autoware_map_msgs::msg::LaneletMapMetaData>(
30-
"/map/lanelet_map_meta_data", rclcpp::QoS{1}.transient_local());
31-
3229
const auto msg = getLaneletMapMetaDataMsg();
3330

31+
const auto metadata_adaptor = component_interface_utils::NodeAdaptor(node);
32+
metadata_adaptor.init_pub(pub_lanelet_map_meta_data_);
3433
pub_lanelet_map_meta_data_->publish(msg);
3534
}
3635

0 commit comments

Comments
 (0)