File tree 2 files changed +7
-3
lines changed
control/autoware_shift_decider
include/autoware/shift_decider
2 files changed +7
-3
lines changed Original file line number Diff line number Diff line change 16
16
#define AUTOWARE__SHIFT_DECIDER__AUTOWARE_SHIFT_DECIDER_HPP_
17
17
18
18
#include " autoware/universe_utils/ros/polling_subscriber.hpp"
19
+ #include " shift_decider_parameters.hpp"
19
20
20
21
#include < rclcpp/rclcpp.hpp>
21
22
@@ -58,7 +59,8 @@ class ShiftDecider : public rclcpp::Node
58
59
autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr current_gear_ptr_;
59
60
uint8_t prev_shift_command = autoware_vehicle_msgs::msg::GearCommand::PARK;
60
61
61
- bool park_on_goal_;
62
+ std::shared_ptr<::shift_decider::ParamListener> param_listener_;
63
+ ::shift_decider::Params param_;
62
64
};
63
65
} // namespace autoware::shift_decider
64
66
Original file line number Diff line number Diff line change @@ -31,7 +31,9 @@ ShiftDecider::ShiftDecider(const rclcpp::NodeOptions & node_options)
31
31
rclcpp::QoS durable_qos (queue_size);
32
32
durable_qos.transient_local ();
33
33
34
- park_on_goal_ = declare_parameter<bool >(" park_on_goal" );
34
+ param_listener_ =
35
+ std::make_shared<::shift_decider::ParamListener>(this ->get_node_parameters_interface ());
36
+ param_ = param_listener_->get_params ();
35
37
36
38
pub_shift_cmd_ =
37
39
create_publisher<autoware_vehicle_msgs::msg::GearCommand>(" output/gear_cmd" , durable_qos);
@@ -71,7 +73,7 @@ void ShiftDecider::updateCurrentShiftCmd()
71
73
if (
72
74
(autoware_state_->state == AutowareState::ARRIVED_GOAL ||
73
75
autoware_state_->state == AutowareState::WAITING_FOR_ROUTE) &&
74
- park_on_goal_ ) {
76
+ param_. park_on_goal ) {
75
77
shift_cmd_.command = GearCommand::PARK;
76
78
} else {
77
79
shift_cmd_.command = current_gear_ptr_->report ;
You can’t perform that action at this time.
0 commit comments