Skip to content

Commit

Permalink
feat: localization initialization method (#112)
Browse files Browse the repository at this point in the history
Signed-off-by: Takagi, Isamu <[email protected]>
  • Loading branch information
isamu-takagi authored May 28, 2024
1 parent 7ee65a6 commit 81ec733
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 2 deletions.
11 changes: 11 additions & 0 deletions autoware_iv_external_api_adaptor/src/converter/response_status.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,15 @@
#include <tier4_api_utils/tier4_api_utils.hpp>

#include <autoware_adapi_v1_msgs/msg/response_status.hpp>
#include <autoware_common_msgs/msg/response_status.hpp>
#include <tier4_external_api_msgs/msg/response_status.hpp>

namespace external_api::converter
{

using AdResponseStatus = autoware_adapi_v1_msgs::msg::ResponseStatus;
using T4ResponseStatus = tier4_external_api_msgs::msg::ResponseStatus;
using CommonResponseStatus = autoware_common_msgs::msg::ResponseStatus;

inline T4ResponseStatus convert(const AdResponseStatus & ad)
{
Expand All @@ -35,6 +37,15 @@ inline T4ResponseStatus convert(const AdResponseStatus & ad)
}
}

inline T4ResponseStatus convert(const CommonResponseStatus & common)
{
if (common.success) {
return tier4_api_utils::response_success(common.message);
} else {
return tier4_api_utils::response_error(common.message);
}
}

} // namespace external_api::converter

#endif // CONVERTER__RESPONSE_STATUS_HPP_
6 changes: 4 additions & 2 deletions autoware_iv_external_api_adaptor/src/initial_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,9 @@ void InitialPose::setInitializePose(
const tier4_external_api_msgs::srv::InitializePose::Response::SharedPtr response)
{
const auto req = std::make_shared<localization_interface::Initialize::Service::Request>();
req->pose.push_back(request->pose);
req->pose.back().pose.covariance = particle_covariance;
req->method = localization_interface::Initialize::Service::Request::AUTO;
req->pose_with_covariance.push_back(request->pose);
req->pose_with_covariance.back().pose.covariance = particle_covariance;

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

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

0 comments on commit 81ec733

Please sign in to comment.