Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 35687b3

Browse files
committedAug 16, 2024·
feat(pacmod_interface): Additional option to receive wheel angle directly
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 6efb5d1 commit 35687b3

File tree

2 files changed

+27
-7
lines changed

2 files changed

+27
-7
lines changed
 

‎pacmod_interface/include/pacmod_interface/pacmod_interface.hpp

+7
Original file line numberDiff line numberDiff line change
@@ -159,6 +159,13 @@ class PacmodInterface : public rclcpp::Node
159159

160160
double margin_time_for_gear_change_; // [s]
161161

162+
// steer command conversion
163+
// if false, it is expected to be converted from and published actuation_status in
164+
// raw_vehicle_cmd_converter
165+
bool enable_pub_steer_ = true; // flag to publish steer_cmd
166+
// if false, it is expected to be converted from and published actuation_status in
167+
bool convert_steer_command_ = true; // flag to convert steer command
168+
162169
autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
163170

164171
// Service

‎pacmod_interface/src/pacmod_interface/pacmod_interface.cpp

+20-7
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,10 @@ PacmodInterface::PacmodInterface()
6262
/* parameter for preventing gear chattering */
6363
margin_time_for_gear_change_ = declare_parameter("margin_time_for_gear_change", 2.0);
6464

65+
/* parameter for steering conversion */
66+
enable_pub_steer_ = declare_parameter("enable_pub_steer", true);
67+
convert_steer_command_ = declare_parameter("convert_steer_command", true);
68+
6569
/* initialize */
6670
prev_steer_cmd_.header.stamp = this->now();
6771
prev_steer_cmd_.command = 0.0;
@@ -321,7 +325,7 @@ void PacmodInterface::callbackPacmodRpt(
321325
}
322326

323327
/* publish current status */
324-
{
328+
if (enable_pub_steer_) {
325329
autoware_vehicle_msgs::msg::SteeringReport steer_msg;
326330
steer_msg.stamp = header.stamp;
327331
steer_msg.steering_tire_angle = current_steer;
@@ -330,11 +334,14 @@ void PacmodInterface::callbackPacmodRpt(
330334

331335
/* publish control status */
332336
{
337+
// NOTE:
338+
// actuation status must be the same data format as the input data.
339+
// raw_vehicle_cmd_converter converts from steering_wheel_angle to steering_tire_angle.
333340
ActuationStatusStamped actuation_status;
334341
actuation_status.header = header;
335342
actuation_status.status.accel_status = accel_rpt_ptr_->output;
336343
actuation_status.status.brake_status = brake_rpt_ptr_->output;
337-
actuation_status.status.steer_status = current_steer;
344+
actuation_status.status.steer_status = current_steer_wheel;
338345
actuation_status_pub_->publish(actuation_status);
339346
}
340347

@@ -396,11 +403,17 @@ void PacmodInterface::publishCommands()
396403
const double current_steer_wheel = steer_wheel_rpt_ptr_->output;
397404

398405
/* calculate desired steering wheel */
399-
double adaptive_gear_ratio = calculateVariableGearRatio(current_velocity, current_steer_wheel);
400-
double desired_steer_wheel =
401-
(control_cmd_ptr_->lateral.steering_tire_angle - steering_offset_) * adaptive_gear_ratio;
402-
desired_steer_wheel =
403-
std::min(std::max(desired_steer_wheel, -max_steering_wheel_), max_steering_wheel_);
406+
const double adaptive_gear_ratio =
407+
calculateVariableGearRatio(current_velocity, current_steer_wheel);
408+
const double desired_steer_wheel = std::invoke([&]() -> double {
409+
double desired_steer_wheel{0.0};
410+
if (convert_steer_command_) {
411+
(control_cmd_ptr_->lateral.steering_tire_angle - steering_offset_) * adaptive_gear_ratio;
412+
} else {
413+
desired_steer_wheel = actuation_cmd_ptr_->actuation.steer_cmd;
414+
}
415+
return std::min(std::max(desired_steer_wheel, -max_steering_wheel_), max_steering_wheel_);
416+
});
404417

405418
/* check clear flag */
406419
bool clear_override = false;

0 commit comments

Comments
 (0)
Please sign in to comment.