Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_ad_api_specs): define routing interface #1559

Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions common/autoware_ad_api_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,14 @@ autoware_package()
rosidl_generate_interfaces(${PROJECT_NAME}
common/msg/ResponseStatus.msg
interface/srv/InterfaceVersion.srv
routing/msg/RouteState.msg
routing/msg/Route.msg
routing/msg/RouteData.msg
routing/msg/RoutePrimitive.msg
routing/msg/RouteSegment.msg
routing/srv/ClearRoute.srv
routing/srv/SetRoute.srv
routing/srv/SetRoutePoints.srv
DEPENDENCIES
builtin_interfaces
std_msgs
Expand Down
5 changes: 5 additions & 0 deletions common/autoware_ad_api_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,11 @@ Considering the product life cycle, there may be multiple vehicles using differe
In that situation, the AD API users such as developers of a web service have to switch the application behavior based on the version that each vehicle uses.
The version of AD API follows [Semantic Versioning][semver] in order to provide an intuitive understanding of the changes between versions.

## Routing

The routing service support two formats. One uses pose and the other uses map dependent data directly.
The body part of the route message is optional, since the route does not exist when it is cleared by the service.

<!-- link -->

[semver]: https://semver.org/
2 changes: 2 additions & 0 deletions common/autoware_ad_api_msgs/routing/msg/Route.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
std_msgs/Header header
autoware_ad_api_msgs/RouteData[<=1] data
3 changes: 3 additions & 0 deletions common/autoware_ad_api_msgs/routing/msg/RouteData.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
geometry_msgs/Pose start
geometry_msgs/Pose goal
autoware_ad_api_msgs/RouteSegment[] segments
2 changes: 2 additions & 0 deletions common/autoware_ad_api_msgs/routing/msg/RoutePrimitive.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
int64 id
string type # The same id may be used for each type.
2 changes: 2 additions & 0 deletions common/autoware_ad_api_msgs/routing/msg/RouteSegment.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
autoware_ad_api_msgs/RoutePrimitive preferred
autoware_ad_api_msgs/RoutePrimitive[] alternatives # Does not include the preferred primitive.
8 changes: 8 additions & 0 deletions common/autoware_ad_api_msgs/routing/msg/RouteState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
uint16 UNKNOWN = 0
uint16 UNSET = 1
uint16 SET = 2
uint16 ARRIVED = 3
uint16 CHANGING = 4

builtin_interfaces/Time stamp
uint16 state
2 changes: 2 additions & 0 deletions common/autoware_ad_api_msgs/routing/srv/ClearRoute.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
---
autoware_ad_api_msgs/ResponseStatus status
6 changes: 6 additions & 0 deletions common/autoware_ad_api_msgs/routing/srv/SetRoute.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
std_msgs/Header header
geometry_msgs/Pose goal
autoware_ad_api_msgs/RouteSegment[] segments
---
uint16 ERROR_ROUTE_EXISTS = 1
autoware_ad_api_msgs/ResponseStatus status
8 changes: 8 additions & 0 deletions common/autoware_ad_api_msgs/routing/srv/SetRoutePoints.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
std_msgs/Header header
geometry_msgs/Pose goal
geometry_msgs/Pose[] waypoints
---
uint16 ERROR_ROUTE_EXISTS = 1
uint16 ERROR_PLANNER_UNREADY = 2
uint16 ERROR_PLANNER_FAILED = 3
autoware_ad_api_msgs/ResponseStatus status
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_AD_API_SPECS__ROUTING_HPP_
#define AUTOWARE_AD_API_SPECS__ROUTING_HPP_

#include <rclcpp/qos.hpp>

#include <autoware_ad_api_msgs/msg/route.hpp>
#include <autoware_ad_api_msgs/msg/route_state.hpp>
#include <autoware_ad_api_msgs/srv/clear_route.hpp>
#include <autoware_ad_api_msgs/srv/set_route.hpp>
#include <autoware_ad_api_msgs/srv/set_route_points.hpp>

namespace autoware_ad_api::routing
{

struct SetRoutePoints
{
using Service = autoware_ad_api_msgs::srv::SetRoutePoints;
static constexpr char name[] = "/api/routing/set_route_points";
};

struct SetRoute
{
using Service = autoware_ad_api_msgs::srv::SetRoute;
static constexpr char name[] = "/api/routing/set_route";
};

struct ClearRoute
{
using Service = autoware_ad_api_msgs::srv::ClearRoute;
static constexpr char name[] = "/api/routing/clear_route";
};

struct RouteState
{
using Message = autoware_ad_api_msgs::msg::RouteState;
static constexpr char name[] = "/api/routing/state";
static constexpr size_t depth = 3;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

struct Route
{
using Message = autoware_ad_api_msgs::msg::Route;
static constexpr char name[] = "/api/routing/route";
static constexpr size_t depth = 1;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace autoware_ad_api::routing

#endif // AUTOWARE_AD_API_SPECS__ROUTING_HPP_
7 changes: 7 additions & 0 deletions common/component_interface_specs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
cmake_minimum_required(VERSION 3.14)
project(component_interface_specs)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_package()
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#define COMPONENT_INTERFACE_SPECS__PLANNING_HPP_

#include <rclcpp/qos.hpp>

#include <autoware_ad_api_msgs/msg/route.hpp>
#include <autoware_ad_api_msgs/msg/route_state.hpp>
#include <autoware_ad_api_msgs/srv/clear_route.hpp>
#include <autoware_ad_api_msgs/srv/set_route.hpp>
#include <autoware_ad_api_msgs/srv/set_route_points.hpp>

namespace planning_interface
{

struct SetRoutePoints
{
using Service = autoware_ad_api_msgs::srv::SetRoutePoints;
static constexpr char name[] = "/planning/mission_planning/set_route_points";
};

struct SetRoute
{
using Service = autoware_ad_api_msgs::srv::SetRoute;
static constexpr char name[] = "/planning/mission_planning/set_route";
};

struct ClearRoute
{
using Service = autoware_ad_api_msgs::srv::ClearRoute;
static constexpr char name[] = "/planning/mission_planning/clear_route";
};

struct RouteState
{
using Message = autoware_ad_api_msgs::msg::RouteState;
static constexpr char name[] = "/planning/mission_planning/state";
kenji-miyake marked this conversation as resolved.
Show resolved Hide resolved
static constexpr size_t depth = 3;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

struct Route
{
using Message = autoware_ad_api_msgs::msg::Route;
static constexpr char name[] = "/planning/mission_planning/route";
static constexpr size_t depth = 1;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

} // namespace planning_interface

#endif // COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
20 changes: 20 additions & 0 deletions common/component_interface_specs/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>component_interface_specs</name>
<version>0.0.0</version>
<description>The component_interface_specs package</description>
<maintainer email="isamu.takagi@tier4.jp">Takagi, Isamu</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<build_depend>autoware_cmake</build_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Original file line number Diff line number Diff line change
Expand Up @@ -87,11 +87,9 @@ class NodeAdaptor
void relay_service(
C & cli, S & srv, CallbackGroup group, std::optional<double> timeout = std::nullopt) const
{
using ReqT = typename C::element_type::SpecType::Service::Request::SharedPtr;
using ResT = typename C::element_type::SpecType::Service::Response::SharedPtr;
init_cli(cli);
init_srv(
srv, [cli, timeout](ReqT req, ResT res) { *res = *cli->call(req, timeout); }, group);
srv, [cli, timeout](auto req, auto res) { *res = *cli->call(req, timeout); }, group);
}

/// Create a service wrapper for logging.
Expand Down