Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
230d35c
Using std::thread for rxThread
Apr 14, 2021
fabb41e
Merge pull request #7 from f1tenth/use-std-thread
Apr 15, 2021
83289aa
Add current control to vesc driver
tbalch-tri Jun 8, 2022
4b43fc3
Add current control to vesc driver
tbalch-tri Jun 8, 2022
e2f8695
Merge pull request #24 from ToyotaResearchInstitute/push-f1tenth
hzheng40 Jun 21, 2022
619fa2a
Merge branch 'main' into push-f1tenth
tbalch-tri Jun 21, 2022
bfb612e
Merge pull request #25 from ToyotaResearchInstitute/push-f1tenth
hzheng40 Jun 21, 2022
e79898f
Fix if comparison.
ValerioMagnago Feb 19, 2023
e3f3084
Merge pull request #27 from Mailamaca/small_fix
JWhitleyWork Feb 20, 2023
5d45659
fixed odometry
sanjotbains May 16, 2025
8728f4d
first braking test
sanjotbains May 16, 2025
0ba271f
linear scaling braking
sanjotbains May 17, 2025
87d91d0
Merge commit '0ba271f65f69fd3037424ff9ecc2bda9aedf8c19' into humble
sanjotbains May 17, 2025
7ba38c4
fixing merge issues
sanjotbains May 17, 2025
1a8ec58
resolving conflicts
sanjotbains May 17, 2025
82920af
Add Traxxas motor config file
sanjotbains May 18, 2025
e8f4d01
Update ackermann_to_vesc.cpp
sanjotbains May 18, 2025
eb4f783
Update README.md
sanjotbains May 18, 2025
0c6a362
parametrizing vel_diff_thresh
sanjotbains May 23, 2025
9844544
making the ackermann to vesc conversion more robust
sanjotbains May 23, 2025
5f4527c
REWROTE THE WHOLE THING< RAWDOGGED IT NO LLM JSUT STRAIGHT ZEN MODE
sanjotbains May 24, 2025
e55dfab
braking sigmoid curve, parameterized functions, configurable from lau…
sanjotbains May 26, 2025
8bcca19
psuedocode for initial acceleration handling, fixing reverse
sanjotbains Jun 1, 2025
a7fa0ed
first successful compile
sanjotbains Jun 1, 2025
6107301
fixed reverse, added smooth start
sanjotbains Jun 3, 2025
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
7 changes: 6 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,11 +1,16 @@
# Veddar VESC Interface
# Ray-Quasar: Veddar VESC Interface

![ROS2 CI Workflow](https://github.com/f1tenth/vesc/workflows/ROS2%20CI%20Workflow/badge.svg)

Packages to interface with Veddar VESC motor controllers. See https://vesc-project.com/ for details

This is a ROS2 implementation of the ROS1 driver using the new serial driver located in [transport drivers](https://github.com/ros-drivers/transport_drivers).

## Ackermann to VESC Node has been reconfigured to publish braking messages.
This functionality existed in the ROS1 version of this package but was not included in the port to ROS2. I have added it back in, and improved it somewhat.

If you are an F1Tenth/Roboracer team using Traxxas' Velineon 3351R 3500 BLDC motor [this motor configuration XML](https://github.com/ray-quasar/vesc/blob/main/velineon3500_HFI.xml) will get you HFI for smoother starts as well.

## How to test

1. Clone this repository and [transport drivers](https://github.com/ros-drivers/transport_drivers) into `src`.
Expand Down
217 changes: 217 additions & 0 deletions velineon3500_HFI.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,217 @@
<?xml version="1.0" encoding="UTF-8"?>
<MCConfiguration>
<ConfigVersion>3</ConfigVersion>
<pwm_mode>1</pwm_mode>
<comm_mode>0</comm_mode>
<motor_type>2</motor_type>
<sensor_mode>0</sensor_mode>
<l_current_max>99</l_current_max>
<l_current_min>-71</l_current_min>
<l_in_current_max>99</l_in_current_max>
<l_in_current_min>-60</l_in_current_min>
<l_in_current_map_start>1</l_in_current_map_start>
<l_in_current_map_filter>0.005</l_in_current_map_filter>
<l_abs_current_max>150</l_abs_current_max>
<l_min_erpm>-100000</l_min_erpm>
<l_max_erpm>100000</l_max_erpm>
<l_erpm_start>0.8</l_erpm_start>
<l_max_erpm_fbrake>300</l_max_erpm_fbrake>
<l_max_erpm_fbrake_cc>1500</l_max_erpm_fbrake_cc>
<l_min_vin>8</l_min_vin>
<l_max_vin>57</l_max_vin>
<l_battery_cut_start>10.2</l_battery_cut_start>
<l_battery_cut_end>9</l_battery_cut_end>
<l_battery_regen_cut_start>1000</l_battery_regen_cut_start>
<l_battery_regen_cut_end>1100</l_battery_regen_cut_end>
<l_slow_abs_current>0</l_slow_abs_current>
<l_temp_fet_start>85</l_temp_fet_start>
<l_temp_fet_end>100</l_temp_fet_end>
<l_temp_motor_start>85</l_temp_motor_start>
<l_temp_motor_end>100</l_temp_motor_end>
<l_temp_accel_dec>0.15</l_temp_accel_dec>
<l_min_duty>0.005</l_min_duty>
<l_max_duty>0.95</l_max_duty>
<l_watt_max>1.5e+06</l_watt_max>
<l_watt_min>-1.5e+06</l_watt_min>
<l_current_max_scale>1</l_current_max_scale>
<l_current_min_scale>1</l_current_min_scale>
<l_duty_start>1</l_duty_start>
<sl_min_erpm>150</sl_min_erpm>
<sl_min_erpm_cycle_int_limit>1100</sl_min_erpm_cycle_int_limit>
<sl_max_fullbreak_current_dir_change>10</sl_max_fullbreak_current_dir_change>
<sl_cycle_int_limit>62</sl_cycle_int_limit>
<sl_phase_advance_at_br>0.8</sl_phase_advance_at_br>
<sl_cycle_int_rpm_br>80000</sl_cycle_int_rpm_br>
<sl_bemf_coupling_k>600</sl_bemf_coupling_k>
<hall_table__0>-1</hall_table__0>
<hall_table__1>1</hall_table__1>
<hall_table__2>3</hall_table__2>
<hall_table__3>2</hall_table__3>
<hall_table__4>5</hall_table__4>
<hall_table__5>6</hall_table__5>
<hall_table__6>4</hall_table__6>
<hall_table__7>-1</hall_table__7>
<hall_sl_erpm>2000</hall_sl_erpm>
<foc_current_kp>0.00264233</foc_current_kp>
<foc_current_ki>6.61179</foc_current_ki>
<foc_f_zv>30000</foc_f_zv>
<foc_dt_us>0.12</foc_dt_us>
<foc_encoder_inverted>0</foc_encoder_inverted>
<foc_encoder_offset>180</foc_encoder_offset>
<foc_encoder_ratio>7</foc_encoder_ratio>
<foc_sensor_mode>3</foc_sensor_mode>
<foc_pll_kp>2000</foc_pll_kp>
<foc_pll_ki>30000</foc_pll_ki>
<foc_motor_l>2.64233e-06</foc_motor_l>
<foc_motor_ld_lq_diff>2.69788e-07</foc_motor_ld_lq_diff>
<foc_motor_r>0.00661179</foc_motor_r>
<foc_motor_flux_linkage>0.000707035</foc_motor_flux_linkage>
<foc_observer_gain>2.00041e+09</foc_observer_gain>
<foc_observer_gain_slow>0.05</foc_observer_gain_slow>
<foc_observer_offset>-1</foc_observer_offset>
<foc_duty_dowmramp_kp>50</foc_duty_dowmramp_kp>
<foc_duty_dowmramp_ki>1000</foc_duty_dowmramp_ki>
<foc_start_curr_dec>1</foc_start_curr_dec>
<foc_start_curr_dec_rpm>2500</foc_start_curr_dec_rpm>
<foc_openloop_rpm>1400</foc_openloop_rpm>
<foc_openloop_rpm_low>0</foc_openloop_rpm_low>
<foc_d_gain_scale_start>0.9</foc_d_gain_scale_start>
<foc_d_gain_scale_max_mod>0.2</foc_d_gain_scale_max_mod>
<foc_sl_openloop_hyst>0.1</foc_sl_openloop_hyst>
<foc_sl_openloop_time_lock>0</foc_sl_openloop_time_lock>
<foc_sl_openloop_time_ramp>0.1</foc_sl_openloop_time_ramp>
<foc_sl_openloop_time>0.05</foc_sl_openloop_time>
<foc_sl_openloop_boost_q>0</foc_sl_openloop_boost_q>
<foc_sl_openloop_max_q>-1</foc_sl_openloop_max_q>
<foc_hall_table__0>255</foc_hall_table__0>
<foc_hall_table__1>255</foc_hall_table__1>
<foc_hall_table__2>255</foc_hall_table__2>
<foc_hall_table__3>255</foc_hall_table__3>
<foc_hall_table__4>255</foc_hall_table__4>
<foc_hall_table__5>255</foc_hall_table__5>
<foc_hall_table__6>255</foc_hall_table__6>
<foc_hall_table__7>255</foc_hall_table__7>
<foc_hall_interp_erpm>500</foc_hall_interp_erpm>
<foc_sl_erpm_start>2500</foc_sl_erpm_start>
<foc_sl_erpm>4000</foc_sl_erpm>
<foc_control_sample_mode>0</foc_control_sample_mode>
<foc_current_sample_mode>0</foc_current_sample_mode>
<foc_sat_comp_mode>0</foc_sat_comp_mode>
<foc_sat_comp>0</foc_sat_comp>
<foc_temp_comp>0</foc_temp_comp>
<foc_temp_comp_base_temp>25</foc_temp_comp_base_temp>
<foc_current_filter_const>0.1</foc_current_filter_const>
<foc_cc_decoupling>0</foc_cc_decoupling>
<foc_observer_type>3</foc_observer_type>
<foc_hfi_voltage_start>10</foc_hfi_voltage_start>
<foc_hfi_voltage_run>6</foc_hfi_voltage_run>
<foc_hfi_voltage_max>8</foc_hfi_voltage_max>
<foc_hfi_gain>0.3</foc_hfi_gain>
<foc_hfi_max_err>0.15</foc_hfi_max_err>
<foc_hfi_hyst>0</foc_hfi_hyst>
<foc_sl_erpm_hfi>3000</foc_sl_erpm_hfi>
<foc_hfi_start_samples>5</foc_hfi_start_samples>
<foc_hfi_obs_ovr_sec>0.001</foc_hfi_obs_ovr_sec>
<foc_hfi_samples>1</foc_hfi_samples>
<foc_offsets_cal_on_boot>1</foc_offsets_cal_on_boot>
<foc_offsets_current__0>2048.78</foc_offsets_current__0>
<foc_offsets_current__1>2049.13</foc_offsets_current__1>
<foc_offsets_current__2>2048.43</foc_offsets_current__2>
<foc_offsets_voltage__0>-0.0004</foc_offsets_voltage__0>
<foc_offsets_voltage__1>0.0001</foc_offsets_voltage__1>
<foc_offsets_voltage__2>0.0002</foc_offsets_voltage__2>
<foc_offsets_voltage_undriven__0>0</foc_offsets_voltage_undriven__0>
<foc_offsets_voltage_undriven__1>0</foc_offsets_voltage_undriven__1>
<foc_offsets_voltage_undriven__2>0</foc_offsets_voltage_undriven__2>
<foc_phase_filter_enable>1</foc_phase_filter_enable>
<foc_phase_filter_disable_fault>1</foc_phase_filter_disable_fault>
<foc_phase_filter_max_erpm>4000</foc_phase_filter_max_erpm>
<foc_mtpa_mode>0</foc_mtpa_mode>
<foc_fw_current_max>0</foc_fw_current_max>
<foc_fw_duty_start>0.9</foc_fw_duty_start>
<foc_fw_q_current_factor>0.02</foc_fw_q_current_factor>
<foc_fw_ramp_time>0.2</foc_fw_ramp_time>
<foc_speed_soure>0</foc_speed_soure>
<foc_short_ls_on_zero_duty>0</foc_short_ls_on_zero_duty>
<sp_pid_loop_rate>5</sp_pid_loop_rate>
<s_pid_kp>0.002</s_pid_kp>
<s_pid_ki>0.0015</s_pid_ki>
<s_pid_kd>0.0002</s_pid_kd>
<s_pid_kd_filter>0.2</s_pid_kd_filter>
<s_pid_min_erpm>900</s_pid_min_erpm>
<s_pid_allow_braking>1</s_pid_allow_braking>
<s_pid_ramp_erpms_s>25000</s_pid_ramp_erpms_s>
<s_pid_speed_source>0</s_pid_speed_source>
<p_pid_kp>0.025</p_pid_kp>
<p_pid_ki>0</p_pid_ki>
<p_pid_kd>0</p_pid_kd>
<p_pid_offset>0</p_pid_offset>
<p_pid_kd_proc>0.00035</p_pid_kd_proc>
<p_pid_kd_filter>0.2</p_pid_kd_filter>
<p_pid_ang_div>1</p_pid_ang_div>
<p_pid_gain_dec_angle>0</p_pid_gain_dec_angle>
<cc_startup_boost_duty>0.01</cc_startup_boost_duty>
<cc_min_current>0.05</cc_min_current>
<cc_gain>0.0046</cc_gain>
<cc_ramp_step_max>0.04</cc_ramp_step_max>
<m_fault_stop_time_ms>500</m_fault_stop_time_ms>
<m_duty_ramp_step>0.02</m_duty_ramp_step>
<m_current_backoff_gain>0.5</m_current_backoff_gain>
<m_encoder_counts>8192</m_encoder_counts>
<m_encoder_sin_amp>1</m_encoder_sin_amp>
<m_encoder_cos_amp>1</m_encoder_cos_amp>
<m_encoder_sin_offset>1.65</m_encoder_sin_offset>
<m_encoder_cos_offset>1.65</m_encoder_cos_offset>
<m_encoder_sincos_filter_constant>0.5</m_encoder_sincos_filter_constant>
<m_encoder_sincos_phase_correction>0</m_encoder_sincos_phase_correction>
<m_sensor_port_mode>0</m_sensor_port_mode>
<m_invert_direction>0</m_invert_direction>
<m_drv8301_oc_mode>0</m_drv8301_oc_mode>
<m_drv8301_oc_adj>16</m_drv8301_oc_adj>
<m_bldc_f_sw_min>3000</m_bldc_f_sw_min>
<m_bldc_f_sw_max>35000</m_bldc_f_sw_max>
<m_dc_f_sw>25000</m_dc_f_sw>
<m_ntc_motor_beta>3380</m_ntc_motor_beta>
<m_out_aux_mode>0</m_out_aux_mode>
<m_motor_temp_sens_type>0</m_motor_temp_sens_type>
<m_ptc_motor_coeff>0.61</m_ptc_motor_coeff>
<m_ntcx_ptcx_res>10000</m_ntcx_ptcx_res>
<m_ntcx_ptcx_temp_base>25</m_ntcx_ptcx_temp_base>
<m_hall_extra_samples>3</m_hall_extra_samples>
<m_batt_filter_const>45</m_batt_filter_const>
<si_motor_poles>2</si_motor_poles>
<si_gear_ratio>1.459</si_gear_ratio>
<si_wheel_diameter>0.11</si_wheel_diameter>
<si_battery_type>0</si_battery_type>
<si_battery_cells>3</si_battery_cells>
<si_battery_ah>5</si_battery_ah>
<si_motor_nl_current>1</si_motor_nl_current>
<motor_brand>Traxxas</motor_brand>
<motor_model>Velineon 3500</motor_model>
<motor_weight>248</motor_weight>
<motor_sensor_type>0</motor_sensor_type>
<motor_description>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Roboto'; font-size:12pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;A motor description can be edited here.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</motor_description>
<motor_quality_bearings>0</motor_quality_bearings>
<motor_quality_magnets>0</motor_quality_magnets>
<motor_quality_construction>0</motor_quality_construction>
<motor_quality_description>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Roboto'; font-size:12pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Some comments about the motor quality. Images can be added as well.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</motor_quality_description>
<bms.type>1</bms.type>
<bms.limit_mode>3</bms.limit_mode>
<bms.t_limit_start>45</bms.t_limit_start>
<bms.t_limit_end>65</bms.t_limit_end>
<bms.soc_limit_start>0.05</bms.soc_limit_start>
<bms.soc_limit_end>0</bms.soc_limit_end>
<bms.vmin_limit_start>2.9</bms.vmin_limit_start>
<bms.vmin_limit_end>2.5</bms.vmin_limit_end>
<bms.vmax_limit_start>4.2</bms.vmax_limit_start>
<bms.vmax_limit_end>4.3</bms.vmax_limit_end>
<bms.fwd_can_mode>0</bms.fwd_can_mode>
</MCConfiguration>
18 changes: 18 additions & 0 deletions vesc_ackermann/include/vesc_ackermann/ackermann_to_vesc.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,13 +32,15 @@
#define VESC_ACKERMANN__ACKERMANN_TO_VESC_HPP_

#include <ackermann_msgs/msg/ackermann_drive_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/float64.hpp>

namespace vesc_ackermann
{

using ackermann_msgs::msg::AckermannDriveStamped;
using nav_msgs::msg::Odometry;
using std_msgs::msg::Float64;

class AckermannToVesc : public rclcpp::Node
Expand All @@ -48,19 +50,35 @@ class AckermannToVesc : public rclcpp::Node

private:
// ROS parameters
u_int8_t operation_mode_;
// bool previous_mode_speed_ = true;
// conversion gain and offset
double speed_to_erpm_gain_, speed_to_erpm_offset_;
double speed_to_braking_gain_, speed_to_braking_center_, speed_to_braking_max_, speed_to_braking_min_;
double steering_to_servo_gain_, steering_to_servo_offset_;
double current_vel_, brake_deadzone_;
double accel_to_current_gain_, accel_to_brake_gain_;

enum operation_modes {
ACCEL_TO_CURRENT,
VEL_TO_CURRENT,
VEL_TO_ERPM
};

/** @todo consider also providing an interpolated look-up table conversion */

// ROS services
rclcpp::Publisher<Float64>::SharedPtr erpm_pub_;
rclcpp::Publisher<Float64>::SharedPtr servo_pub_;
rclcpp::Publisher<Float64>::SharedPtr brake_pub_;
rclcpp::Publisher<Float64>::SharedPtr current_pub_;

rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
rclcpp::Subscription<AckermannDriveStamped>::SharedPtr ackermann_sub_;

// ROS callbacks
void ackermannCmdCallback(const AckermannDriveStamped::SharedPtr cmd);
void odomCallback(const nav_msgs::msg::Odometry::SharedPtr odom_msg);
};

} // namespace vesc_ackermann
Expand Down
Loading