@@ -74,14 +74,12 @@ PacmodInterface::PacmodInterface()
74
74
" /control/command/control_cmd" , 1 , std::bind (&PacmodInterface::callbackControlCmd, this , _1));
75
75
gear_cmd_sub_ = create_subscription<autoware_vehicle_msgs::msg::GearCommand>(
76
76
" /control/command/gear_cmd" , 1 , std::bind (&PacmodInterface::callbackGearCmd, this , _1));
77
- turn_indicators_cmd_sub_ =
78
- create_subscription<autoware_vehicle_msgs::msg::TurnIndicatorsCommand>(
79
- " /control/command/turn_indicators_cmd" , rclcpp::QoS{1 },
80
- std::bind (&PacmodInterface::callbackTurnIndicatorsCommand, this , _1));
81
- hazard_lights_cmd_sub_ =
82
- create_subscription<autoware_vehicle_msgs::msg::HazardLightsCommand>(
83
- " /control/command/hazard_lights_cmd" , rclcpp::QoS{1 },
84
- std::bind (&PacmodInterface::callbackHazardLightsCommand, this , _1));
77
+ turn_indicators_cmd_sub_ = create_subscription<autoware_vehicle_msgs::msg::TurnIndicatorsCommand>(
78
+ " /control/command/turn_indicators_cmd" , rclcpp::QoS{1 },
79
+ std::bind (&PacmodInterface::callbackTurnIndicatorsCommand, this , _1));
80
+ hazard_lights_cmd_sub_ = create_subscription<autoware_vehicle_msgs::msg::HazardLightsCommand>(
81
+ " /control/command/hazard_lights_cmd" , rclcpp::QoS{1 },
82
+ std::bind (&PacmodInterface::callbackHazardLightsCommand, this , _1));
85
83
86
84
actuation_cmd_sub_ = create_subscription<ActuationCommandStamped>(
87
85
" /control/command/actuation_cmd" , 1 ,
@@ -137,9 +135,8 @@ PacmodInterface::PacmodInterface()
137
135
" /vehicle/status/steering_status" , rclcpp::QoS{1 });
138
136
gear_status_pub_ = create_publisher<autoware_vehicle_msgs::msg::GearReport>(
139
137
" /vehicle/status/gear_status" , rclcpp::QoS{1 });
140
- turn_indicators_status_pub_ =
141
- create_publisher<autoware_vehicle_msgs::msg::TurnIndicatorsReport>(
142
- " /vehicle/status/turn_indicators_status" , rclcpp::QoS{1 });
138
+ turn_indicators_status_pub_ = create_publisher<autoware_vehicle_msgs::msg::TurnIndicatorsReport>(
139
+ " /vehicle/status/turn_indicators_status" , rclcpp::QoS{1 });
143
140
hazard_lights_status_pub_ = create_publisher<autoware_vehicle_msgs::msg::HazardLightsReport>(
144
141
" /vehicle/status/hazard_lights_status" , rclcpp::QoS{1 });
145
142
actuation_status_pub_ =
@@ -601,8 +598,7 @@ double PacmodInterface::calculateVariableGearRatio(const double vel, const doubl
601
598
1e-5 , vgr_coef_a_ + vgr_coef_b_ * vel * vel - vgr_coef_c_ * std::fabs (steer_wheel));
602
599
}
603
600
604
- uint16_t PacmodInterface::toPacmodShiftCmd (
605
- const autoware_vehicle_msgs::msg::GearCommand & gear_cmd)
601
+ uint16_t PacmodInterface::toPacmodShiftCmd (const autoware_vehicle_msgs::msg::GearCommand & gear_cmd)
606
602
{
607
603
using pacmod3_msgs::msg::SystemCmdInt;
608
604
0 commit comments