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

refactor(autoware_auto_control_msgs): replace autoware_auto_control_msgs with autoware_control_msgs #61

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 9 additions & 9 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_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 |

- From Pacmod

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
10 changes: 4 additions & 6 deletions pacmod_interface/include/pacmod_interface/pacmod_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#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>
Expand All @@ -31,6 +30,7 @@
#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 <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 @@ -74,8 +74,7 @@ class PacmodInterface : public rclcpp::Node

/* subscribers */
// From Autoware
rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr
control_cmd_sub_;
rclcpp::Subscription<autoware_control_msgs::msg::Control>::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
turn_indicators_cmd_sub_;
Expand Down Expand Up @@ -169,7 +168,7 @@ class PacmodInterface : public rclcpp::Node

/* input values */
ActuationCommandStamped::ConstSharedPtr actuation_cmd_ptr_;
autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr control_cmd_ptr_;
autoware_control_msgs::msg::Control::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_;
Expand All @@ -191,8 +190,7 @@ 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);
Expand Down
2 changes: 1 addition & 1 deletion 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>can_msgs</depend>
<depend>diagnostic_updater</depend>
<depend>geometry_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ PacmodDiagPublisher::PacmodDiagPublisher()
current_acc_sub_ = create_subscription<AccelWithCovarianceStamped>(
"/localization/acceleration", 1,
std::bind(&PacmodDiagPublisher::callbackAccel, this, std::placeholders::_1));
control_cmd_sub_ = create_subscription<AckermannControlCommand>(
control_cmd_sub_ = create_subscription<Control>(
"/control/command/control_cmd", 1,
std::bind(&PacmodDiagPublisher::callbackControlCmd, this, std::placeholders::_1));
odom_sub_ = create_subscription<Odometry>(
Expand Down Expand Up @@ -119,8 +119,7 @@ void PacmodDiagPublisher::callbackAccel(const AccelWithCovarianceStamped::ConstS
addValueToQue(acc_que_, accel->accel.accel.linear.x, accel->header.stamp, accel_store_time_);
}

void PacmodDiagPublisher::callbackControlCmd(
const AckermannControlCommand::ConstSharedPtr control_cmd)
void PacmodDiagPublisher::callbackControlCmd(const Control::ConstSharedPtr control_cmd)
{
addValueToQue(
acc_cmd_que_, control_cmd->longitudinal.acceleration, control_cmd->stamp, accel_store_time_);
Expand Down
4 changes: 2 additions & 2 deletions pacmod_interface/src/pacmod_interface/pacmod_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ PacmodInterface::PacmodInterface()
using std::placeholders::_2;

// From autoware
control_cmd_sub_ = create_subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>(
control_cmd_sub_ = create_subscription<autoware_control_msgs::msg::Control>(
"/control/command/control_cmd", 1, std::bind(&PacmodInterface::callbackControlCmd, this, _1));
gear_cmd_sub_ = create_subscription<autoware_auto_vehicle_msgs::msg::GearCommand>(
"/control/command/gear_cmd", 1, std::bind(&PacmodInterface::callbackGearCmd, this, _1));
Expand Down Expand Up @@ -187,7 +187,7 @@ void PacmodInterface::callbackEmergencyCmd(
}

void PacmodInterface::callbackControlCmd(
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg)
const autoware_control_msgs::msg::Control::ConstSharedPtr msg)
{
control_command_received_time_ = this->now();
control_cmd_ptr_ = msg;
Expand Down