Skip to content

Commit

Permalink
feat!: replace autoware_auto_msgs with autoware_msgs for tools (autow…
Browse files Browse the repository at this point in the history
…arefoundation#7250)

Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
Co-authored-by: Cynthia Liu <cynthia.liu@autocore.ai>
Co-authored-by: NorahXiong <norah.xiong@autocore.ai>
Co-authored-by: beginningfan <beginning.fan@autocore.ai>
  • Loading branch information
4 people authored and a-maumau committed Jun 7, 2024
1 parent a96b986 commit 641089e
Show file tree
Hide file tree
Showing 10 changed files with 120 additions and 126 deletions.
22 changes: 11 additions & 11 deletions tools/reaction_analyzer/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -201,21 +201,21 @@ for each of the nodes.
- `sensor_msgs/msg/Image`
- `geometry_msgs/msg/PoseWithCovarianceStamped`
- `sensor_msgs/msg/Imu`
- `autoware_auto_vehicle_msgs/msg/ControlModeReport`
- `autoware_auto_vehicle_msgs/msg/GearReport`
- `autoware_auto_vehicle_msgs/msg/HazardLightsReport`
- `autoware_auto_vehicle_msgs/msg/SteeringReport`
- `autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport`
- `autoware_auto_vehicle_msgs/msg/VelocityReport`
- `autoware_vehicle_msgs/msg/ControlModeReport`
- `autoware_vehicle_msgs/msg/GearReport`
- `autoware_vehicle_msgs/msg/HazardLightsReport`
- `autoware_vehicle_msgs/msg/SteeringReport`
- `autoware_vehicle_msgs/msg/TurnIndicatorsReport`
- `autoware_vehicle_msgs/msg/VelocityReport`

- **Subscriber Message Types:**

- `sensor_msgs/msg/PointCloud2`
- `autoware_auto_perception_msgs/msg/DetectedObjects`
- `autoware_auto_perception_msgs/msg/TrackedObjects`
- `autoware_auto_msgs/msg/PredictedObject`
- `autoware_auto_planning_msgs/msg/Trajectory`
- `autoware_auto_control_msgs/msg/AckermannControlCommand`
- `autoware_perception_msgs/msg/DetectedObjects`
- `autoware_perception_msgs/msg/TrackedObjects`
- `autoware_perception_msgs/msg/PredictedObject`
- `autoware_planning_msgs/msg/Trajectory`
- `autoware_control_msgs/msg/Control`

- **Reaction Types:**
- `FIRST_BRAKE`
Expand Down
4 changes: 2 additions & 2 deletions tools/reaction_analyzer/include/reaction_analyzer_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,9 @@ using autoware_adapi_v1_msgs::msg::LocalizationInitializationState;
using autoware_adapi_v1_msgs::msg::OperationModeState;
using autoware_adapi_v1_msgs::msg::RouteState;
using autoware_adapi_v1_msgs::srv::ChangeOperationMode;
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_internal_msgs::msg::PublishedTime;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::PoseStamped;
using nav_msgs::msg::Odometry;
Expand Down
33 changes: 15 additions & 18 deletions tools/reaction_analyzer/include/subscriber.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,23 +39,23 @@

namespace reaction_analyzer::subscriber
{
using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_auto_perception_msgs::msg::DetectedObject;
using autoware_auto_perception_msgs::msg::DetectedObjects;
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_auto_perception_msgs::msg::TrackedObject;
using autoware_auto_perception_msgs::msg::TrackedObjects;
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_control_msgs::msg::Control;
using autoware_internal_msgs::msg::PublishedTime;
using autoware_perception_msgs::msg::DetectedObject;
using autoware_perception_msgs::msg::DetectedObjects;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::TrackedObject;
using autoware_perception_msgs::msg::TrackedObjects;
using autoware_planning_msgs::msg::Trajectory;
using geometry_msgs::msg::Pose;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::PointCloud2;

// Buffers to be used to store subscribed messages' data, pipeline Header, and PublishedTime
using MessageBuffer = std::optional<PublishedTime>;
// We need to store the past AckermannControlCommands to analyze the first brake
using ControlCommandBuffer = std::pair<std::vector<AckermannControlCommand>, MessageBuffer>;
// We need to store the past Control to analyze the first brake
using ControlCommandBuffer = std::pair<std::vector<Control>, MessageBuffer>;
// Variant to store different types of buffers
using MessageBufferVariant = std::variant<ControlCommandBuffer, MessageBuffer>;

Expand All @@ -67,15 +67,15 @@ struct SubscriberVariables
std::unique_ptr<message_filters::Subscriber<MessageType>> sub1_;
std::unique_ptr<message_filters::Subscriber<PublishedTime>> sub2_;
std::unique_ptr<message_filters::Synchronizer<ExactTimePolicy>> synchronizer_;
// tmp: only for the messages who don't have header e.g. AckermannControlCommand
// tmp: only for the messages who don't have header e.g. Control
std::unique_ptr<message_filters::Cache<PublishedTime>> cache_;
};

// Variant to create subscribers for different message types
using SubscriberVariablesVariant = std::variant<
SubscriberVariables<PointCloud2>, SubscriberVariables<DetectedObjects>,
SubscriberVariables<TrackedObjects>, SubscriberVariables<PredictedObjects>,
SubscriberVariables<Trajectory>, SubscriberVariables<AckermannControlCommand>>;
SubscriberVariables<Trajectory>, SubscriberVariables<Control>>;

// The configuration of the topic to be subscribed which are defined in reaction_chain
struct TopicConfig
Expand Down Expand Up @@ -153,14 +153,11 @@ class SubscriberBase
bool init_subscribers();
std::optional<SubscriberVariablesVariant> get_subscriber_variable(
const TopicConfig & topic_config);
std::optional<size_t> find_first_brake_idx(
const std::vector<AckermannControlCommand> & cmd_array);
void set_control_command_to_buffer(
std::vector<AckermannControlCommand> & buffer, const AckermannControlCommand & cmd) const;
std::optional<size_t> find_first_brake_idx(const std::vector<Control> & cmd_array);
void set_control_command_to_buffer(std::vector<Control> & buffer, const Control & cmd) const;

// Callbacks for modules are subscribed
void on_control_command(
const std::string & node_name, const AckermannControlCommand::ConstSharedPtr & msg_ptr);
void on_control_command(const std::string & node_name, const Control::ConstSharedPtr & msg_ptr);
void on_trajectory(const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr);
void on_trajectory(
const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr,
Expand Down
36 changes: 18 additions & 18 deletions tools/reaction_analyzer/include/topic_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,12 @@
#include <tf2_eigen/tf2_eigen/tf2_eigen.hpp>
#include <utils.hpp>

#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/steering_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/turn_indicators_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
#include <autoware_vehicle_msgs/msg/control_mode_report.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>
#include <autoware_vehicle_msgs/msg/turn_indicators_report.hpp>
#include <autoware_vehicle_msgs/msg/velocity_report.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
Expand All @@ -45,12 +45,12 @@

namespace reaction_analyzer::topic_publisher
{
using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_auto_perception_msgs::msg::DetectedObject;
using autoware_auto_perception_msgs::msg::DetectedObjects;
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_control_msgs::msg::Control;
using autoware_perception_msgs::msg::DetectedObject;
using autoware_perception_msgs::msg::DetectedObjects;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_planning_msgs::msg::Trajectory;
using geometry_msgs::msg::Pose;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::PointCloud2;
Expand Down Expand Up @@ -164,12 +164,12 @@ using PublisherVariablesVariant = std::variant<
PublisherVariables<geometry_msgs::msg::PoseWithCovarianceStamped>,
PublisherVariables<geometry_msgs::msg::PoseStamped>, PublisherVariables<nav_msgs::msg::Odometry>,
PublisherVariables<sensor_msgs::msg::Imu>,
PublisherVariables<autoware_auto_vehicle_msgs::msg::ControlModeReport>,
PublisherVariables<autoware_auto_vehicle_msgs::msg::GearReport>,
PublisherVariables<autoware_auto_vehicle_msgs::msg::HazardLightsReport>,
PublisherVariables<autoware_auto_vehicle_msgs::msg::SteeringReport>,
PublisherVariables<autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport>,
PublisherVariables<autoware_auto_vehicle_msgs::msg::VelocityReport>>;
PublisherVariables<autoware_vehicle_msgs::msg::ControlModeReport>,
PublisherVariables<autoware_vehicle_msgs::msg::GearReport>,
PublisherVariables<autoware_vehicle_msgs::msg::HazardLightsReport>,
PublisherVariables<autoware_vehicle_msgs::msg::SteeringReport>,
PublisherVariables<autoware_vehicle_msgs::msg::TurnIndicatorsReport>,
PublisherVariables<autoware_vehicle_msgs::msg::VelocityReport>>;

using LidarOutputPair = std::pair<
std::shared_ptr<PublisherVariables<PointCloud2>>,
Expand Down
30 changes: 15 additions & 15 deletions tools/reaction_analyzer/include/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,12 +22,12 @@
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/math/unit_conversion.hpp>

#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_control_msgs/msg/control.hpp>
#include <autoware_internal_msgs/msg/published_time.hpp>
#include <autoware_perception_msgs/msg/detected_objects.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_perception_msgs/msg/tracked_objects.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <unique_identifier_msgs/msg/uuid.hpp>
#include <visualization_msgs/msg/marker.hpp>
Expand All @@ -52,16 +52,16 @@
// The reaction_analyzer namespace contains utility functions for the Reaction Analyzer tool.
namespace reaction_analyzer
{
using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_auto_perception_msgs::msg::DetectedObject;
using autoware_auto_perception_msgs::msg::DetectedObjects;
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_auto_perception_msgs::msg::TrackedObject;
using autoware_auto_perception_msgs::msg::TrackedObjects;
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
using autoware_control_msgs::msg::Control;
using autoware_internal_msgs::msg::PublishedTime;
using autoware_perception_msgs::msg::DetectedObject;
using autoware_perception_msgs::msg::DetectedObjects;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::TrackedObject;
using autoware_perception_msgs::msg::TrackedObjects;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using sensor_msgs::msg::PointCloud2;

/**
Expand Down Expand Up @@ -111,7 +111,7 @@ enum class PublisherMessageType {
*/
enum class SubscriberMessageType {
UNKNOWN = 0,
ACKERMANN_CONTROL_COMMAND = 1,
CONTROL = 1,
TRAJECTORY = 2,
POINTCLOUD2 = 3,
DETECTED_OBJECTS = 4,
Expand Down
10 changes: 5 additions & 5 deletions tools/reaction_analyzer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_auto_control_msgs</depend>
<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_system_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_internal_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_system_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>eigen</depend>
<depend>libpcl-all-dev</depend>
<depend>message_filters</depend>
Expand Down
28 changes: 14 additions & 14 deletions tools/reaction_analyzer/param/reaction_analyzer.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -54,27 +54,27 @@
obstacle_cruise_planner:
topic_name: /planning/scenario_planning/lane_driving/trajectory
time_debug_topic_name: /planning/scenario_planning/lane_driving/trajectory/debug/published_time
message_type: autoware_auto_planning_msgs/msg/Trajectory
message_type: autoware_planning_msgs/msg/Trajectory
scenario_selector:
topic_name: /planning/scenario_planning/scenario_selector/trajectory
time_debug_topic_name: /planning/scenario_planning/scenario_selector/trajectory/debug/published_time
message_type: autoware_auto_planning_msgs/msg/Trajectory
message_type: autoware_planning_msgs/msg/Trajectory
motion_velocity_smoother:
topic_name: /planning/scenario_planning/motion_velocity_smoother/trajectory
time_debug_topic_name: /planning/scenario_planning/motion_velocity_smoother/trajectory/debug/published_time
message_type: autoware_auto_planning_msgs/msg/Trajectory
message_type: autoware_planning_msgs/msg/Trajectory
planning_validator:
topic_name: /planning/scenario_planning/trajectory
time_debug_topic_name: /planning/scenario_planning/trajectory/debug/published_time
message_type: autoware_auto_planning_msgs/msg/Trajectory
message_type: autoware_planning_msgs/msg/Trajectory
trajectory_follower:
topic_name: /control/trajectory_follower/control_cmd
time_debug_topic_name: /control/trajectory_follower/control_cmd/debug/published_time
message_type: autoware_auto_control_msgs/msg/AckermannControlCommand
message_type: autoware_control_msgs/msg/Control
vehicle_cmd_gate:
topic_name: /control/command/control_cmd
time_debug_topic_name: /control/command/control_cmd/debug/published_time
message_type: autoware_auto_control_msgs/msg/AckermannControlCommand
message_type: autoware_control_msgs/msg/Control
common_ground_filter:
topic_name: /perception/obstacle_segmentation/single_frame/pointcloud
time_debug_topic_name: /perception/obstacle_segmentation/single_frame/pointcloud/debug/published_time
Expand All @@ -86,32 +86,32 @@
multi_object_tracker:
topic_name: /perception/object_recognition/tracking/near_objects
time_debug_topic_name: /perception/object_recognition/tracking/near_objects/debug/published_time
message_type: autoware_auto_perception_msgs/msg/TrackedObjects
message_type: autoware_perception_msgs/msg/TrackedObjects
lidar_centerpoint:
topic_name: /perception/object_recognition/detection/centerpoint/objects
time_debug_topic_name: /perception/object_recognition/detection/centerpoint/objects/debug/published_time
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
message_type: autoware_perception_msgs/msg/DetectedObjects
obstacle_pointcloud_based_validator:
topic_name: /perception/object_recognition/detection/centerpoint/validation/objects
time_debug_topic_name: /perception/object_recognition/detection/centerpoint/validation/objects/debug/published_time
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
message_type: autoware_perception_msgs/msg/DetectedObjects
decorative_tracker_merger:
topic_name: /perception/object_recognition/tracking/objects
time_debug_topic_name: /perception/object_recognition/tracking/objects/debug/published_time
message_type: autoware_auto_perception_msgs/msg/TrackedObjects
message_type: autoware_perception_msgs/msg/TrackedObjects
detected_object_feature_remover:
topic_name: /perception/object_recognition/detection/clustering/objects
time_debug_topic_name: /perception/object_recognition/detection/clustering/objects/debug/published_time
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
message_type: autoware_perception_msgs/msg/DetectedObjects
detection_by_tracker:
topic_name: /perception/object_recognition/detection/detection_by_tracker/objects
time_debug_topic_name: /perception/object_recognition/detection/detection_by_tracker/objects/debug/published_time
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
message_type: autoware_perception_msgs/msg/DetectedObjects
object_lanelet_filter:
topic_name: /perception/object_recognition/detection/objects
time_debug_topic_name: /perception/object_recognition/detection/objects/debug/published_time
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
message_type: autoware_perception_msgs/msg/DetectedObjects
map_based_prediction:
topic_name: /perception/object_recognition/objects
time_debug_topic_name: /perception/object_recognition/objects/debug/published_time
message_type: autoware_auto_perception_msgs/msg/PredictedObjects
message_type: autoware_perception_msgs/msg/PredictedObjects
Loading

0 comments on commit 641089e

Please sign in to comment.