Skip to content

Commit b9a763e

Browse files
author
marcin.mirski
committed
Add left and right game controller rumble channels
1 parent 881f3a5 commit b9a763e

File tree

2 files changed

+36
-7
lines changed

2 files changed

+36
-7
lines changed

joy/include/joy/game_controller.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737
#include <memory>
3838
#include <string>
3939
#include <thread>
40+
#include <utility>
4041

4142
#include <rclcpp/rclcpp.hpp>
4243
#include <sensor_msgs/msg/joy.hpp>
@@ -75,6 +76,10 @@ class GameController final : public rclcpp::Node
7576
double scale_{0.0};
7677
double autorepeat_rate_{0.0};
7778
int autorepeat_interval_ms_{0};
79+
std::pair<builtin_interfaces::msg::Time, uint16_t> rumble_intensity_left_stamped_{
80+
builtin_interfaces::msg::Time(), 0};
81+
std::pair<builtin_interfaces::msg::Time, uint16_t> rumble_intensity_right_stamped_{
82+
builtin_interfaces::msg::Time(), 0};
7883
bool sticky_buttons_{false};
7984
bool publish_soon_{false};
8085
rclcpp::Time publish_soon_time_;

joy/src/game_controller.cpp

Lines changed: 31 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -131,26 +131,50 @@ GameController::~GameController()
131131

132132
void GameController::feedbackCb(const std::shared_ptr<sensor_msgs::msg::JoyFeedback> msg)
133133
{
134+
uint32_t duration_ms = 1000;
135+
134136
if (msg->type != sensor_msgs::msg::JoyFeedback::TYPE_RUMBLE) {
135137
// We only support rumble
136138
return;
137139
}
138140

139-
if (msg->id != 0) {
140-
// There can be only one (rumble)
141-
// TODO(Rod Taylor): Support high and low frequency rumble channels.
141+
if (msg->intensity < 0.0 || msg->intensity > 1.0) {
142+
// We only accept intensities between 0 and 1.
142143
return;
143144
}
144145

145-
if (msg->intensity < 0.0 || msg->intensity > 1.0) {
146-
// We only accept intensities between 0 and 1.
146+
uint16_t intensity = static_cast<uint16_t>(msg->intensity * 0xFFFF);
147+
rclcpp::Time now = this->now();
148+
149+
// 0: Both left motor (low frequency) and right motor (high frequency) rumble
150+
// 1: Left rumble
151+
// 2: Right rumble
152+
if (msg->id == 0) {
153+
rumble_intensity_left_stamped_ = {now, intensity};
154+
rumble_intensity_right_stamped_ = {now, intensity};
155+
} else if (msg->id == 1) {
156+
rumble_intensity_left_stamped_ = {now, intensity};
157+
if ((now - rumble_intensity_right_stamped_.first) >=
158+
rclcpp::Duration::from_seconds(duration_ms / 1000.0))
159+
{
160+
rumble_intensity_right_stamped_ = {now, 0};
161+
}
162+
} else if (msg->id == 2) {
163+
rumble_intensity_right_stamped_ = {now, intensity};
164+
if ((now - rumble_intensity_left_stamped_.first) >=
165+
rclcpp::Duration::from_seconds(duration_ms / 1000.0))
166+
{
167+
rumble_intensity_left_stamped_ = {now, 0};
168+
}
169+
} else {
147170
return;
148171
}
149172

150173
if (game_controller_ != nullptr) {
151174
// We purposely ignore the return value; if it fails, what can we do?
152-
uint16_t intensity = static_cast<uint16_t>(msg->intensity * 0xFFFF);
153-
SDL_GameControllerRumble(game_controller_, intensity, intensity, 1000);
175+
SDL_GameControllerRumble(
176+
game_controller_, rumble_intensity_left_stamped_.second,
177+
rumble_intensity_right_stamped_.second, duration_ms);
154178
}
155179
}
156180

0 commit comments

Comments
 (0)