File tree 2 files changed +15
-2
lines changed
autoware_iv_external_api_adaptor/src
2 files changed +15
-2
lines changed Original file line number Diff line number Diff line change 18
18
#include < tier4_api_utils/tier4_api_utils.hpp>
19
19
20
20
#include < autoware_adapi_v1_msgs/msg/response_status.hpp>
21
+ #include < autoware_common_msgs/msg/response_status.hpp>
21
22
#include < tier4_external_api_msgs/msg/response_status.hpp>
22
23
23
24
namespace external_api ::converter
24
25
{
25
26
26
27
using AdResponseStatus = autoware_adapi_v1_msgs::msg::ResponseStatus;
27
28
using T4ResponseStatus = tier4_external_api_msgs::msg::ResponseStatus;
29
+ using CommonResponseStatus = autoware_common_msgs::msg::ResponseStatus;
28
30
29
31
inline T4ResponseStatus convert (const AdResponseStatus & ad)
30
32
{
@@ -35,6 +37,15 @@ inline T4ResponseStatus convert(const AdResponseStatus & ad)
35
37
}
36
38
}
37
39
40
+ inline T4ResponseStatus convert (const CommonResponseStatus & common)
41
+ {
42
+ if (common.success ) {
43
+ return tier4_api_utils::response_success (common.message );
44
+ } else {
45
+ return tier4_api_utils::response_error (common.message );
46
+ }
47
+ }
48
+
38
49
} // namespace external_api::converter
39
50
40
51
#endif // CONVERTER__RESPONSE_STATUS_HPP_
Original file line number Diff line number Diff line change @@ -61,8 +61,9 @@ void InitialPose::setInitializePose(
61
61
const tier4_external_api_msgs::srv::InitializePose::Response::SharedPtr response)
62
62
{
63
63
const auto req = std::make_shared<localization_interface::Initialize::Service::Request>();
64
- req->pose .push_back (request->pose );
65
- req->pose .back ().pose .covariance = particle_covariance;
64
+ req->method = localization_interface::Initialize::Service::Request::AUTO;
65
+ req->pose_with_covariance .push_back (request->pose );
66
+ req->pose_with_covariance .back ().pose .covariance = particle_covariance;
66
67
67
68
try {
68
69
const auto res = cli_localization_initialize_->call (req, initial_pose_timeout);
@@ -77,6 +78,7 @@ void InitialPose::setInitializePoseAuto(
77
78
const tier4_external_api_msgs::srv::InitializePoseAuto::Response::SharedPtr response)
78
79
{
79
80
const auto req = std::make_shared<localization_interface::Initialize::Service::Request>();
81
+ req->method = localization_interface::Initialize::Service::Request::AUTO;
80
82
81
83
try {
82
84
const auto res = cli_localization_initialize_->call (req, initial_pose_timeout);
You can’t perform that action at this time.
0 commit comments