Skip to content

Commit

Permalink
feat!: replace autoware_auto_msgs with autoware_msgs for control modules
Browse files Browse the repository at this point in the history
Signed-off-by: Ryohsuke Mitsudome <[email protected]>
Co-authored-by: Cynthia Liu <[email protected]>
Co-authored-by: NorahXiong <[email protected]>
Co-authored-by: beginningfan <[email protected]>
  • Loading branch information
4 people committed Jun 3, 2024
1 parent 19ea101 commit 7b50687
Show file tree
Hide file tree
Showing 105 changed files with 703 additions and 741 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@
#include <tier4_autoware_utils/ros/polling_subscriber.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_auto_system_msgs/msg/autoware_state.hpp>
#include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <autoware_system_msgs/msg/autoware_state.hpp>
#include <autoware_vehicle_msgs/msg/velocity_report.hpp>
#include <geometry_msgs/msg/vector3.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/imu.hpp>
Expand All @@ -52,9 +52,9 @@
namespace autoware::motion::control::autonomous_emergency_braking
{

using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_system_msgs::msg::AutowareState;
using autoware_auto_vehicle_msgs::msg::VelocityReport;
using autoware_planning_msgs::msg::Trajectory;
using autoware_system_msgs::msg::AutowareState;
using autoware_vehicle_msgs::msg::VelocityReport;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::Imu;
using sensor_msgs::msg::PointCloud2;
Expand Down
7 changes: 4 additions & 3 deletions control/autonomous_emergency_braking/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,10 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_auto_control_msgs</depend>
<depend>autoware_auto_system_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_system_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>diagnostic_updater</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
Expand Down
14 changes: 7 additions & 7 deletions control/control_performance_analysis/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,13 @@ Error acceleration calculations are made based on the velocity calculations abov

### Input topics

| Name | Type | Description |
| ---------------------------------------- | -------------------------------------------------------- | ------------------------------------------- |
| `/planning/scenario_planning/trajectory` | autoware_auto_planning_msgs::msg::Trajectory | Output trajectory from planning module. |
| `/control/command/control_cmd` | autoware_auto_control_msgs::msg::AckermannControlCommand | Output control command from control module. |
| `/vehicle/status/steering_status` | autoware_auto_vehicle_msgs::msg::SteeringReport | Steering information from vehicle. |
| `/localization/kinematic_state` | nav_msgs::msg::Odometry | Use twist from odometry. |
| `/tf` | tf2_msgs::msg::TFMessage | Extract ego pose from tf. |
| Name | Type | Description |
| ---------------------------------------- | ------------------------------------------ | ------------------------------------------- |
| `/planning/scenario_planning/trajectory` | autoware_planning_msgs::msg::Trajectory | Output trajectory from planning module. |
| `/control/command/control_cmd` | autoware_control_msgs::msg::Control | Output control command from control module. |
| `/vehicle/status/steering_status` | autoware_vehicle_msgs::msg::SteeringReport | Steering information from vehicle. |
| `/localization/kinematic_state` | nav_msgs::msg::Odometry | Use twist from odometry. |
| `/tf` | tf2_msgs::msg::TFMessage | Extract ego pose from tf. |

### Output topics

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@
#include <Eigen/Core>
#include <rclcpp/time.hpp>

#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_auto_vehicle_msgs/msg/steering_report.hpp>
#include <autoware_control_msgs/msg/control.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <autoware_vehicle_msgs/msg/steering_report.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_array.hpp>
#include <geometry_msgs/msg/twist.hpp>
Expand All @@ -39,9 +39,9 @@

namespace control_performance_analysis
{
using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_vehicle_msgs::msg::SteeringReport;
using autoware_control_msgs::msg::Control;
using autoware_planning_msgs::msg::Trajectory;
using autoware_vehicle_msgs::msg::SteeringReport;
using control_performance_analysis::msg::DrivingMonitorStamped;
using control_performance_analysis::msg::Error;
using control_performance_analysis::msg::ErrorStamped;
Expand Down Expand Up @@ -73,7 +73,7 @@ class ControlPerformanceAnalysisCore
// Setters
void setCurrentPose(const Pose & msg);
void setCurrentWaypoints(const Trajectory & trajectory);
void setCurrentControlValue(const AckermannControlCommand & msg);
void setCurrentControlValue(const Control & msg);
void setInterpolatedVars(
const Pose & interpolated_pose, const double & interpolated_velocity,
const double & interpolated_acceleration, const double & interpolated_steering_angle);
Expand All @@ -100,10 +100,10 @@ class ControlPerformanceAnalysisCore
Params p_;

// Variables Received Outside
std::shared_ptr<autoware_auto_planning_msgs::msg::Trajectory> current_trajectory_ptr_;
std::shared_ptr<autoware_planning_msgs::msg::Trajectory> current_trajectory_ptr_;
std::shared_ptr<Pose> current_vec_pose_ptr_;
std::shared_ptr<std::vector<Odometry>> odom_history_ptr_; // velocities at k-2, k-1, k, k+1
std::shared_ptr<AckermannControlCommand> current_control_ptr_;
std::shared_ptr<Control> current_control_ptr_;
std::shared_ptr<SteeringReport> current_vec_steering_msg_ptr_;

// State holder
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@
#include <signal_processing/lowpass_filter_1d.hpp>
#include <tier4_autoware_utils/ros/self_pose_listener.hpp>

#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_auto_vehicle_msgs/msg/steering_report.hpp>
#include <autoware_control_msgs/msg/control.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <autoware_vehicle_msgs/msg/steering_report.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>

Expand All @@ -36,9 +36,9 @@

namespace control_performance_analysis
{
using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_vehicle_msgs::msg::SteeringReport;
using autoware_control_msgs::msg::Control;
using autoware_planning_msgs::msg::Trajectory;
using autoware_vehicle_msgs::msg::SteeringReport;
using control_performance_analysis::msg::DrivingMonitorStamped;
using control_performance_analysis::msg::ErrorStamped;
using geometry_msgs::msg::PoseStamped;
Expand All @@ -52,9 +52,8 @@ class ControlPerformanceAnalysisNode : public rclcpp::Node
private:
// Subscribers and Local Variable Assignment
rclcpp::Subscription<Trajectory>::SharedPtr sub_trajectory_; // subscribe to trajectory
rclcpp::Subscription<AckermannControlCommand>::SharedPtr
sub_control_cmd_; // subscribe to steering control value
rclcpp::Subscription<Odometry>::SharedPtr sub_velocity_; // subscribe to velocity
rclcpp::Subscription<Control>::SharedPtr sub_control_cmd_; // subscribe to steering control value
rclcpp::Subscription<Odometry>::SharedPtr sub_velocity_; // subscribe to velocity
rclcpp::Subscription<SteeringReport>::SharedPtr sub_vehicle_steering_;

// Publishers
Expand All @@ -68,26 +67,26 @@ class ControlPerformanceAnalysisNode : public rclcpp::Node

// Callback Methods
void onTrajectory(const Trajectory::ConstSharedPtr msg);
void onControlRaw(const AckermannControlCommand::ConstSharedPtr control_msg);
void onControlRaw(const Control::ConstSharedPtr control_msg);
void onVecSteeringMeasured(const SteeringReport::ConstSharedPtr meas_steer_msg);
void onVelocity(const Odometry::ConstSharedPtr msg);

// Parameters
Params param_{}; // wheelbase, control period and feedback coefficients.
// State holder
AckermannControlCommand::ConstSharedPtr last_control_cmd_;
Control::ConstSharedPtr last_control_cmd_;
double d_control_cmd_{0};

// Subscriber Parameters
Trajectory::ConstSharedPtr current_trajectory_ptr_; // ConstPtr to local traj.
AckermannControlCommand::ConstSharedPtr current_control_msg_ptr_;
Control::ConstSharedPtr current_control_msg_ptr_;
SteeringReport::ConstSharedPtr current_vec_steering_msg_ptr_;
Odometry::ConstSharedPtr current_odom_ptr_;
PoseStamped::ConstSharedPtr current_pose_; // pose of the vehicle, x, y, heading

// prev states
Trajectory prev_traj;
AckermannControlCommand prev_cmd;
Control prev_cmd;
SteeringReport prev_steering;

// Algorithm
Expand Down
6 changes: 3 additions & 3 deletions control/control_performance_analysis/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@

<build_depend>builtin_interfaces</build_depend>

<depend>autoware_auto_control_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
<depend>libboost-dev</depend>
<depend>motion_utils</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,9 +75,9 @@ void ControlPerformanceAnalysisCore::setCurrentPose(const Pose & msg)
current_vec_pose_ptr_ = std::make_shared<Pose>(msg);
}

void ControlPerformanceAnalysisCore::setCurrentControlValue(const AckermannControlCommand & msg)
void ControlPerformanceAnalysisCore::setCurrentControlValue(const Control & msg)
{
current_control_ptr_ = std::make_shared<AckermannControlCommand>(msg);
current_control_ptr_ = std::make_shared<Control>(msg);
}

std::pair<bool, int32_t> ControlPerformanceAnalysisCore::findClosestPrevWayPointIdx_path_direction()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

namespace
{
using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_control_msgs::msg::Control;
using control_performance_analysis::msg::DrivingMonitorStamped;
using control_performance_analysis::msg::ErrorStamped;

Expand Down Expand Up @@ -62,7 +62,7 @@ ControlPerformanceAnalysisNode::ControlPerformanceAnalysisNode(
"~/input/reference_trajectory", 1,
std::bind(&ControlPerformanceAnalysisNode::onTrajectory, this, _1));

sub_control_cmd_ = create_subscription<AckermannControlCommand>(
sub_control_cmd_ = create_subscription<Control>(
"~/input/control_raw", 1, std::bind(&ControlPerformanceAnalysisNode::onControlRaw, this, _1));

sub_vehicle_steering_ = create_subscription<SteeringReport>(
Expand Down Expand Up @@ -93,8 +93,7 @@ void ControlPerformanceAnalysisNode::onTrajectory(const Trajectory::ConstSharedP
current_trajectory_ptr_ = msg;
}

void ControlPerformanceAnalysisNode::onControlRaw(
const AckermannControlCommand::ConstSharedPtr control_msg)
void ControlPerformanceAnalysisNode::onControlRaw(const Control::ConstSharedPtr control_msg)
{
if (last_control_cmd_) {
const rclcpp::Duration & duration =
Expand Down
10 changes: 5 additions & 5 deletions control/control_validator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,11 @@ Other features are to be implemented.

The `control_validator` takes in the following inputs:

| Name | Type | Description |
| ------------------------------ | ------------------------------------- | ------------------------------------------------------------------------------ |
| `~/input/kinematics` | nav_msgs/Odometry | ego pose and twist |
| `~/input/reference_trajectory` | autoware_auto_control_msgs/Trajectory | reference trajectory which is outputted from planning module to to be followed |
| `~/input/predicted_trajectory` | autoware_auto_control_msgs/Trajectory | predicted trajectory which is outputted from control module |
| Name | Type | Description |
| ------------------------------ | --------------------------------- | ------------------------------------------------------------------------------ |
| `~/input/kinematics` | nav_msgs/Odometry | ego pose and twist |
| `~/input/reference_trajectory` | autoware_planning_msgs/Trajectory | reference trajectory which is outputted from planning module to to be followed |
| `~/input/predicted_trajectory` | autoware_planning_msgs/Trajectory | predicted trajectory which is outputted from control module |

### Outputs

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
#include <nav_msgs/msg/odometry.hpp>

Expand All @@ -31,8 +31,8 @@

namespace control_validator
{
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using control_validator::msg::ControlValidatorStatus;
using diagnostic_updater::DiagnosticStatusWrapper;
using diagnostic_updater::Updater;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

Expand All @@ -32,8 +32,7 @@ class ControlValidatorDebugMarkerPublisher
explicit ControlValidatorDebugMarkerPublisher(rclcpp::Node * node);

void pushPoseMarker(
const autoware_auto_planning_msgs::msg::TrajectoryPoint & p, const std::string & ns,
int id = 0);
const autoware_planning_msgs::msg::TrajectoryPoint & p, const std::string & ns, int id = 0);
void pushPoseMarker(const geometry_msgs::msg::Pose & pose, const std::string & ns, int id = 0);
void pushVirtualWall(const geometry_msgs::msg::Pose & pose);
void pushWarningMsg(const geometry_msgs::msg::Pose & pose, const std::string & msg);
Expand Down
6 changes: 3 additions & 3 deletions control/control_validator/include/control_validator/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,16 +18,16 @@
#include <motion_utils/trajectory/conversion.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>

#include <string>
#include <utility>
#include <vector>

namespace control_validator
{
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
using autoware_planning_msgs::msg::Trajectory;
using autoware_planning_msgs::msg::TrajectoryPoint;
using geometry_msgs::msg::Pose;
using motion_utils::convertToTrajectory;
using motion_utils::convertToTrajectoryPointArray;
Expand Down
2 changes: 1 addition & 1 deletion control/control_validator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<build_depend>rosidl_default_generators</build_depend>

<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>diagnostic_updater</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
Expand Down
2 changes: 1 addition & 1 deletion control/control_validator/src/debug_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ void ControlValidatorDebugMarkerPublisher::clearMarkers()
}

void ControlValidatorDebugMarkerPublisher::pushPoseMarker(
const autoware_auto_planning_msgs::msg::TrajectoryPoint & p, const std::string & ns, int id)
const autoware_planning_msgs::msg::TrajectoryPoint & p, const std::string & ns, int id)
{
pushPoseMarker(p.pose, ns, id);
}
Expand Down
18 changes: 9 additions & 9 deletions control/external_cmd_selector/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@ The current mode is set via service, `remote` is remotely operated, `local` is t

### Output topics

| Name | Type | Description |
| ------------------------------------------------------ | ------------------------------------------------------ | ----------------------------------------------- |
| `/control/external_cmd_selector/current_selector_mode` | TBD | Current selected mode, remote or local. |
| `/diagnostics` | diagnostic_msgs::msg::DiagnosticArray | Check if node is active or not. |
| `/external/selected/external_control_cmd` | TBD | Pass through control command with current mode. |
| `/external/selected/gear_cmd` | autoware_auto_vehicle_msgs::msg::GearCommand | Pass through gear command with current mode. |
| `/external/selected/hazard_lights_cmd` | autoware_auto_vehicle_msgs::msg::HazardLightsCommand | Pass through hazard light with current mode. |
| `/external/selected/heartbeat` | TBD | Pass through heartbeat with current mode. |
| `/external/selected/turn_indicators_cmd` | autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand | Pass through turn indicator with current mode. |
| Name | Type | Description |
| ------------------------------------------------------ | ------------------------------------------------- | ----------------------------------------------- |
| `/control/external_cmd_selector/current_selector_mode` | TBD | Current selected mode, remote or local. |
| `/diagnostics` | diagnostic_msgs::msg::DiagnosticArray | Check if node is active or not. |
| `/external/selected/external_control_cmd` | TBD | Pass through control command with current mode. |
| `/external/selected/gear_cmd` | autoware_vehicle_msgs::msg::GearCommand | Pass through gear command with current mode. |
| `/external/selected/hazard_lights_cmd` | autoware_vehicle_msgs::msg::HazardLightsCommand | Pass through hazard light with current mode. |
| `/external/selected/heartbeat` | TBD | Pass through heartbeat with current mode. |
| `/external/selected/turn_indicators_cmd` | autoware_vehicle_msgs::msg::TurnIndicatorsCommand | Pass through turn indicator with current mode. |
Loading

0 comments on commit 7b50687

Please sign in to comment.