File tree Expand file tree Collapse file tree 3 files changed +32
-0
lines changed
common/autoware_component_interface_specs
include/autoware/component_interface_specs Expand file tree Collapse file tree 3 files changed +32
-0
lines changed Original file line number Diff line number Diff line change 18
18
#include < autoware/component_interface_specs/utils.hpp>
19
19
#include < rclcpp/qos.hpp>
20
20
21
+ #include < autoware_adapi_v1_msgs/msg/localization_initialization_state.hpp>
22
+ #include < autoware_internal_localization_msgs/srv/initialize_localization.hpp>
21
23
#include < geometry_msgs/msg/accel_with_covariance_stamped.hpp>
22
24
#include < nav_msgs/msg/odometry.hpp>
23
25
24
26
namespace autoware ::component_interface_specs::localization
25
27
{
26
28
29
+ struct Initialize
30
+ {
31
+ using Service = autoware_internal_localization_msgs::srv::InitializeLocalization;
32
+ static constexpr char name[] = " /localization/initialize" ;
33
+ };
34
+
35
+ struct InitializationState
36
+ {
37
+ using Message = autoware_adapi_v1_msgs::msg::LocalizationInitializationState;
38
+ static constexpr char name[] = " /localization/initialization_state" ;
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
+
27
44
struct KinematicState
28
45
{
29
46
using Message = nav_msgs::msg::Odometry;
Original file line number Diff line number Diff line change 12
12
<buildtool_depend >ament_cmake_auto</buildtool_depend >
13
13
<buildtool_depend >autoware_cmake</buildtool_depend >
14
14
15
+ <depend >autoware_adapi_v1_msgs</depend >
15
16
<depend >autoware_control_msgs</depend >
17
+ <depend >autoware_internal_localization_msgs</depend >
16
18
<depend >autoware_localization_msgs</depend >
17
19
<depend >autoware_map_msgs</depend >
18
20
<depend >autoware_perception_msgs</depend >
Original file line number Diff line number Diff line change @@ -42,4 +42,17 @@ TEST(localization, interface)
42
42
EXPECT_EQ (qos.reliability (), rclcpp::ReliabilityPolicy::Reliable);
43
43
EXPECT_EQ (qos.durability (), rclcpp::DurabilityPolicy::Volatile);
44
44
}
45
+
46
+ {
47
+ using autoware::component_interface_specs::localization::InitializationState;
48
+ size_t depth = 1 ;
49
+ EXPECT_EQ (InitializationState::depth, depth);
50
+ EXPECT_EQ (InitializationState::reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
51
+ EXPECT_EQ (InitializationState::durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
52
+
53
+ const auto qos = autoware::component_interface_specs::get_qos<InitializationState>();
54
+ EXPECT_EQ (qos.depth (), depth);
55
+ EXPECT_EQ (qos.reliability (), rclcpp::ReliabilityPolicy::Reliable);
56
+ EXPECT_EQ (qos.durability (), rclcpp::DurabilityPolicy::TransientLocal);
57
+ }
45
58
}
You can’t perform that action at this time.
0 commit comments