Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions joy/include/joy/game_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include <memory>
#include <string>
#include <thread>
#include <utility>

#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/joy.hpp>
Expand Down Expand Up @@ -75,6 +76,10 @@ class GameController final : public rclcpp::Node
double scale_{0.0};
double autorepeat_rate_{0.0};
int autorepeat_interval_ms_{0};
std::pair<builtin_interfaces::msg::Time, uint16_t> rumble_intensity_left_stamped_{
builtin_interfaces::msg::Time(), 0};
std::pair<builtin_interfaces::msg::Time, uint16_t> rumble_intensity_right_stamped_{
builtin_interfaces::msg::Time(), 0};
bool sticky_buttons_{false};
bool publish_soon_{false};
rclcpp::Time publish_soon_time_;
Expand Down
38 changes: 31 additions & 7 deletions joy/src/game_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,26 +131,50 @@ GameController::~GameController()

void GameController::feedbackCb(const std::shared_ptr<sensor_msgs::msg::JoyFeedback> msg)
{
uint32_t duration_ms = 1000;

if (msg->type != sensor_msgs::msg::JoyFeedback::TYPE_RUMBLE) {
// We only support rumble
return;
}

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

if (msg->intensity < 0.0 || msg->intensity > 1.0) {
// We only accept intensities between 0 and 1.
uint16_t intensity = static_cast<uint16_t>(msg->intensity * 0xFFFF);
rclcpp::Time now = this->now();

// 0: Both left motor (low frequency) and right motor (high frequency) rumble
// 1: Left rumble
// 2: Right rumble
if (msg->id == 0) {
rumble_intensity_left_stamped_ = {now, intensity};
rumble_intensity_right_stamped_ = {now, intensity};
} else if (msg->id == 1) {
rumble_intensity_left_stamped_ = {now, intensity};
if ((now - rumble_intensity_right_stamped_.first) >=
rclcpp::Duration::from_seconds(duration_ms / 1000.0))
{
rumble_intensity_right_stamped_ = {now, 0};
}
} else if (msg->id == 2) {
rumble_intensity_right_stamped_ = {now, intensity};
if ((now - rumble_intensity_left_stamped_.first) >=
rclcpp::Duration::from_seconds(duration_ms / 1000.0))
{
rumble_intensity_left_stamped_ = {now, 0};
}
} else {
return;
}

if (game_controller_ != nullptr) {
// We purposely ignore the return value; if it fails, what can we do?
uint16_t intensity = static_cast<uint16_t>(msg->intensity * 0xFFFF);
SDL_GameControllerRumble(game_controller_, intensity, intensity, 1000);
SDL_GameControllerRumble(
game_controller_, rumble_intensity_left_stamped_.second,
rumble_intensity_right_stamped_.second, duration_ms);
}
}

Expand Down