Skip to content

Commit 4472d7d

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

File tree

2 files changed

+30
-7
lines changed

2 files changed

+30
-7
lines changed

joy/include/joy/game_controller.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,8 @@ class GameController final : public rclcpp::Node
7575
double scale_{0.0};
7676
double autorepeat_rate_{0.0};
7777
int autorepeat_interval_ms_{0};
78+
std::pair<builtin_interfaces::msg::Time, uint16_t> rumble_intensity_left_stamped_{builtin_interfaces::msg::Time(), 0};
79+
std::pair<builtin_interfaces::msg::Time, uint16_t> rumble_intensity_right_stamped_{builtin_interfaces::msg::Time(), 0};
7880
bool sticky_buttons_{false};
7981
bool publish_soon_{false};
8082
rclcpp::Time publish_soon_time_;

joy/src/game_controller.cpp

Lines changed: 28 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -131,26 +131,47 @@ 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+
rumble_intensity_right_stamped_ = {now, 0};
160+
}
161+
} else if (msg->id == 2) {
162+
rumble_intensity_right_stamped_ = {now, intensity};
163+
if ((now - rumble_intensity_left_stamped_.first) >=
164+
rclcpp::Duration::from_seconds(duration_ms / 1000.0)) {
165+
rumble_intensity_left_stamped_ = {now, 0};
166+
}
167+
} else {
147168
return;
148169
}
149170

150171
if (game_controller_ != nullptr) {
151172
// 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);
173+
SDL_GameControllerRumble(game_controller_, rumble_intensity_left_stamped_.second,
174+
rumble_intensity_right_stamped_.second, duration_ms);
154175
}
155176
}
156177

0 commit comments

Comments
 (0)