Skip to content

Commit 14c75e6

Browse files
authored
feat(joy_controller): use polling subscriber (autowarefoundation#7286)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 3b036b1 commit 14c75e6

File tree

3 files changed

+20
-20
lines changed

3 files changed

+20
-20
lines changed

control/joy_controller/include/joy_controller/joy_controller.hpp

+7-5
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "joy_controller/joy_converter/joy_converter_base.hpp"
1919

2020
#include <rclcpp/rclcpp.hpp>
21+
#include <tier4_autoware_utils/ros/polling_subscriber.hpp>
2122

2223
#include <autoware_control_msgs/msg/control.hpp>
2324
#include <autoware_vehicle_msgs/msg/engage.hpp>
@@ -66,19 +67,20 @@ class AutowareJoyControllerNode : public rclcpp::Node
6667
double backward_accel_ratio_;
6768

6869
// CallbackGroups
69-
rclcpp::CallbackGroup::SharedPtr callback_group_subscribers_;
7070
rclcpp::CallbackGroup::SharedPtr callback_group_services_;
7171

7272
// Subscriber
73-
rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr sub_joy_;
74-
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
73+
tier4_autoware_utils::InterProcessPollingSubscriber<sensor_msgs::msg::Joy> sub_joy_{
74+
this, "input/joy"};
75+
tier4_autoware_utils::InterProcessPollingSubscriber<nav_msgs::msg::Odometry> sub_odom_{
76+
this, "input/odometry"};
7577

7678
rclcpp::Time last_joy_received_time_;
7779
std::shared_ptr<const JoyConverterBase> joy_;
7880
geometry_msgs::msg::TwistStamped::ConstSharedPtr twist_;
7981

80-
void onJoy(const sensor_msgs::msg::Joy::ConstSharedPtr msg);
81-
void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);
82+
void onJoy();
83+
void onOdometry();
8284

8385
// Publisher
8486
rclcpp::Publisher<autoware_control_msgs::msg::Control>::SharedPtr pub_control_command_;

control/joy_controller/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
<depend>sensor_msgs</depend>
2727
<depend>std_srvs</depend>
2828
<depend>tier4_api_utils</depend>
29+
<depend>tier4_autoware_utils</depend>
2930
<depend>tier4_control_msgs</depend>
3031
<depend>tier4_external_api_msgs</depend>
3132

control/joy_controller/src/joy_controller/joy_controller_node.cpp

+12-15
Original file line numberDiff line numberDiff line change
@@ -148,8 +148,9 @@ double calcMapping(const double input, const double sensitivity)
148148

149149
namespace joy_controller
150150
{
151-
void AutowareJoyControllerNode::onJoy(const sensor_msgs::msg::Joy::ConstSharedPtr msg)
151+
void AutowareJoyControllerNode::onJoy()
152152
{
153+
const auto msg = sub_joy_.takeData();
153154
last_joy_received_time_ = msg->header.stamp;
154155
if (joy_type_ == "G29") {
155156
joy_ = std::make_shared<const G29JoyConverter>(*msg);
@@ -190,8 +191,13 @@ void AutowareJoyControllerNode::onJoy(const sensor_msgs::msg::Joy::ConstSharedPt
190191
}
191192
}
192193

193-
void AutowareJoyControllerNode::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg)
194+
void AutowareJoyControllerNode::onOdometry()
194195
{
196+
if (raw_control_) {
197+
return;
198+
}
199+
200+
const auto msg = sub_odom_.takeData();
195201
auto twist = std::make_shared<geometry_msgs::msg::TwistStamped>();
196202
twist->header = msg->header;
197203
twist->twist = msg->twist.twist;
@@ -243,6 +249,9 @@ bool AutowareJoyControllerNode::isDataReady()
243249

244250
void AutowareJoyControllerNode::onTimer()
245251
{
252+
onOdometry();
253+
onJoy();
254+
246255
if (!isDataReady()) {
247256
return;
248257
}
@@ -470,23 +479,11 @@ AutowareJoyControllerNode::AutowareJoyControllerNode(const rclcpp::NodeOptions &
470479
RCLCPP_INFO(get_logger(), "Joy type: %s", joy_type_.c_str());
471480

472481
// Callback Groups
473-
callback_group_subscribers_ =
474-
this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
475482
callback_group_services_ =
476483
this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
477-
auto subscriber_option = rclcpp::SubscriptionOptions();
478-
subscriber_option.callback_group = callback_group_subscribers_;
479484

480485
// Subscriber
481-
sub_joy_ = this->create_subscription<sensor_msgs::msg::Joy>(
482-
"input/joy", 1, std::bind(&AutowareJoyControllerNode::onJoy, this, std::placeholders::_1),
483-
subscriber_option);
484-
if (!raw_control_) {
485-
sub_odom_ = this->create_subscription<nav_msgs::msg::Odometry>(
486-
"input/odometry", 1,
487-
std::bind(&AutowareJoyControllerNode::onOdometry, this, std::placeholders::_1),
488-
subscriber_option);
489-
} else {
486+
if (raw_control_) {
490487
twist_ = std::make_shared<geometry_msgs::msg::TwistStamped>();
491488
}
492489

0 commit comments

Comments
 (0)