Skip to content

Commit a369c32

Browse files
mitsudome-rcyn-liuNorahXiongbeginningfan
authored and
KhalilSelyan
committed
feat!: replace autoware_auto_msgs with autoware_msgs for tools (#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>
1 parent cbf1c8b commit a369c32

10 files changed

+120
-126
lines changed

tools/reaction_analyzer/README.md

+11-11
Original file line numberDiff line numberDiff line change
@@ -201,21 +201,21 @@ for each of the nodes.
201201
- `sensor_msgs/msg/Image`
202202
- `geometry_msgs/msg/PoseWithCovarianceStamped`
203203
- `sensor_msgs/msg/Imu`
204-
- `autoware_auto_vehicle_msgs/msg/ControlModeReport`
205-
- `autoware_auto_vehicle_msgs/msg/GearReport`
206-
- `autoware_auto_vehicle_msgs/msg/HazardLightsReport`
207-
- `autoware_auto_vehicle_msgs/msg/SteeringReport`
208-
- `autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport`
209-
- `autoware_auto_vehicle_msgs/msg/VelocityReport`
204+
- `autoware_vehicle_msgs/msg/ControlModeReport`
205+
- `autoware_vehicle_msgs/msg/GearReport`
206+
- `autoware_vehicle_msgs/msg/HazardLightsReport`
207+
- `autoware_vehicle_msgs/msg/SteeringReport`
208+
- `autoware_vehicle_msgs/msg/TurnIndicatorsReport`
209+
- `autoware_vehicle_msgs/msg/VelocityReport`
210210

211211
- **Subscriber Message Types:**
212212

213213
- `sensor_msgs/msg/PointCloud2`
214-
- `autoware_auto_perception_msgs/msg/DetectedObjects`
215-
- `autoware_auto_perception_msgs/msg/TrackedObjects`
216-
- `autoware_auto_msgs/msg/PredictedObject`
217-
- `autoware_auto_planning_msgs/msg/Trajectory`
218-
- `autoware_auto_control_msgs/msg/AckermannControlCommand`
214+
- `autoware_perception_msgs/msg/DetectedObjects`
215+
- `autoware_perception_msgs/msg/TrackedObjects`
216+
- `autoware_perception_msgs/msg/PredictedObject`
217+
- `autoware_planning_msgs/msg/Trajectory`
218+
- `autoware_control_msgs/msg/Control`
219219

220220
- **Reaction Types:**
221221
- `FIRST_BRAKE`

tools/reaction_analyzer/include/reaction_analyzer_node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -42,9 +42,9 @@ using autoware_adapi_v1_msgs::msg::LocalizationInitializationState;
4242
using autoware_adapi_v1_msgs::msg::OperationModeState;
4343
using autoware_adapi_v1_msgs::msg::RouteState;
4444
using autoware_adapi_v1_msgs::srv::ChangeOperationMode;
45-
using autoware_auto_perception_msgs::msg::PredictedObject;
46-
using autoware_auto_perception_msgs::msg::PredictedObjects;
4745
using autoware_internal_msgs::msg::PublishedTime;
46+
using autoware_perception_msgs::msg::PredictedObject;
47+
using autoware_perception_msgs::msg::PredictedObjects;
4848
using geometry_msgs::msg::Pose;
4949
using geometry_msgs::msg::PoseStamped;
5050
using nav_msgs::msg::Odometry;

tools/reaction_analyzer/include/subscriber.hpp

+15-18
Original file line numberDiff line numberDiff line change
@@ -39,23 +39,23 @@
3939

4040
namespace reaction_analyzer::subscriber
4141
{
42-
using autoware_auto_control_msgs::msg::AckermannControlCommand;
43-
using autoware_auto_perception_msgs::msg::DetectedObject;
44-
using autoware_auto_perception_msgs::msg::DetectedObjects;
45-
using autoware_auto_perception_msgs::msg::PredictedObject;
46-
using autoware_auto_perception_msgs::msg::PredictedObjects;
47-
using autoware_auto_perception_msgs::msg::TrackedObject;
48-
using autoware_auto_perception_msgs::msg::TrackedObjects;
49-
using autoware_auto_planning_msgs::msg::Trajectory;
42+
using autoware_control_msgs::msg::Control;
5043
using autoware_internal_msgs::msg::PublishedTime;
44+
using autoware_perception_msgs::msg::DetectedObject;
45+
using autoware_perception_msgs::msg::DetectedObjects;
46+
using autoware_perception_msgs::msg::PredictedObject;
47+
using autoware_perception_msgs::msg::PredictedObjects;
48+
using autoware_perception_msgs::msg::TrackedObject;
49+
using autoware_perception_msgs::msg::TrackedObjects;
50+
using autoware_planning_msgs::msg::Trajectory;
5151
using geometry_msgs::msg::Pose;
5252
using nav_msgs::msg::Odometry;
5353
using sensor_msgs::msg::PointCloud2;
5454

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

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

7474
// Variant to create subscribers for different message types
7575
using SubscriberVariablesVariant = std::variant<
7676
SubscriberVariables<PointCloud2>, SubscriberVariables<DetectedObjects>,
7777
SubscriberVariables<TrackedObjects>, SubscriberVariables<PredictedObjects>,
78-
SubscriberVariables<Trajectory>, SubscriberVariables<AckermannControlCommand>>;
78+
SubscriberVariables<Trajectory>, SubscriberVariables<Control>>;
7979

8080
// The configuration of the topic to be subscribed which are defined in reaction_chain
8181
struct TopicConfig
@@ -153,14 +153,11 @@ class SubscriberBase
153153
bool init_subscribers();
154154
std::optional<SubscriberVariablesVariant> get_subscriber_variable(
155155
const TopicConfig & topic_config);
156-
std::optional<size_t> find_first_brake_idx(
157-
const std::vector<AckermannControlCommand> & cmd_array);
158-
void set_control_command_to_buffer(
159-
std::vector<AckermannControlCommand> & buffer, const AckermannControlCommand & cmd) const;
156+
std::optional<size_t> find_first_brake_idx(const std::vector<Control> & cmd_array);
157+
void set_control_command_to_buffer(std::vector<Control> & buffer, const Control & cmd) const;
160158

161159
// Callbacks for modules are subscribed
162-
void on_control_command(
163-
const std::string & node_name, const AckermannControlCommand::ConstSharedPtr & msg_ptr);
160+
void on_control_command(const std::string & node_name, const Control::ConstSharedPtr & msg_ptr);
164161
void on_trajectory(const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr);
165162
void on_trajectory(
166163
const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr,

tools/reaction_analyzer/include/topic_publisher.hpp

+18-18
Original file line numberDiff line numberDiff line change
@@ -20,12 +20,12 @@
2020
#include <tf2_eigen/tf2_eigen/tf2_eigen.hpp>
2121
#include <utils.hpp>
2222

23-
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
24-
#include <autoware_auto_vehicle_msgs/msg/gear_report.hpp>
25-
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_report.hpp>
26-
#include <autoware_auto_vehicle_msgs/msg/steering_report.hpp>
27-
#include <autoware_auto_vehicle_msgs/msg/turn_indicators_report.hpp>
28-
#include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
23+
#include <autoware_vehicle_msgs/msg/control_mode_report.hpp>
24+
#include <autoware_vehicle_msgs/msg/gear_report.hpp>
25+
#include <autoware_vehicle_msgs/msg/hazard_lights_report.hpp>
26+
#include <autoware_vehicle_msgs/msg/steering_report.hpp>
27+
#include <autoware_vehicle_msgs/msg/turn_indicators_report.hpp>
28+
#include <autoware_vehicle_msgs/msg/velocity_report.hpp>
2929
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
3030
#include <nav_msgs/msg/odometry.hpp>
3131
#include <sensor_msgs/msg/camera_info.hpp>
@@ -45,12 +45,12 @@
4545

4646
namespace reaction_analyzer::topic_publisher
4747
{
48-
using autoware_auto_control_msgs::msg::AckermannControlCommand;
49-
using autoware_auto_perception_msgs::msg::DetectedObject;
50-
using autoware_auto_perception_msgs::msg::DetectedObjects;
51-
using autoware_auto_perception_msgs::msg::PredictedObject;
52-
using autoware_auto_perception_msgs::msg::PredictedObjects;
53-
using autoware_auto_planning_msgs::msg::Trajectory;
48+
using autoware_control_msgs::msg::Control;
49+
using autoware_perception_msgs::msg::DetectedObject;
50+
using autoware_perception_msgs::msg::DetectedObjects;
51+
using autoware_perception_msgs::msg::PredictedObject;
52+
using autoware_perception_msgs::msg::PredictedObjects;
53+
using autoware_planning_msgs::msg::Trajectory;
5454
using geometry_msgs::msg::Pose;
5555
using nav_msgs::msg::Odometry;
5656
using sensor_msgs::msg::PointCloud2;
@@ -164,12 +164,12 @@ using PublisherVariablesVariant = std::variant<
164164
PublisherVariables<geometry_msgs::msg::PoseWithCovarianceStamped>,
165165
PublisherVariables<geometry_msgs::msg::PoseStamped>, PublisherVariables<nav_msgs::msg::Odometry>,
166166
PublisherVariables<sensor_msgs::msg::Imu>,
167-
PublisherVariables<autoware_auto_vehicle_msgs::msg::ControlModeReport>,
168-
PublisherVariables<autoware_auto_vehicle_msgs::msg::GearReport>,
169-
PublisherVariables<autoware_auto_vehicle_msgs::msg::HazardLightsReport>,
170-
PublisherVariables<autoware_auto_vehicle_msgs::msg::SteeringReport>,
171-
PublisherVariables<autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport>,
172-
PublisherVariables<autoware_auto_vehicle_msgs::msg::VelocityReport>>;
167+
PublisherVariables<autoware_vehicle_msgs::msg::ControlModeReport>,
168+
PublisherVariables<autoware_vehicle_msgs::msg::GearReport>,
169+
PublisherVariables<autoware_vehicle_msgs::msg::HazardLightsReport>,
170+
PublisherVariables<autoware_vehicle_msgs::msg::SteeringReport>,
171+
PublisherVariables<autoware_vehicle_msgs::msg::TurnIndicatorsReport>,
172+
PublisherVariables<autoware_vehicle_msgs::msg::VelocityReport>>;
173173

174174
using LidarOutputPair = std::pair<
175175
std::shared_ptr<PublisherVariables<PointCloud2>>,

tools/reaction_analyzer/include/utils.hpp

+15-15
Original file line numberDiff line numberDiff line change
@@ -22,12 +22,12 @@
2222
#include <tier4_autoware_utils/geometry/geometry.hpp>
2323
#include <tier4_autoware_utils/math/unit_conversion.hpp>
2424

25-
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
26-
#include <autoware_auto_perception_msgs/msg/detected_objects.hpp>
27-
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
28-
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
29-
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
25+
#include <autoware_control_msgs/msg/control.hpp>
3026
#include <autoware_internal_msgs/msg/published_time.hpp>
27+
#include <autoware_perception_msgs/msg/detected_objects.hpp>
28+
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
29+
#include <autoware_perception_msgs/msg/tracked_objects.hpp>
30+
#include <autoware_planning_msgs/msg/trajectory.hpp>
3131
#include <sensor_msgs/msg/point_cloud2.hpp>
3232
#include <unique_identifier_msgs/msg/uuid.hpp>
3333
#include <visualization_msgs/msg/marker.hpp>
@@ -52,16 +52,16 @@
5252
// The reaction_analyzer namespace contains utility functions for the Reaction Analyzer tool.
5353
namespace reaction_analyzer
5454
{
55-
using autoware_auto_control_msgs::msg::AckermannControlCommand;
56-
using autoware_auto_perception_msgs::msg::DetectedObject;
57-
using autoware_auto_perception_msgs::msg::DetectedObjects;
58-
using autoware_auto_perception_msgs::msg::PredictedObject;
59-
using autoware_auto_perception_msgs::msg::PredictedObjects;
60-
using autoware_auto_perception_msgs::msg::TrackedObject;
61-
using autoware_auto_perception_msgs::msg::TrackedObjects;
62-
using autoware_auto_planning_msgs::msg::Trajectory;
63-
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
55+
using autoware_control_msgs::msg::Control;
6456
using autoware_internal_msgs::msg::PublishedTime;
57+
using autoware_perception_msgs::msg::DetectedObject;
58+
using autoware_perception_msgs::msg::DetectedObjects;
59+
using autoware_perception_msgs::msg::PredictedObject;
60+
using autoware_perception_msgs::msg::PredictedObjects;
61+
using autoware_perception_msgs::msg::TrackedObject;
62+
using autoware_perception_msgs::msg::TrackedObjects;
63+
using autoware_planning_msgs::msg::Trajectory;
64+
using autoware_planning_msgs::msg::TrajectoryPoint;
6565
using sensor_msgs::msg::PointCloud2;
6666

6767
/**
@@ -111,7 +111,7 @@ enum class PublisherMessageType {
111111
*/
112112
enum class SubscriberMessageType {
113113
UNKNOWN = 0,
114-
ACKERMANN_CONTROL_COMMAND = 1,
114+
CONTROL = 1,
115115
TRAJECTORY = 2,
116116
POINTCLOUD2 = 3,
117117
DETECTED_OBJECTS = 4,

tools/reaction_analyzer/package.xml

+5-5
Original file line numberDiff line numberDiff line change
@@ -15,12 +15,12 @@
1515
<buildtool_depend>autoware_cmake</buildtool_depend>
1616

1717
<depend>autoware_adapi_v1_msgs</depend>
18-
<depend>autoware_auto_control_msgs</depend>
19-
<depend>autoware_auto_perception_msgs</depend>
20-
<depend>autoware_auto_planning_msgs</depend>
21-
<depend>autoware_auto_system_msgs</depend>
22-
<depend>autoware_auto_vehicle_msgs</depend>
18+
<depend>autoware_control_msgs</depend>
2319
<depend>autoware_internal_msgs</depend>
20+
<depend>autoware_perception_msgs</depend>
21+
<depend>autoware_planning_msgs</depend>
22+
<depend>autoware_system_msgs</depend>
23+
<depend>autoware_vehicle_msgs</depend>
2424
<depend>eigen</depend>
2525
<depend>libpcl-all-dev</depend>
2626
<depend>message_filters</depend>

tools/reaction_analyzer/param/reaction_analyzer.param.yaml

+14-14
Original file line numberDiff line numberDiff line change
@@ -54,27 +54,27 @@
5454
obstacle_cruise_planner:
5555
topic_name: /planning/scenario_planning/lane_driving/trajectory
5656
time_debug_topic_name: /planning/scenario_planning/lane_driving/trajectory/debug/published_time
57-
message_type: autoware_auto_planning_msgs/msg/Trajectory
57+
message_type: autoware_planning_msgs/msg/Trajectory
5858
scenario_selector:
5959
topic_name: /planning/scenario_planning/scenario_selector/trajectory
6060
time_debug_topic_name: /planning/scenario_planning/scenario_selector/trajectory/debug/published_time
61-
message_type: autoware_auto_planning_msgs/msg/Trajectory
61+
message_type: autoware_planning_msgs/msg/Trajectory
6262
motion_velocity_smoother:
6363
topic_name: /planning/scenario_planning/motion_velocity_smoother/trajectory
6464
time_debug_topic_name: /planning/scenario_planning/motion_velocity_smoother/trajectory/debug/published_time
65-
message_type: autoware_auto_planning_msgs/msg/Trajectory
65+
message_type: autoware_planning_msgs/msg/Trajectory
6666
planning_validator:
6767
topic_name: /planning/scenario_planning/trajectory
6868
time_debug_topic_name: /planning/scenario_planning/trajectory/debug/published_time
69-
message_type: autoware_auto_planning_msgs/msg/Trajectory
69+
message_type: autoware_planning_msgs/msg/Trajectory
7070
trajectory_follower:
7171
topic_name: /control/trajectory_follower/control_cmd
7272
time_debug_topic_name: /control/trajectory_follower/control_cmd/debug/published_time
73-
message_type: autoware_auto_control_msgs/msg/AckermannControlCommand
73+
message_type: autoware_control_msgs/msg/Control
7474
vehicle_cmd_gate:
7575
topic_name: /control/command/control_cmd
7676
time_debug_topic_name: /control/command/control_cmd/debug/published_time
77-
message_type: autoware_auto_control_msgs/msg/AckermannControlCommand
77+
message_type: autoware_control_msgs/msg/Control
7878
common_ground_filter:
7979
topic_name: /perception/obstacle_segmentation/single_frame/pointcloud
8080
time_debug_topic_name: /perception/obstacle_segmentation/single_frame/pointcloud/debug/published_time
@@ -86,32 +86,32 @@
8686
multi_object_tracker:
8787
topic_name: /perception/object_recognition/tracking/near_objects
8888
time_debug_topic_name: /perception/object_recognition/tracking/near_objects/debug/published_time
89-
message_type: autoware_auto_perception_msgs/msg/TrackedObjects
89+
message_type: autoware_perception_msgs/msg/TrackedObjects
9090
lidar_centerpoint:
9191
topic_name: /perception/object_recognition/detection/centerpoint/objects
9292
time_debug_topic_name: /perception/object_recognition/detection/centerpoint/objects/debug/published_time
93-
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
93+
message_type: autoware_perception_msgs/msg/DetectedObjects
9494
obstacle_pointcloud_based_validator:
9595
topic_name: /perception/object_recognition/detection/centerpoint/validation/objects
9696
time_debug_topic_name: /perception/object_recognition/detection/centerpoint/validation/objects/debug/published_time
97-
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
97+
message_type: autoware_perception_msgs/msg/DetectedObjects
9898
decorative_tracker_merger:
9999
topic_name: /perception/object_recognition/tracking/objects
100100
time_debug_topic_name: /perception/object_recognition/tracking/objects/debug/published_time
101-
message_type: autoware_auto_perception_msgs/msg/TrackedObjects
101+
message_type: autoware_perception_msgs/msg/TrackedObjects
102102
detected_object_feature_remover:
103103
topic_name: /perception/object_recognition/detection/clustering/objects
104104
time_debug_topic_name: /perception/object_recognition/detection/clustering/objects/debug/published_time
105-
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
105+
message_type: autoware_perception_msgs/msg/DetectedObjects
106106
detection_by_tracker:
107107
topic_name: /perception/object_recognition/detection/detection_by_tracker/objects
108108
time_debug_topic_name: /perception/object_recognition/detection/detection_by_tracker/objects/debug/published_time
109-
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
109+
message_type: autoware_perception_msgs/msg/DetectedObjects
110110
object_lanelet_filter:
111111
topic_name: /perception/object_recognition/detection/objects
112112
time_debug_topic_name: /perception/object_recognition/detection/objects/debug/published_time
113-
message_type: autoware_auto_perception_msgs/msg/DetectedObjects
113+
message_type: autoware_perception_msgs/msg/DetectedObjects
114114
map_based_prediction:
115115
topic_name: /perception/object_recognition/objects
116116
time_debug_topic_name: /perception/object_recognition/objects/debug/published_time
117-
message_type: autoware_auto_perception_msgs/msg/PredictedObjects
117+
message_type: autoware_perception_msgs/msg/PredictedObjects

0 commit comments

Comments
 (0)