Skip to content

Commit

Permalink
Add lanelet XML API (autowarefoundation#26)
Browse files Browse the repository at this point in the history
  • Loading branch information
isamu-takagi authored Oct 26, 2021
1 parent 22fc3a8 commit dfb57dd
Show file tree
Hide file tree
Showing 2 changed files with 32 additions and 0 deletions.
23 changes: 23 additions & 0 deletions autoware_iv_external_api_adaptor/src/map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,16 @@ Map::Map(const rclcpp::NodeOptions & options)
: Node("external_api_map", options)
{
using namespace std::placeholders;
autoware_api_utils::ServiceProxyNodeInterface proxy(this);

group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
srv_lanelet_xml_ = proxy.create_service<autoware_external_api_msgs::srv::GetTextFile>(
"/api/external/get/map/lanelet/xml",
std::bind(&Map::getLaneletXml, this, _1, _2),
rmw_qos_profile_services_default, group_);
cli_lanelet_xml_ = proxy.create_client<autoware_external_api_msgs::srv::GetTextFile>(
"/api/autoware/get/map/lanelet/xml",
rmw_qos_profile_services_default);

pub_map_info_ = create_publisher<autoware_external_api_msgs::msg::MapHash>(
"/api/external/get/map/info/hash", rclcpp::QoS(1).transient_local());
Expand All @@ -34,6 +44,19 @@ void Map::getMapHash(const autoware_external_api_msgs::msg::MapHash::SharedPtr m
pub_map_info_->publish(*message);
}

void Map::getLaneletXml(
const autoware_external_api_msgs::srv::GetTextFile::Request::SharedPtr request,
const autoware_external_api_msgs::srv::GetTextFile::Response::SharedPtr response)
{
auto [status, resp] = cli_lanelet_xml_->call(request);
if (!autoware_api_utils::is_success(status)) {
response->status = status;
return;
}
response->file = resp->file;
response->status = resp->status;
}

} // namespace external_api

#include "rclcpp_components/register_node_macro.hpp"
Expand Down
9 changes: 9 additions & 0 deletions autoware_iv_external_api_adaptor/src/map.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@
#define MAP_HPP_

#include "rclcpp/rclcpp.hpp"
#include "autoware_api_utils/autoware_api_utils.hpp"
#include "autoware_external_api_msgs/srv/get_text_file.hpp"
#include "autoware_external_api_msgs/msg/map_hash.hpp"

namespace external_api
Expand All @@ -27,14 +29,21 @@ class Map : public rclcpp::Node
explicit Map(const rclcpp::NodeOptions & options);

private:
using GetTextFile = autoware_external_api_msgs::srv::GetTextFile;
using MapHash = autoware_external_api_msgs::msg::MapHash;

// ros interface
rclcpp::CallbackGroup::SharedPtr group_;
autoware_api_utils::Service<GetTextFile>::SharedPtr srv_lanelet_xml_;
autoware_api_utils::Client<GetTextFile>::SharedPtr cli_lanelet_xml_;
rclcpp::Publisher<MapHash>::SharedPtr pub_map_info_;
rclcpp::Subscription<MapHash>::SharedPtr sub_map_info_;

// ros callback
void getMapHash(const autoware_external_api_msgs::msg::MapHash::SharedPtr message);
void getLaneletXml(
const autoware_external_api_msgs::srv::GetTextFile::Request::SharedPtr request,
const autoware_external_api_msgs::srv::GetTextFile::Response::SharedPtr response);
};

} // namespace external_api
Expand Down

0 comments on commit dfb57dd

Please sign in to comment.