Skip to content

Commit 81ec733

Browse files
authored
feat: localization initialization method (#112)
Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>
1 parent 7ee65a6 commit 81ec733

File tree

2 files changed

+15
-2
lines changed

2 files changed

+15
-2
lines changed

autoware_iv_external_api_adaptor/src/converter/response_status.hpp

+11
Original file line numberDiff line numberDiff line change
@@ -18,13 +18,15 @@
1818
#include <tier4_api_utils/tier4_api_utils.hpp>
1919

2020
#include <autoware_adapi_v1_msgs/msg/response_status.hpp>
21+
#include <autoware_common_msgs/msg/response_status.hpp>
2122
#include <tier4_external_api_msgs/msg/response_status.hpp>
2223

2324
namespace external_api::converter
2425
{
2526

2627
using AdResponseStatus = autoware_adapi_v1_msgs::msg::ResponseStatus;
2728
using T4ResponseStatus = tier4_external_api_msgs::msg::ResponseStatus;
29+
using CommonResponseStatus = autoware_common_msgs::msg::ResponseStatus;
2830

2931
inline T4ResponseStatus convert(const AdResponseStatus & ad)
3032
{
@@ -35,6 +37,15 @@ inline T4ResponseStatus convert(const AdResponseStatus & ad)
3537
}
3638
}
3739

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+
3849
} // namespace external_api::converter
3950

4051
#endif // CONVERTER__RESPONSE_STATUS_HPP_

autoware_iv_external_api_adaptor/src/initial_pose.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -61,8 +61,9 @@ void InitialPose::setInitializePose(
6161
const tier4_external_api_msgs::srv::InitializePose::Response::SharedPtr response)
6262
{
6363
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;
6667

6768
try {
6869
const auto res = cli_localization_initialize_->call(req, initial_pose_timeout);
@@ -77,6 +78,7 @@ void InitialPose::setInitializePoseAuto(
7778
const tier4_external_api_msgs::srv::InitializePoseAuto::Response::SharedPtr response)
7879
{
7980
const auto req = std::make_shared<localization_interface::Initialize::Service::Request>();
81+
req->method = localization_interface::Initialize::Service::Request::AUTO;
8082

8183
try {
8284
const auto res = cli_localization_initialize_->call(req, initial_pose_timeout);

0 commit comments

Comments
 (0)