Skip to content

Commit 2b12934

Browse files
committed
fix negative trigger values in game_controller_node
1 parent 881f3a5 commit 2b12934

File tree

2 files changed

+20
-12
lines changed

2 files changed

+20
-12
lines changed

joy/include/joy/game_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class GameController final : public rclcpp::Node
6363
bool handleControllerButtonUp(const SDL_ControllerButtonEvent & e);
6464
void handleControllerDeviceAdded(const SDL_ControllerDeviceEvent & e);
6565
void handleControllerDeviceRemoved(const SDL_ControllerDeviceEvent & e);
66-
float convertRawAxisValueToROS(int16_t val);
66+
float convertRawAxisValueToROS(int16_t val, const uint8_t & axis);
6767
void feedbackCb(const std::shared_ptr<sensor_msgs::msg::JoyFeedback> msg);
6868

6969
int dev_id_{0};

joy/src/game_controller.cpp

Lines changed: 19 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -66,12 +66,10 @@ GameController::GameController(const rclcpp::NodeOptions & options)
6666
unscaled_deadzone_ = 32767.0 * scaled_deadzone_;
6767
// According to the SDL documentation, this always returns a value between
6868
// -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);
7573

7674
autorepeat_rate_ = this->declare_parameter("autorepeat_rate", 20.0);
7775
if (autorepeat_rate_ < 0.0) {
@@ -154,7 +152,7 @@ void GameController::feedbackCb(const std::shared_ptr<sensor_msgs::msg::JoyFeedb
154152
}
155153
}
156154

157-
float GameController::convertRawAxisValueToROS(int16_t val)
155+
float GameController::convertRawAxisValueToROS(int16_t val, const uint8_t & axis)
158156
{
159157
// SDL reports axis values between -32768 and 32767. To make sure
160158
// 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)
177175
double_val = 0.0;
178176
}
179177

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);
181189
}
182190

183191
bool GameController::handleControllerAxis(const SDL_ControllerAxisEvent & e)
@@ -194,7 +202,7 @@ bool GameController::handleControllerAxis(const SDL_ControllerAxisEvent & e)
194202
}
195203

196204
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));
198206
if (last_axis_value != joy_msg_.axes.at(e.axis)) {
199207
if (coalesce_interval_ms_ > 0 && !publish_soon_) {
200208
publish_soon_ = true;
@@ -309,10 +317,10 @@ void GameController::handleControllerDeviceAdded(const SDL_ControllerDeviceEvent
309317
}
310318

311319
// 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) {
313321
int16_t state =
314322
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);
316324
}
317325

318326
#if SDL_VERSION_ATLEAST(2, 0, 18)

0 commit comments

Comments
 (0)