@@ -66,12 +66,10 @@ GameController::GameController(const rclcpp::NodeOptions & options)
66
66
unscaled_deadzone_ = 32767.0 * scaled_deadzone_;
67
67
// According to the SDL documentation, this always returns a value between
68
68
// -32768 and 32767. However, we want to report a value between -1.0 and 1.0,
69
- // hence the "scale" dividing by 32767. Also note that SDL returns the axes
70
- // with "forward" and "left" as negative. This is opposite to the ROS
71
- // conventionof "forward" and "left" as positive, so we invert the axes here
72
- // as well. Finally, we take into account the amount of deadzone so we truly
73
- // do get value between -1.0 and 1.0 (and not -deadzone to +deadzone).
74
- scale_ = static_cast <float >(-1.0 / (1.0 - scaled_deadzone_) / 32767.0 );
69
+ // hence the "scale" dividing by 32767. Finally, we take into account the
70
+ // amount of deadzone so we truly do get value between -1.0 and 1.0 (and
71
+ // not -deadzone to +deadzone).
72
+ scale_ = static_cast <float >(1.0 / (1.0 - scaled_deadzone_) / 32767.0 );
75
73
76
74
autorepeat_rate_ = this ->declare_parameter (" autorepeat_rate" , 20.0 );
77
75
if (autorepeat_rate_ < 0.0 ) {
@@ -154,7 +152,7 @@ void GameController::feedbackCb(const std::shared_ptr<sensor_msgs::msg::JoyFeedb
154
152
}
155
153
}
156
154
157
- float GameController::convertRawAxisValueToROS (int16_t val)
155
+ float GameController::convertRawAxisValueToROS (int16_t val, const uint8_t & axis )
158
156
{
159
157
// SDL reports axis values between -32768 and 32767. To make sure
160
158
// we report out scaled value between -1.0 and 1.0, we add one to
@@ -177,7 +175,17 @@ float GameController::convertRawAxisValueToROS(int16_t val)
177
175
double_val = 0.0 ;
178
176
}
179
177
180
- return static_cast <float >(double_val * scale_);
178
+ double ret = double_val * scale_;
179
+ switch (axis) {
180
+ case SDL_CONTROLLER_AXIS_LEFTX:
181
+ case SDL_CONTROLLER_AXIS_LEFTY:
182
+ case SDL_CONTROLLER_AXIS_RIGHTX:
183
+ case SDL_CONTROLLER_AXIS_RIGHTY:
184
+ ret *= -1 ;
185
+ break ;
186
+ }
187
+
188
+ return static_cast <float >(ret);
181
189
}
182
190
183
191
bool GameController::handleControllerAxis (const SDL_ControllerAxisEvent & e)
@@ -194,7 +202,7 @@ bool GameController::handleControllerAxis(const SDL_ControllerAxisEvent & e)
194
202
}
195
203
196
204
float last_axis_value = joy_msg_.axes .at (e.axis );
197
- joy_msg_.axes .at (e.axis ) = convertRawAxisValueToROS (e.value );
205
+ joy_msg_.axes .at (e.axis ) = convertRawAxisValueToROS (e.value , static_cast < uint8_t >(e. axis ) );
198
206
if (last_axis_value != joy_msg_.axes .at (e.axis )) {
199
207
if (coalesce_interval_ms_ > 0 && !publish_soon_) {
200
208
publish_soon_ = true ;
@@ -309,10 +317,10 @@ void GameController::handleControllerDeviceAdded(const SDL_ControllerDeviceEvent
309
317
}
310
318
311
319
// Get the initial state for each of the axes
312
- for (int i = 0 ; i < SDL_CONTROLLER_AXIS_MAX; ++i) {
320
+ for (uint8_t i = 0 ; i < SDL_CONTROLLER_AXIS_MAX; ++i) {
313
321
int16_t state =
314
322
SDL_GameControllerGetAxis (game_controller_, static_cast <SDL_GameControllerAxis>(i));
315
- joy_msg_.axes .at (i) = convertRawAxisValueToROS (state);
323
+ joy_msg_.axes .at (i) = convertRawAxisValueToROS (state, i );
316
324
}
317
325
318
326
#if SDL_VERSION_ATLEAST(2, 0, 18)
0 commit comments