@@ -131,26 +131,50 @@ GameController::~GameController()
131
131
132
132
void GameController::feedbackCb (const std::shared_ptr<sensor_msgs::msg::JoyFeedback> msg)
133
133
{
134
+ uint32_t duration_ms = 1000 ;
135
+
134
136
if (msg->type != sensor_msgs::msg::JoyFeedback::TYPE_RUMBLE) {
135
137
// We only support rumble
136
138
return ;
137
139
}
138
140
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.
142
143
return ;
143
144
}
144
145
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 {
147
170
return ;
148
171
}
149
172
150
173
if (game_controller_ != nullptr ) {
151
174
// 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);
154
178
}
155
179
}
156
180
0 commit comments