15
15
#ifndef AUTOWARE_SHIFT_DECIDER__AUTOWARE_SHIFT_DECIDER_HPP_
16
16
#define AUTOWARE_SHIFT_DECIDER__AUTOWARE_SHIFT_DECIDER_HPP_
17
17
18
+ #include " tier4_autoware_utils/ros/polling_subscriber.hpp"
19
+
18
20
#include < rclcpp/rclcpp.hpp>
19
21
20
22
#include < autoware_control_msgs/msg/control.hpp>
@@ -41,16 +43,19 @@ class ShiftDecider : public rclcpp::Node
41
43
void initTimer (double period_s);
42
44
43
45
rclcpp::Publisher<autoware_vehicle_msgs::msg::GearCommand>::SharedPtr pub_shift_cmd_;
44
- rclcpp::Subscription<autoware_control_msgs::msg::Control>::SharedPtr sub_control_cmd_;
45
- rclcpp::Subscription<autoware_system_msgs::msg::AutowareState>::SharedPtr sub_autoware_state_;
46
- rclcpp::Subscription<autoware_vehicle_msgs::msg::GearReport>::SharedPtr sub_current_gear_;
46
+ tier4_autoware_utils::InterProcessPollingSubscriber<autoware_control_msgs::msg::Control>
47
+ sub_control_cmd_{this , " input/control_cmd" };
48
+ tier4_autoware_utils::InterProcessPollingSubscriber<autoware_system_msgs::msg::AutowareState>
49
+ sub_autoware_state_{this , " input/state" };
50
+ tier4_autoware_utils::InterProcessPollingSubscriber<autoware_vehicle_msgs::msg::GearReport>
51
+ sub_current_gear_{this , " input/current_gear" };
47
52
48
53
rclcpp::TimerBase::SharedPtr timer_;
49
54
50
- autoware_control_msgs::msg::Control::SharedPtr control_cmd_;
51
- autoware_system_msgs::msg::AutowareState::SharedPtr autoware_state_;
55
+ autoware_control_msgs::msg::Control::ConstSharedPtr control_cmd_;
56
+ autoware_system_msgs::msg::AutowareState::ConstSharedPtr autoware_state_;
52
57
autoware_vehicle_msgs::msg::GearCommand shift_cmd_;
53
- autoware_vehicle_msgs::msg::GearReport::SharedPtr current_gear_ptr_;
58
+ autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr current_gear_ptr_;
54
59
uint8_t prev_shift_command = autoware_vehicle_msgs::msg::GearCommand::PARK;
55
60
56
61
bool park_on_goal_;
0 commit comments