Skip to content

Commit 30a9576

Browse files
authored
Merge pull request #1481 from tier4/feat/vehicle_cmd_gate_check_cmd_continuity
feat(autoware_vehicle_cmd_gate): check the timestamp of input topics to avoid using old topics
2 parents e3f5099 + 60b733a commit 30a9576

File tree

3 files changed

+75
-4
lines changed

3 files changed

+75
-4
lines changed

control/autoware_vehicle_cmd_gate/README.md

+7
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,13 @@ This functionality for starting/stopping was embedded in the source code but was
8484

8585
## Assumptions / Known limits
8686

87+
### External Emergency Heartbeat
88+
8789
The parameter `check_external_emergency_heartbeat` (true by default) enables an emergency stop request from external modules.
8890
This feature requires a `~/input/external_emergency_stop_heartbeat` topic for health monitoring of the external module, and the vehicle_cmd_gate module will not start without the topic.
8991
The `check_external_emergency_heartbeat` parameter must be false when the "external emergency stop" function is not used.
92+
93+
### Commands on Mode changes
94+
95+
Output commands' topics: `turn_indicators_cmd`, `hazard_light` and `gear_cmd` are selected based on `gate_mode`.
96+
However, to ensure the continuity of commands, these commands will not change until the topics of new input commands arrive, even if a mode change occurs.

control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp

+57-4
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,10 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
5353
using std::placeholders::_2;
5454
using std::placeholders::_3;
5555

56+
prev_turn_indicator_ = nullptr;
57+
prev_hazard_light_ = nullptr;
58+
prev_gear_ = nullptr;
59+
5660
rclcpp::QoS durable_qos{1};
5761
durable_qos.transient_local();
5862

@@ -352,6 +356,23 @@ void VehicleCmdGate::onEmergencyCtrlCmd(Control::ConstSharedPtr msg)
352356
}
353357
}
354358

359+
// check the continuity of topics
360+
template <typename T>
361+
T VehicleCmdGate::getContinuousTopic(
362+
const std::shared_ptr<T> & prev_topic, const T & current_topic, const std::string & topic_name)
363+
{
364+
if ((rclcpp::Time(current_topic.stamp) - rclcpp::Time(prev_topic->stamp)).seconds() >= 0.0) {
365+
return current_topic;
366+
} else {
367+
if (topic_name != "") {
368+
RCLCPP_INFO(
369+
get_logger(),
370+
"The operation mode is changed, but the %s is not received yet:", topic_name.c_str());
371+
}
372+
return *prev_topic;
373+
}
374+
}
375+
355376
void VehicleCmdGate::onTimer()
356377
{
357378
// Subscriber for auto
@@ -447,6 +468,8 @@ void VehicleCmdGate::onTimer()
447468
if (!is_engaged_) {
448469
turn_indicator.command = TurnIndicatorsCommand::NO_COMMAND;
449470
hazard_light.command = HazardLightsCommand::NO_COMMAND;
471+
turn_indicator.stamp = this->now();
472+
hazard_light.stamp = this->now();
450473
}
451474
} else if (current_gate_mode_.data == GateMode::EXTERNAL) {
452475
turn_indicator = remote_commands_.turn_indicator;
@@ -457,10 +480,40 @@ void VehicleCmdGate::onTimer()
457480
}
458481
}
459482

460-
// Publish topics
461-
turn_indicator_cmd_pub_->publish(turn_indicator);
462-
hazard_light_cmd_pub_->publish(hazard_light);
463-
gear_cmd_pub_->publish(gear);
483+
// Publish Turn Indicators, Hazard Lights and Gear Command
484+
if (prev_turn_indicator_ != nullptr) {
485+
*prev_turn_indicator_ =
486+
getContinuousTopic(prev_turn_indicator_, turn_indicator, "TurnIndicatorsCommand");
487+
turn_indicator_cmd_pub_->publish(*prev_turn_indicator_);
488+
} else {
489+
if (msg_auto_command_turn_indicator || msg_remote_command_turn_indicator) {
490+
prev_turn_indicator_ = std::make_shared<TurnIndicatorsCommand>(turn_indicator);
491+
}
492+
turn_indicator_cmd_pub_->publish(turn_indicator);
493+
}
494+
495+
if (prev_hazard_light_ != nullptr) {
496+
*prev_hazard_light_ =
497+
getContinuousTopic(prev_hazard_light_, hazard_light, "HazardLightsCommand");
498+
hazard_light_cmd_pub_->publish(*prev_hazard_light_);
499+
} else {
500+
if (
501+
msg_auto_command_hazard_light || msg_remote_command_hazard_light ||
502+
msg_emergency_command_hazard_light) {
503+
prev_hazard_light_ = std::make_shared<HazardLightsCommand>(hazard_light);
504+
}
505+
hazard_light_cmd_pub_->publish(hazard_light);
506+
}
507+
508+
if (prev_gear_ != nullptr) {
509+
*prev_gear_ = getContinuousTopic(prev_gear_, gear, "GearCommand");
510+
gear_cmd_pub_->publish(*prev_gear_);
511+
} else {
512+
if (msg_auto_command_gear || msg_remote_command_gear || msg_emergency_command_gear) {
513+
prev_gear_ = std::make_shared<GearCommand>(gear);
514+
}
515+
gear_cmd_pub_->publish(gear);
516+
}
464517
}
465518

466519
void VehicleCmdGate::publishControlCommands(const Commands & commands)

control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp

+11
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,7 @@
5050
#include <visualization_msgs/msg/marker_array.hpp>
5151

5252
#include <memory>
53+
#include <string>
5354
#include <vector>
5455

5556
namespace autoware::vehicle_cmd_gate
@@ -183,6 +184,11 @@ class VehicleCmdGate : public rclcpp::Node
183184
this, "input/emergency/gear_cmd"};
184185
void onEmergencyCtrlCmd(Control::ConstSharedPtr msg);
185186

187+
// Previous Turn Indicators, Hazard Lights and Gear
188+
TurnIndicatorsCommand::SharedPtr prev_turn_indicator_;
189+
HazardLightsCommand::SharedPtr prev_hazard_light_;
190+
GearCommand::SharedPtr prev_gear_;
191+
186192
// Parameter
187193
bool use_emergency_handling_;
188194
bool check_external_emergency_heartbeat_;
@@ -232,6 +238,11 @@ class VehicleCmdGate : public rclcpp::Node
232238

233239
void checkExternalEmergencyStop(diagnostic_updater::DiagnosticStatusWrapper & stat);
234240

241+
template <typename T>
242+
T getContinuousTopic(
243+
const std::shared_ptr<T> & prev_topic, const T & current_topic,
244+
const std::string & topic_name = "");
245+
235246
// Algorithm
236247
Control prev_control_cmd_;
237248
Control createStopControlCmd() const;

0 commit comments

Comments
 (0)