Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat!: replacing autoware_auto_msgs with autoware_msgs #78

Merged
merged 9 commits into from
Jun 4, 2024
4 changes: 0 additions & 4 deletions build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,6 @@ repositories:
type: git
url: https://github.com/autowarefoundation/autoware_common.git
version: main
core/external/autoware_auto_msgs:
type: git
url: https://github.com/tier4/autoware_auto_msgs.git # TODO(Tier IV): Move to autowarefoundation/autoware_msgs
version: tier4/main
universe/autoware:
type: git
url: https://github.com/autowarefoundation/autoware.universe
Expand Down
36 changes: 18 additions & 18 deletions pacmod_interface/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,15 +8,15 @@

- From Autoware

| Name | Type | Description |
| -------------------------------------- | -------------------------------------------------------- | ----------------------------------------------------- |
| `/control/command/control_cmd` | autoware_auto_control_msgs::msg::AckermannControlCommand | lateral and longitudinal control command |
| `/control/command/gear_cmd` | autoware_auto_vehicle_msgs::msg::GearCommand | gear command |
| `/control/command/turn_indicators_cmd` | autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand | turn indicators command |
| `/control/command/hazard_lights_cmd` | autoware_auto_vehicle_msgs::msg::HazardLightsCommand | hazard lights command |
| `/vehicle/engage` | autoware_auto_vehicle_msgs::msg::Engage | engage command |
| `/vehicle/command/actuation_cmd` | tier4_vehicle_msgs::msg::ActuationCommandStamped | actuation (accel/brake pedal, steering wheel) command |
| `/control/command/emergency_cmd` | tier4_vehicle_msgs::msg::VehicleEmergencyStamped | emergency command |
| Name | Type | Description |
| -------------------------------------- | ------------------------------------------------- | ----------------------------------------------------- |
| `/control/command/control_cmd` | autoware_control_msgs::msg::Control | lateral and longitudinal control command |
| `/control/command/gear_cmd` | autoware_vehicle_msgs::msg::GearCommand | gear command |
| `/control/command/turn_indicators_cmd` | autoware_vehicle_msgs::msg::TurnIndicatorsCommand | turn indicators command |
| `/control/command/hazard_lights_cmd` | autoware_vehicle_msgs::msg::HazardLightsCommand | hazard lights command |
| `/vehicle/engage` | autoware_vehicle_msgs::msg::Engage | engage command |
| `/vehicle/command/actuation_cmd` | tier4_vehicle_msgs::msg::ActuationCommandStamped | actuation (accel/brake pedal, steering wheel) command |
| `/control/command/emergency_cmd` | tier4_vehicle_msgs::msg::VehicleEmergencyStamped | emergency command |

- From Pacmod

Expand Down Expand Up @@ -45,15 +45,15 @@

- To Autoware

| Name | Type | Description |
| ---------------------------------------- | ------------------------------------------------------- | ---------------------------------------------------- |
| `/vehicle/status/control_mode` | autoware_auto_vehicle_msgs::msg::ControlModeReport | control mode |
| `/vehicle/status/velocity_status` | autoware_auto_vehicle_msgs::msg::VelocityReport | velocity |
| `/vehicle/status/steering_status` | autoware_auto_vehicle_msgs::msg::SteeringReport | steering wheel angle |
| `/vehicle/status/gear_status` | autoware_auto_vehicle_msgs::msg::GearReport | gear status |
| `/vehicle/status/turn_indicators_status` | autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport | turn indicators status |
| `/vehicle/status/hazard_lights_status` | autoware_auto_vehicle_msgs::msg::HazardLightsReport | hazard lights status |
| `/vehicle/status/actuation_status` | autoware_auto_vehicle_msgs::msg::ActuationStatusStamped | actuation (accel/brake pedal, steering wheel) status |
| Name | Type | Description |
| ---------------------------------------- | -------------------------------------------------- | ---------------------------------------------------- |
| `/vehicle/status/control_mode` | autoware_vehicle_msgs::msg::ControlModeReport | control mode |
| `/vehicle/status/velocity_status` | autoware_vehicle_msgs::msg::VelocityReport | velocity |
| `/vehicle/status/steering_status` | autoware_vehicle_msgs::msg::SteeringReport | steering wheel angle |
| `/vehicle/status/gear_status` | autoware_vehicle_msgs::msg::GearReport | gear status |
| `/vehicle/status/turn_indicators_status` | autoware_vehicle_msgs::msg::TurnIndicatorsReport | turn indicators status |
| `/vehicle/status/hazard_lights_status` | autoware_vehicle_msgs::msg::HazardLightsReport | hazard lights status |
| `/vehicle/status/actuation_status` | autoware_vehicle_msgs::msg::ActuationStatusStamped | actuation (accel/brake pedal, steering wheel) status |

## ROS Parameters

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

#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_control_msgs/msg/control.hpp>
#include <can_msgs/msg/frame.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
Expand All @@ -42,7 +42,7 @@
#include <utility>
#include <vector>

using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_control_msgs::msg::Control;
using geometry_msgs::msg::AccelWithCovarianceStamped;
using nav_msgs::msg::Odometry;

Expand Down Expand Up @@ -76,7 +76,7 @@ class PacmodDiagPublisher : public rclcpp::Node

// Acceleration-related Topics
rclcpp::Subscription<AccelWithCovarianceStamped>::SharedPtr current_acc_sub_;
rclcpp::Subscription<AckermannControlCommand>::SharedPtr control_cmd_sub_;
rclcpp::Subscription<Control>::SharedPtr control_cmd_sub_;
rclcpp::Subscription<Odometry>::SharedPtr odom_sub_;

/* ros parameters */
Expand Down Expand Up @@ -122,7 +122,7 @@ class PacmodDiagPublisher : public rclcpp::Node

void callbackAccel(const AccelWithCovarianceStamped::ConstSharedPtr accel);
void callbackOdometry(const Odometry::SharedPtr odom);
void callbackControlCmd(const AckermannControlCommand::ConstSharedPtr control_cmd);
void callbackControlCmd(const Control::ConstSharedPtr control_cmd);

/* functions */
void checkPacmodMsgs(diagnostic_updater::DiagnosticStatusWrapper & stat);
Expand Down
78 changes: 37 additions & 41 deletions pacmod_interface/include/pacmod_interface/pacmod_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,18 +19,18 @@
#include <tier4_api_utils/tier4_api_utils.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/engage.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.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_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/turn_indicators_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
#include <autoware_auto_vehicle_msgs/srv/control_mode_command.hpp>
#include <autoware_control_msgs/msg/control.hpp>
#include <autoware_vehicle_msgs/msg/control_mode_report.hpp>
#include <autoware_vehicle_msgs/msg/engage.hpp>
#include <autoware_vehicle_msgs/msg/gear_command.hpp>
#include <autoware_vehicle_msgs/msg/gear_report.hpp>
#include <autoware_vehicle_msgs/msg/hazard_lights_command.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_command.hpp>
#include <autoware_vehicle_msgs/msg/turn_indicators_report.hpp>
#include <autoware_vehicle_msgs/msg/velocity_report.hpp>
#include <autoware_vehicle_msgs/srv/control_mode_command.hpp>
#include <pacmod3_msgs/msg/global_rpt.hpp>
#include <pacmod3_msgs/msg/steering_cmd.hpp>
#include <pacmod3_msgs/msg/system_cmd_float.hpp>
Expand Down Expand Up @@ -58,18 +58,17 @@ class PacmodInterface : public rclcpp::Node
using ActuationCommandStamped = tier4_vehicle_msgs::msg::ActuationCommandStamped;
using ActuationStatusStamped = tier4_vehicle_msgs::msg::ActuationStatusStamped;
using SteeringWheelStatusStamped = tier4_vehicle_msgs::msg::SteeringWheelStatusStamped;
using ControlModeCommand = autoware_auto_vehicle_msgs::srv::ControlModeCommand;
using ControlModeCommand = autoware_vehicle_msgs::srv::ControlModeCommand;
PacmodInterface();

private:
/* subscribers */
// From Autoware
rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr
control_cmd_sub_;
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::GearCommand>::SharedPtr gear_cmd_sub_;
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand>::SharedPtr
rclcpp::Subscription<autoware_control_msgs::msg::Control>::SharedPtr control_cmd_sub_;
rclcpp::Subscription<autoware_vehicle_msgs::msg::GearCommand>::SharedPtr gear_cmd_sub_;
rclcpp::Subscription<autoware_vehicle_msgs::msg::TurnIndicatorsCommand>::SharedPtr
turn_indicators_cmd_sub_;
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::HazardLightsCommand>::SharedPtr
rclcpp::Subscription<autoware_vehicle_msgs::msg::HazardLightsCommand>::SharedPtr
hazard_lights_cmd_sub_;
rclcpp::Subscription<ActuationCommandStamped>::SharedPtr actuation_cmd_sub_;
rclcpp::Subscription<tier4_vehicle_msgs::msg::VehicleEmergencyStamped>::SharedPtr emergency_sub_;
Expand Down Expand Up @@ -97,15 +96,13 @@ class PacmodInterface : public rclcpp::Node
raw_steer_cmd_pub_; // only for debug

// To Autoware
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::ControlModeReport>::SharedPtr
control_mode_pub_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::VelocityReport>::SharedPtr vehicle_twist_pub_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::SteeringReport>::SharedPtr
steering_status_pub_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::GearReport>::SharedPtr gear_status_pub_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport>::SharedPtr
rclcpp::Publisher<autoware_vehicle_msgs::msg::ControlModeReport>::SharedPtr control_mode_pub_;
rclcpp::Publisher<autoware_vehicle_msgs::msg::VelocityReport>::SharedPtr vehicle_twist_pub_;
rclcpp::Publisher<autoware_vehicle_msgs::msg::SteeringReport>::SharedPtr steering_status_pub_;
rclcpp::Publisher<autoware_vehicle_msgs::msg::GearReport>::SharedPtr gear_status_pub_;
rclcpp::Publisher<autoware_vehicle_msgs::msg::TurnIndicatorsReport>::SharedPtr
turn_indicators_status_pub_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::HazardLightsReport>::SharedPtr
rclcpp::Publisher<autoware_vehicle_msgs::msg::HazardLightsReport>::SharedPtr
hazard_lights_status_pub_;
rclcpp::Publisher<ActuationStatusStamped>::SharedPtr actuation_status_pub_;
rclcpp::Publisher<SteeringWheelStatusStamped>::SharedPtr steering_wheel_status_pub_;
Expand Down Expand Up @@ -164,10 +161,10 @@ class PacmodInterface : public rclcpp::Node

/* input values */
ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr_;
autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr control_cmd_ptr_;
autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr turn_indicators_cmd_ptr_;
autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr hazard_lights_cmd_ptr_;
autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr gear_cmd_ptr_;
autoware_control_msgs::msg::Control::ConstSharedPtr control_cmd_ptr_;
autoware_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr turn_indicators_cmd_ptr_;
autoware_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr hazard_lights_cmd_ptr_;
autoware_vehicle_msgs::msg::GearCommand::ConstSharedPtr gear_cmd_ptr_;

pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr steer_wheel_rpt_ptr_; // [rad]
pacmod3_msgs::msg::WheelSpeedRpt::ConstSharedPtr wheel_speed_rpt_ptr_; // [m/s]
Expand All @@ -188,18 +185,17 @@ class PacmodInterface : public rclcpp::Node

/* callbacks */
void callbackActuationCmd(const ActuationCommandStamped::ConstSharedPtr msg);
void callbackControlCmd(
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg);
void callbackControlCmd(const autoware_control_msgs::msg::Control::ConstSharedPtr msg);

void callbackEmergencyCmd(
const tier4_vehicle_msgs::msg::VehicleEmergencyStamped::ConstSharedPtr msg);

void callbackGearCmd(const autoware_auto_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg);
void callbackGearCmd(const autoware_vehicle_msgs::msg::GearCommand::ConstSharedPtr msg);
void callbackTurnIndicatorsCommand(
const autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr msg);
const autoware_vehicle_msgs::msg::TurnIndicatorsCommand::ConstSharedPtr msg);
void callbackHazardLightsCommand(
const autoware_auto_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg);
void callbackEngage(const autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg);
const autoware_vehicle_msgs::msg::HazardLightsCommand::ConstSharedPtr msg);
void callbackEngage(const autoware_vehicle_msgs::msg::Engage::ConstSharedPtr msg);
void callbackRearDoor(const pacmod3_msgs::msg::SystemRptInt::ConstSharedPtr rear_door_rpt);
void callbackSteerWheelRpt(
const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr steer_wheel_rpt);
Expand All @@ -219,14 +215,14 @@ class PacmodInterface : public rclcpp::Node
const pacmod3_msgs::msg::SystemRptInt & shift_rpt);
double calculateVariableGearRatio(const double vel, const double steer_wheel);
double calcSteerWheelRateCmd(const double gear_ratio);
uint16_t toPacmodShiftCmd(const autoware_auto_vehicle_msgs::msg::GearCommand & gear_cmd);
uint16_t toPacmodShiftCmd(const autoware_vehicle_msgs::msg::GearCommand & gear_cmd);
uint16_t getGearCmdForPreventChatter(uint16_t gear_command);
uint16_t toPacmodTurnCmd(
const autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand & turn,
const autoware_auto_vehicle_msgs::msg::HazardLightsCommand & hazard);
const autoware_vehicle_msgs::msg::TurnIndicatorsCommand & turn,
const autoware_vehicle_msgs::msg::HazardLightsCommand & hazard);
uint16_t toPacmodTurnCmdWithHazardRecover(
const autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand & turn,
const autoware_auto_vehicle_msgs::msg::HazardLightsCommand & hazard);
const autoware_vehicle_msgs::msg::TurnIndicatorsCommand & turn,
const autoware_vehicle_msgs::msg::HazardLightsCommand & hazard);

std::optional<int32_t> toAutowareShiftReport(const pacmod3_msgs::msg::SystemRptInt & shift);
int32_t toAutowareTurnIndicatorsReport(const pacmod3_msgs::msg::SystemRptInt & turn);
Expand Down
29 changes: 13 additions & 16 deletions pacmod_interface/include/pacmod_steer_test/pacmod_steer_test.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,12 @@
#include <rclcpp/rclcpp.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/engage.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_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/vehicle_control_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
#include <autoware_vehicle_msgs/msg/control_mode_report.hpp>
#include <autoware_vehicle_msgs/msg/engage.hpp>
#include <autoware_vehicle_msgs/msg/gear_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 <pacmod3_msgs/msg/global_rpt.hpp>
#include <pacmod3_msgs/msg/steering_cmd.hpp>
#include <pacmod3_msgs/msg/system_cmd_float.hpp>
Expand Down Expand Up @@ -57,7 +56,7 @@ class PacmodSteerTest : public rclcpp::Node

/* subscribers */
// From Autoware
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::Engage>::SharedPtr engage_cmd_sub_;
rclcpp::Subscription<autoware_vehicle_msgs::msg::Engage>::SharedPtr engage_cmd_sub_;

// From Pacmod
std::unique_ptr<message_filters::Subscriber<pacmod3_msgs::msg::SystemRptFloat>>
Expand All @@ -80,13 +79,11 @@ class PacmodSteerTest : public rclcpp::Node
rclcpp::Publisher<pacmod3_msgs::msg::SystemCmdInt>::SharedPtr turn_cmd_pub_;

// output vehicle info
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::ControlModeReport>::SharedPtr
control_mode_pub_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::VelocityReport>::SharedPtr vehicle_twist_pub_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::SteeringReport>::SharedPtr
steering_status_pub_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::GearReport>::SharedPtr shift_status_pub_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport>::SharedPtr
rclcpp::Publisher<autoware_vehicle_msgs::msg::ControlModeReport>::SharedPtr control_mode_pub_;
rclcpp::Publisher<autoware_vehicle_msgs::msg::VelocityReport>::SharedPtr vehicle_twist_pub_;
rclcpp::Publisher<autoware_vehicle_msgs::msg::SteeringReport>::SharedPtr steering_status_pub_;
rclcpp::Publisher<autoware_vehicle_msgs::msg::GearReport>::SharedPtr shift_status_pub_;
rclcpp::Publisher<autoware_vehicle_msgs::msg::TurnIndicatorsReport>::SharedPtr
turn_signal_status_pub_;

vehicle_info_util::VehicleInfo vehicle_info_;
Expand Down Expand Up @@ -118,7 +115,7 @@ class PacmodSteerTest : public rclcpp::Node
bool engage_cmd_ = false;

/* callbacks */
void callbackEngage(const autoware_auto_vehicle_msgs::msg::Engage::ConstSharedPtr msg);
void callbackEngage(const autoware_vehicle_msgs::msg::Engage::ConstSharedPtr msg);
void callbackPacmodRpt(
const pacmod3_msgs::msg::SystemRptFloat::ConstSharedPtr steer_wheel_rpt,
const pacmod3_msgs::msg::WheelSpeedRpt::ConstSharedPtr wheel_speed_rpt,
Expand Down
4 changes: 2 additions & 2 deletions pacmod_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>autoware_auto_control_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>can_msgs</depend>
<depend>diagnostic_updater</depend>
<depend>geometry_msgs</depend>
Expand Down
Loading
Loading