Skip to content

Commit

Permalink
feat: add get_qos() function
Browse files Browse the repository at this point in the history
Signed-off-by: Ryohsuke Mitsudome <[email protected]>
  • Loading branch information
mitsudome-r committed Dec 12, 2024
1 parent 7dfb09a commit 8db28c0
Show file tree
Hide file tree
Showing 7 changed files with 64 additions and 13 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
// Copyright 2023 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__CORE_COMPONENT_INTERFACE_SPECS__BASE_HPP_
#define AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__BASE_HPP_

#include <rclcpp/qos.hpp>

#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_map_msgs/msg/map_projector_info.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

namespace autoware::core_component_interface_specs
{

struct InterfaceBase
{
static constexpr char name[] = "";
static constexpr size_t depth = 1;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;

auto get_qos() const
{
return rclcpp::QoS{depth}.reliability(reliability).durability(durability);
}
};


} // namespace autoware::core_component_interface_specs::map

#endif // AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__BASE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,12 @@
#include <rclcpp/qos.hpp>

#include <autoware_control_msgs/msg/control.hpp>
#include <autoware/core_component_interface_specs/base.hpp>

namespace autoware::core_component_interface_specs::control
{

struct ControlCommand
struct ControlCommand : InterfaceBase
{
using Message = autoware_control_msgs::msg::Control;
static constexpr char name[] = "/control/command/control_cmd";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,14 @@

#include <rclcpp/qos.hpp>

#include <autoware/core_component_interface_specs/base.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>

namespace autoware::core_component_interface_specs::localization
{

struct KinematicState
struct KinematicState : InterfaceBase
{
using Message = nav_msgs::msg::Odometry;
static constexpr char name[] = "/localization/kinematic_state";
Expand All @@ -32,7 +33,7 @@ struct KinematicState
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

struct Acceleration
struct Acceleration : InterfaceBase
{
using Message = geometry_msgs::msg::AccelWithCovarianceStamped;
static constexpr char name[] = "/localization/acceleration";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,15 @@

#include <rclcpp/qos.hpp>

#include <autoware/core_component_interface_specs/base.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_map_msgs/msg/map_projector_info.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

namespace autoware::core_component_interface_specs::map
{

struct MapProjectorInfo
struct MapProjectorInfo : InterfaceBase
{
using Message = autoware_map_msgs::msg::MapProjectorInfo;
static constexpr char name[] = "/map/map_projector_info";
Expand All @@ -33,7 +34,7 @@ struct MapProjectorInfo
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

struct PointCloudMap
struct PointCloudMap : InterfaceBase
{
using Message = sensor_msgs::msg::PointCloud2;
static constexpr char name[] = "/map/point_cloud_map";
Expand All @@ -42,7 +43,7 @@ struct PointCloudMap
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

struct VectorMap
struct VectorMap : InterfaceBase
{
using Message = autoware_map_msgs::msg::LaneletMapBin;
static constexpr char name[] = "/map/vector_map";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,13 @@

#include <rclcpp/qos.hpp>

#include <autoware/core_component_interface_specs/base.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>

namespace autoware::core_component_interface_specs::perception
{

struct ObjectRecognition
struct ObjectRecognition : InterfaceBase
{
using Message = autoware_perception_msgs::msg::PredictedObjects;
static constexpr char name[] = "/perception/object_recognition/objects";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,12 @@
#include <autoware_planning_msgs/msg/lanelet_route.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>

#include <autoware/core_component_interface_specs/base.hpp>

namespace autoware::core_component_interface_specs::planning
{

struct LaneletRoute
struct LaneletRoute : InterfaceBase
{
using Message = autoware_planning_msgs::msg::LaneletRoute;
static constexpr char name[] = "/planning/mission_planning/route_selector/main/route";
Expand All @@ -32,7 +34,7 @@ struct LaneletRoute
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
};

struct Trajectory
struct Trajectory : InterfaceBase
{
using Message = autoware_planning_msgs::msg::Trajectory;
static constexpr char name[] = "/planning/scenario_planning/trajectory";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,10 @@
#ifndef AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#define AUTOWARE__CORE_COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_

#include "base.hpp"
#include <rclcpp/qos.hpp>

#include <autoware/core_component_interface_specs/base.hpp>
#include <autoware_vehicle_msgs/msg/gear_report.hpp>
#include <autoware_vehicle_msgs/msg/hazard_lights_report.hpp>
#include <autoware_vehicle_msgs/msg/steering_report.hpp>
Expand All @@ -25,7 +27,7 @@
namespace autoware::core_component_interface_specs::vehicle
{

struct SteeringStatus
struct SteeringStatus : InterfaceBase
{
using Message = autoware_vehicle_msgs::msg::SteeringReport;
static constexpr char name[] = "/vehicle/status/steering_status";
Expand All @@ -34,7 +36,7 @@ struct SteeringStatus
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

struct GearStatus
struct GearStatus : InterfaceBase
{
using Message = autoware_vehicle_msgs::msg::GearReport;
static constexpr char name[] = "/vehicle/status/gear_status";
Expand All @@ -43,7 +45,7 @@ struct GearStatus
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

struct TurnIndicatorStatus
struct TurnIndicatorStatus : InterfaceBase
{
using Message = autoware_vehicle_msgs::msg::TurnIndicatorsReport;
static constexpr char name[] = "/vehicle/status/turn_indicators_status";
Expand All @@ -52,7 +54,7 @@ struct TurnIndicatorStatus
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

struct HazardLightStatus
struct HazardLightStatus : InterfaceBase
{
using Message = autoware_vehicle_msgs::msg::HazardLightsReport;
static constexpr char name[] = "/vehicle/status/hazard_lights_status";
Expand Down

0 comments on commit 8db28c0

Please sign in to comment.