Skip to content

Commit

Permalink
fix: make get_qos() a free 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 Jan 15, 2025
1 parent 70a9fbe commit cfba383
Show file tree
Hide file tree
Showing 13 changed files with 99 additions and 34 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,15 @@
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__CONTROL_HPP_

#include <autoware/component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/utils.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_control_msgs/msg/control.hpp>

namespace autoware::component_interface_specs::control
{

struct ControlCommand : InterfaceBase
struct ControlCommand
{
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 @@ -15,7 +15,7 @@
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_

#include <autoware/component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/utils.hpp>
#include <rclcpp/qos.hpp>

#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
Expand All @@ -24,7 +24,7 @@
namespace autoware::component_interface_specs::localization
{

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

struct Acceleration : InterfaceBase
struct Acceleration
{
using Message = geometry_msgs::msg::AccelWithCovarianceStamped;
static constexpr char name[] = "/localization/acceleration";
Expand All @@ -44,4 +44,4 @@ struct Acceleration : InterfaceBase

} // namespace autoware::component_interface_specs::localization

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__LOCALIZATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__MAP_HPP_

#include <autoware/component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/utils.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
Expand All @@ -25,7 +25,7 @@
namespace autoware::component_interface_specs::map
{

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

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

struct VectorMap : InterfaceBase
struct VectorMap
{
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 @@ -15,15 +15,15 @@
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_

#include <autoware/component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/utils.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_perception_msgs/msg/predicted_objects.hpp>

namespace autoware::component_interface_specs::perception
{

struct ObjectRecognition : InterfaceBase
struct ObjectRecognition
{
using Message = autoware_perception_msgs::msg::PredictedObjects;
static constexpr char name[] = "/perception/object_recognition/objects";
Expand All @@ -34,4 +34,4 @@ struct ObjectRecognition : InterfaceBase

} // namespace autoware::component_interface_specs::perception

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PERCEPTION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_

#include <autoware/component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/utils.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_planning_msgs/msg/lanelet_route.hpp>
Expand All @@ -24,7 +24,7 @@
namespace autoware::component_interface_specs::planning
{

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

struct Trajectory : InterfaceBase
struct Trajectory
{
using Message = autoware_planning_msgs::msg::Trajectory;
static constexpr char name[] = "/planning/scenario_planning/trajectory";
Expand All @@ -44,4 +44,4 @@ struct Trajectory : InterfaceBase

} // namespace autoware::component_interface_specs::planning

#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
#endif // AUTOWARE__COMPONENT_INTERFACE_SPECS__PLANNING_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -24,18 +24,11 @@
namespace autoware::component_interface_specs
{

struct InterfaceBase
template <typename T>
rclcpp::QoS get_qos(T interface)
{
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;

static rclcpp::QoS get_qos()
{
return rclcpp::QoS{depth}.reliability(reliability).durability(durability);
}
};
return rclcpp::QoS{interface.depth}.reliability(interface.reliability).durability(interface.durability);
}

} // namespace autoware::component_interface_specs

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
#ifndef AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_
#define AUTOWARE__COMPONENT_INTERFACE_SPECS__VEHICLE_HPP_

#include "base.hpp"
#include "utils.hpp"

#include <autoware/component_interface_specs/base.hpp>
#include <autoware/component_interface_specs/utils.hpp>
#include <rclcpp/qos.hpp>

#include <autoware_vehicle_msgs/msg/gear_report.hpp>
Expand All @@ -28,7 +28,7 @@
namespace autoware::component_interface_specs::vehicle
{

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

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

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

struct HazardLightStatus : InterfaceBase
struct HazardLightStatus
{
using Message = autoware_vehicle_msgs::msg::HazardLightsReport;
static constexpr char name[] = "/vehicle/status/hazard_lights_status";
Expand Down
11 changes: 11 additions & 0 deletions common/autoware_component_interface_specs/test/test_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,4 +17,15 @@

TEST(control, interface)
{
using autoware::component_interface_specs::control::ControlCommand;
ControlCommand control_command;
size_t depth = 1;
EXPECT_EQ(control_command.depth, depth);
EXPECT_EQ(control_command.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(control_command.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);

const auto qos = autoware::component_interface_specs::get_qos(control_command);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::TransientLocal);
}
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,12 @@ TEST(localization, interface)
EXPECT_EQ(kinematic_state.depth, depth);
EXPECT_EQ(kinematic_state.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(kinematic_state.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);


const auto qos = autoware::component_interface_specs::get_qos(kinematic_state);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::Volatile);
}

{
Expand All @@ -33,5 +39,10 @@ TEST(localization, interface)
EXPECT_EQ(acceleration.depth, depth);
EXPECT_EQ(acceleration.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(acceleration.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);

const auto qos = autoware::component_interface_specs::get_qos(acceleration);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::Volatile);
}
}
15 changes: 15 additions & 0 deletions common/autoware_component_interface_specs/test/test_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,11 @@ TEST(map, interface)
EXPECT_EQ(map_projector.depth, depth);
EXPECT_EQ(map_projector.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(map_projector.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);

const auto qos = autoware::component_interface_specs::get_qos(map_projector);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::TransientLocal);
}

{
Expand All @@ -33,6 +38,11 @@ TEST(map, interface)
EXPECT_EQ(point_cloud_map.depth, depth);
EXPECT_EQ(point_cloud_map.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(point_cloud_map.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);

const auto qos = autoware::component_interface_specs::get_qos(point_cloud_map);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::TransientLocal);
}

{
Expand All @@ -42,5 +52,10 @@ TEST(map, interface)
EXPECT_EQ(vector_map.depth, depth);
EXPECT_EQ(vector_map.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(vector_map.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);

const auto qos = autoware::component_interface_specs::get_qos(vector_map);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::TransientLocal);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -24,5 +24,10 @@ TEST(perception, interface)
EXPECT_EQ(object_recognition.depth, depth);
EXPECT_EQ(object_recognition.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(object_recognition.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);

const auto qos = autoware::component_interface_specs::get_qos(object_recognition);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::Volatile);
}
}
10 changes: 10 additions & 0 deletions common/autoware_component_interface_specs/test/test_planning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,11 @@ TEST(planning, interface)
EXPECT_EQ(route.depth, depth);
EXPECT_EQ(route.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(route.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);

const auto qos = autoware::component_interface_specs::get_qos(route);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::TransientLocal);
}

{
Expand All @@ -33,5 +38,10 @@ TEST(planning, interface)
EXPECT_EQ(trajectory.depth, depth);
EXPECT_EQ(trajectory.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(trajectory.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);

const auto qos = autoware::component_interface_specs::get_qos(trajectory);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::Volatile);
}
}
20 changes: 20 additions & 0 deletions common/autoware_component_interface_specs/test/test_vehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,11 @@ TEST(vehicle, interface)
EXPECT_EQ(status.depth, depth);
EXPECT_EQ(status.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(status.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);

const auto qos = autoware::component_interface_specs::get_qos(status);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::Volatile);
}

{
Expand All @@ -33,6 +38,11 @@ TEST(vehicle, interface)
EXPECT_EQ(status.depth, depth);
EXPECT_EQ(status.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(status.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);

const auto qos = autoware::component_interface_specs::get_qos(status);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::Volatile);
}

{
Expand All @@ -42,6 +52,11 @@ TEST(vehicle, interface)
EXPECT_EQ(status.depth, depth);
EXPECT_EQ(status.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(status.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);

const auto qos = autoware::component_interface_specs::get_qos(status);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::Volatile);
}

{
Expand All @@ -51,5 +66,10 @@ TEST(vehicle, interface)
EXPECT_EQ(status.depth, depth);
EXPECT_EQ(status.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(status.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);

const auto qos = autoware::component_interface_specs::get_qos(status);
EXPECT_EQ(qos.depth(), depth);
EXPECT_EQ(qos.reliability(), rclcpp::ReliabilityPolicy::Reliable);
EXPECT_EQ(qos.durability(), rclcpp::DurabilityPolicy::Volatile);
}
}

0 comments on commit cfba383

Please sign in to comment.