Skip to content

Commit 468f6fc

Browse files
committedJun 11, 2024
RT1-6697 use polling subscriber
Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 687ead9 commit 468f6fc

File tree

3 files changed

+15
-29
lines changed

3 files changed

+15
-29
lines changed
 

‎control/autoware_shift_decider/include/autoware_shift_decider/autoware_shift_decider.hpp

+11-6
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef AUTOWARE_SHIFT_DECIDER__AUTOWARE_SHIFT_DECIDER_HPP_
1616
#define AUTOWARE_SHIFT_DECIDER__AUTOWARE_SHIFT_DECIDER_HPP_
1717

18+
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
19+
1820
#include <rclcpp/rclcpp.hpp>
1921

2022
#include <autoware_control_msgs/msg/control.hpp>
@@ -41,16 +43,19 @@ class ShiftDecider : public rclcpp::Node
4143
void initTimer(double period_s);
4244

4345
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"};
4752

4853
rclcpp::TimerBase::SharedPtr timer_;
4954

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_;
5257
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_;
5459
uint8_t prev_shift_command = autoware_vehicle_msgs::msg::GearCommand::PARK;
5560

5661
bool park_on_goal_;

‎control/autoware_shift_decider/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
<depend>autoware_vehicle_msgs</depend>
1919
<depend>rclcpp</depend>
2020
<depend>rclcpp_components</depend>
21+
<depend>tier4_autoware_utils</depend>
2122

2223
<test_depend>ament_cmake_cppcheck</test_depend>
2324
<test_depend>ament_cmake_cpplint</test_depend>

‎control/autoware_shift_decider/src/autoware_shift_decider.cpp

+3-23
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,6 @@
1818

1919
#include <cstddef>
2020
#include <functional>
21-
#include <memory>
22-
#include <utility>
2321

2422
namespace autoware::shift_decider
2523
{
@@ -37,33 +35,15 @@ ShiftDecider::ShiftDecider(const rclcpp::NodeOptions & node_options)
3735

3836
pub_shift_cmd_ =
3937
create_publisher<autoware_vehicle_msgs::msg::GearCommand>("output/gear_cmd", durable_qos);
40-
sub_control_cmd_ = create_subscription<autoware_control_msgs::msg::Control>(
41-
"input/control_cmd", queue_size, std::bind(&ShiftDecider::onControlCmd, this, _1));
42-
sub_autoware_state_ = create_subscription<autoware_system_msgs::msg::AutowareState>(
43-
"input/state", queue_size, std::bind(&ShiftDecider::onAutowareState, this, _1));
44-
sub_current_gear_ = create_subscription<autoware_vehicle_msgs::msg::GearReport>(
45-
"input/current_gear", queue_size, std::bind(&ShiftDecider::onCurrentGear, this, _1));
4638

4739
initTimer(0.1);
4840
}
4941

50-
void ShiftDecider::onControlCmd(autoware_control_msgs::msg::Control::SharedPtr msg)
51-
{
52-
control_cmd_ = msg;
53-
}
54-
55-
void ShiftDecider::onAutowareState(autoware_system_msgs::msg::AutowareState::SharedPtr msg)
56-
{
57-
autoware_state_ = msg;
58-
}
59-
60-
void ShiftDecider::onCurrentGear(autoware_vehicle_msgs::msg::GearReport::SharedPtr msg)
61-
{
62-
current_gear_ptr_ = msg;
63-
}
64-
6542
void ShiftDecider::onTimer()
6643
{
44+
control_cmd_ = sub_control_cmd_.takeData();
45+
autoware_state_ = sub_autoware_state_.takeData();
46+
current_gear_ptr_ = sub_current_gear_.takeData();
6747
if (!autoware_state_ || !control_cmd_ || !current_gear_ptr_) {
6848
return;
6949
}

0 commit comments

Comments
 (0)