@@ -148,8 +148,9 @@ double calcMapping(const double input, const double sensitivity)
148
148
149
149
namespace joy_controller
150
150
{
151
- void AutowareJoyControllerNode::onJoy (const sensor_msgs::msg::Joy::ConstSharedPtr msg )
151
+ void AutowareJoyControllerNode::onJoy ()
152
152
{
153
+ const auto msg = sub_joy_.takeData ();
153
154
last_joy_received_time_ = msg->header .stamp ;
154
155
if (joy_type_ == " G29" ) {
155
156
joy_ = std::make_shared<const G29JoyConverter>(*msg);
@@ -190,8 +191,13 @@ void AutowareJoyControllerNode::onJoy(const sensor_msgs::msg::Joy::ConstSharedPt
190
191
}
191
192
}
192
193
193
- void AutowareJoyControllerNode::onOdometry (const nav_msgs::msg::Odometry::ConstSharedPtr msg )
194
+ void AutowareJoyControllerNode::onOdometry ()
194
195
{
196
+ if (raw_control_) {
197
+ return ;
198
+ }
199
+
200
+ const auto msg = sub_odom_.takeData ();
195
201
auto twist = std::make_shared<geometry_msgs::msg::TwistStamped>();
196
202
twist->header = msg->header ;
197
203
twist->twist = msg->twist .twist ;
@@ -243,6 +249,9 @@ bool AutowareJoyControllerNode::isDataReady()
243
249
244
250
void AutowareJoyControllerNode::onTimer ()
245
251
{
252
+ onOdometry ();
253
+ onJoy ();
254
+
246
255
if (!isDataReady ()) {
247
256
return ;
248
257
}
@@ -470,23 +479,11 @@ AutowareJoyControllerNode::AutowareJoyControllerNode(const rclcpp::NodeOptions &
470
479
RCLCPP_INFO (get_logger (), " Joy type: %s" , joy_type_.c_str ());
471
480
472
481
// Callback Groups
473
- callback_group_subscribers_ =
474
- this ->create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive);
475
482
callback_group_services_ =
476
483
this ->create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive);
477
- auto subscriber_option = rclcpp::SubscriptionOptions ();
478
- subscriber_option.callback_group = callback_group_subscribers_;
479
484
480
485
// 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_) {
490
487
twist_ = std::make_shared<geometry_msgs::msg::TwistStamped>();
491
488
}
492
489
0 commit comments