From 5da3302732f24d95f34c6602e6a13f821dbee125 Mon Sep 17 00:00:00 2001 From: Rahul Menon Date: Tue, 17 Oct 2023 10:15:20 -0500 Subject: [PATCH] deployment updates --- CMakeLists.txt | 5 +++++ config/joystick.lua | 6 +----- config/radio.lua | 6 +++--- src/radio_driver/radio_driver.cpp | 4 ++-- src/radio_driver/radio_interface.cpp | 3 ++- 5 files changed, 13 insertions(+), 11 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 560f571..fd98da1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -94,6 +94,11 @@ IF(${CMAKE_BUILD_MODE} MATCHES "Omega") src/radio_driver/radio_interface.cpp src/vesc_driver/serial.cc) TARGET_LINK_LIBRARIES(radio_driver ${libs}) + + ROSBUILD_ADD_EXECUTABLE(joystick + src/joystick/joystick.cc + src/joystick/joystick_driver.cc) + TARGET_LINK_LIBRARIES(joystick ${libs}) ENDIF() MESSAGE(STATUS "Building simulator") diff --git a/config/joystick.lua b/config/joystick.lua index 2a10dbc..574f074 100644 --- a/config/joystick.lua +++ b/config/joystick.lua @@ -1,9 +1,5 @@ -joystick_port="/dev/input/js1" +joystick_port="/dev/input/js0" -- name of controller used joystick_name="Logitech_F710" -- joystick_name="Sony_DualShock_4" - - - - diff --git a/config/radio.lua b/config/radio.lua index d5263c3..1fb0aee 100644 --- a/config/radio.lua +++ b/config/radio.lua @@ -5,9 +5,9 @@ command_rate = 20; -- how often to send commands (Hz) command_timeout = 0.5; -- if a command is not received after this amount of time, the car will stop full_speed = 8.0; -- fastest the car is capable of going (m/s) -max_speed = 2.0; -- fastest we want to allow the car to go (m/s) -max_accel = 6.0; -- most acceleration we want to allow -max_decel = 6.0; -- most decelration we want to allow +max_speed = 4.0; -- fastest we want to allow the car to go (m/s) +max_accel = 10.0; -- most acceleration we want to allow +max_decel = 10.0; -- most decelration we want to allow speed_to_throttle = 1.0 / full_speed; -- how much throttle to apply per m/s of speed, assumption of linearity diff --git a/src/radio_driver/radio_driver.cpp b/src/radio_driver/radio_driver.cpp index 56a5d2c..dc1e358 100644 --- a/src/radio_driver/radio_driver.cpp +++ b/src/radio_driver/radio_driver.cpp @@ -96,8 +96,7 @@ void RadioDriver::joystickCallback(const sensor_msgs::Joy& msg) { // TODO: make this configurable // TODO: add turbo - // TODO: check this is the right range - joystick_velocity_ = -msg.axes[4] * max_speed_; + joystick_velocity_ = -msg.axes[3] * max_speed_; joystick_curvature_ = -msg.axes[0] * max_curvature_; static std_msgs::Bool autonomy_enabler_msg; @@ -142,6 +141,7 @@ void RadioDriver::timerCallback(const ros::SteadyTimerEvent& event) { } } + // TODO: braking throttle = speedToThrottle(vel); steering = curvatureToSteering(curv); diff --git a/src/radio_driver/radio_interface.cpp b/src/radio_driver/radio_interface.cpp index 0567e81..394f3c4 100644 --- a/src/radio_driver/radio_interface.cpp +++ b/src/radio_driver/radio_interface.cpp @@ -46,7 +46,8 @@ void RadioInterface::commandToBuffer(float throttle, float steering) { // TODO: print these to see if they are correct uint32_t throttle_pwm = (throttle + 1) * (max_val - min_val) / 2 + min_val; - uint32_t steering_pwm = (steering + 1) * (max_val - min_val) / 2 + min_val; + uint32_t steering_pwm = (-steering + 1) * (max_val - min_val) / 2 + min_val; + LOG(INFO) << "Throttle: " << throttle_pwm << ", Steering: " << steering_pwm; if (throttle_pwm < min_val || throttle_pwm > max_val) { LOG(ERROR) << "Throttle command out of range: " << throttle_pwm;