Skip to content

Commit a512718

Browse files
committed
fix: delete onTimer interface
Signed-off-by: veqcc <ryuta.kambe@tier4.jp>
1 parent 0728530 commit a512718

8 files changed

+19
-13
lines changed

system/emergency_handler/README.md

+1-2
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,10 @@ Currently, there are two types of MRM:
1212
- Emergency Stop Operator: publishes `/system/emergency/control_cmd` to make an emergency stop
1313
- Comfortable Stop Operator: publishes `/planning/scenario_planning/max_velocity_candidates` to make a comfortable stop
1414

15-
These operators have `operate()`, `cancel()` and `onTimer` public functions.
15+
These operators have `operate()` and `cancel()` public functions.
1616

1717
- `operate()`: executes the MRM operation
1818
- `cancel()`: cancels the MRM operation
19-
- `onTimer()`: executes each operator's timer callback
2019

2120
### State Transitions
2221

system/emergency_handler/config/emergency_handler.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88

99
# emergency stop operator class
1010
emergency_stop_operator:
11+
update_rate: 30
1112
target_acceleration: -2.5
1213
target_jerk: -1.5
1314
turning_hazard_on: true

system/emergency_handler/schema/emergency_handler.schema.json

+6
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,11 @@
2323
},
2424
"emergency_stop_operator": {
2525
"type": "object",
26+
"update_rate": {
27+
"type": "integer",
28+
"description": "Timer callback period.",
29+
"default": 30
30+
},
2631
"properties": {
2732
"target_acceleration": {
2833
"type": "number",
@@ -46,6 +51,7 @@
4651
}
4752
},
4853
"required": [
54+
"update_rate",
4955
"target_acceleration",
5056
"target_jerk",
5157
"turning_hazard_on",

system/emergency_handler/src/comfortable_stop_operator.cpp

-5
Original file line numberDiff line numberDiff line change
@@ -33,11 +33,6 @@ ComfortableStopOperator::ComfortableStopOperator(rclcpp::Node * node) : node_(no
3333
"~/output/velocity_limit/clear", rclcpp::QoS{1}.transient_local());
3434
}
3535

36-
void ComfortableStopOperator::onTimer()
37-
{
38-
// do nothing
39-
}
40-
4136
bool ComfortableStopOperator::operate()
4237
{
4338
publishVelocityLimit();

system/emergency_handler/src/comfortable_stop_operator.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,6 @@ class ComfortableStopOperator
3636
explicit ComfortableStopOperator(rclcpp::Node * node);
3737
bool operate();
3838
bool cancel();
39-
void onTimer();
4039

4140
private:
4241
// Parameters

system/emergency_handler/src/emergency_handler_core.cpp

-4
Original file line numberDiff line numberDiff line change
@@ -203,10 +203,6 @@ void EmergencyHandler::checkHazardStatusTimeout()
203203

204204
void EmergencyHandler::onTimer()
205205
{
206-
// execute onTimer callback of each operator
207-
emergency_stop_operator_->onTimer();
208-
comfortable_stop_operator_->onTimer();
209-
210206
if (!isDataReady()) {
211207
return;
212208
}

system/emergency_handler/src/emergency_stop_operator.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ namespace emergency_handler::emergency_stop_operator
2020
EmergencyStopOperator::EmergencyStopOperator(rclcpp::Node * node) : node_(node)
2121
{
2222
// Parameter
23+
params_.update_rate = node_->declare_parameter<int>("emergency_stop_operator.update_rate");
2324
params_.target_acceleration =
2425
node_->declare_parameter<double>("emergency_stop_operator.target_acceleration");
2526
params_.target_jerk = node_->declare_parameter<double>("emergency_stop_operator.target_jerk");
@@ -45,6 +46,11 @@ EmergencyStopOperator::EmergencyStopOperator(rclcpp::Node * node) : node_(node)
4546

4647
// Initialize
4748
is_prev_control_cmd_subscribed_ = false;
49+
50+
// Timer
51+
const auto update_period_ns = rclcpp::Rate(params_.update_rate).period();
52+
timer_ = rclcpp::create_timer(
53+
node_, node_->get_clock(), update_period_ns, std::bind(&EmergencyStopOperator::onTimer, this));
4854
}
4955

5056
void EmergencyStopOperator::onControlCommand(AckermannControlCommand::ConstSharedPtr msg)

system/emergency_handler/src/emergency_stop_operator.hpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@ using autoware_auto_vehicle_msgs::msg::HazardLightsCommand;
3131

3232
struct Param
3333
{
34+
int update_rate;
3435
double target_acceleration;
3536
double target_jerk;
3637
bool turning_hazard_on;
@@ -43,7 +44,6 @@ class EmergencyStopOperator
4344
explicit EmergencyStopOperator(rclcpp::Node * node);
4445
bool operate();
4546
bool cancel();
46-
void onTimer();
4747

4848
private:
4949
// Parameters
@@ -66,6 +66,10 @@ class EmergencyStopOperator
6666
rclcpp::Publisher<GearCommand>::SharedPtr pub_gear_cmd_;
6767
void publishGearCmd();
6868

69+
// Timer
70+
rclcpp::TimerBase::SharedPtr timer_;
71+
void onTimer();
72+
6973
// Alrogithm
7074
bool is_prev_control_cmd_subscribed_;
7175
AckermannControlCommand prev_control_cmd_;

0 commit comments

Comments
 (0)