Skip to content

Commit

Permalink
deployment updates
Browse files Browse the repository at this point in the history
  • Loading branch information
rmeno12 committed Oct 17, 2023
1 parent ac8a45d commit 5da3302
Show file tree
Hide file tree
Showing 5 changed files with 13 additions and 11 deletions.
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand Down
6 changes: 1 addition & 5 deletions config/joystick.lua
Original file line number Diff line number Diff line change
@@ -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"




6 changes: 3 additions & 3 deletions config/radio.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
4 changes: 2 additions & 2 deletions src/radio_driver/radio_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -142,6 +141,7 @@ void RadioDriver::timerCallback(const ros::SteadyTimerEvent& event) {
}
}

// TODO: braking
throttle = speedToThrottle(vel);
steering = curvatureToSteering(curv);

Expand Down
3 changes: 2 additions & 1 deletion src/radio_driver/radio_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 5da3302

Please sign in to comment.