|
| 1 | +--- |
| 2 | +title: How to Find VESC Servo Parameters |
| 3 | +author: hyeongjoon-yang |
| 4 | +date: 2026-02-03 21:00:00 +0900 |
| 5 | +categories: [build, beginner] |
| 6 | +tags: [gain, servo, vesc] |
| 7 | +image: |
| 8 | + path: /assets/img/posts/servo-parameter/servo-output.png |
| 9 | +lang: en |
| 10 | +lang_ref: servo-parameter |
| 11 | +math: true |
| 12 | +--- |
| 13 | + |
| 14 | +In autonomous driving, precise steering control directly affects path following performance. If the conversion between steering commands and actual wheel angles is inaccurate, the vehicle cannot follow the intended path and may result in path deviation or accidents. This post covers the concept and characteristics of Servo Parameters and how to calibrate them through experiments. |
| 15 | + |
| 16 | +## What is Servo Parameter? |
| 17 | + |
| 18 | +In the VESC ROS package, steering commands are input as steering angles in radians and converted to values between 0 and 1 that the servo understands. This conversion relationship can be represented by gain and offset as follows: |
| 19 | + |
| 20 | +``` |
| 21 | +servo_value = steering_angle_to_servo_gain × steering_angle + steering_angle_to_servo_offset |
| 22 | +``` |
| 23 | + |
| 24 | +- **steering_angle**: Steering angle input by the user (radians) |
| 25 | +- **servo_value**: Command delivered to the servo (0 ~ 1) |
| 26 | +- **steering_angle_to_servo_gain**: Proportional constant for converting steering angle to servo value |
| 27 | +- **steering_angle_to_servo_offset**: Servo value at straight-ahead position (steering angle 0) |
| 28 | + |
| 29 | +## Theoretical Measurement of Servo Parameters |
| 30 | + |
| 31 | +For ERPM gain, hardware specifications such as gear ratio, pole pairs, and wheel radius are multiplied linearly, so it can be calculated mathematically. |
| 32 | + |
| 33 | +On the other hand, Servo Parameters are difficult to measure theoretically. To understand why, you need to know the structure of RC car steering systems. |
| 34 | + |
| 35 | +### What is Ackermann Steering Geometry? |
| 36 | + |
| 37 | +When a vehicle turns, the two front wheels are positioned at different distances from the center of rotation. The inner wheel is closer to the center of rotation, and the outer wheel is farther away. |
| 38 | + |
| 39 | +Wheels can only roll purely in a direction perpendicular to their axis. If both front wheels turn at the same steering angle, the extensions of the two wheel axes become parallel, resulting in different turning radii for each wheel and slip occurring. |
| 40 | + |
| 41 | +To prevent this, the inner wheel must turn more and the outer wheel less so that the extensions of both wheel axes meet at the same center of rotation. This geometric condition is called **Ackermann Steering Geometry**. |
| 42 | + |
| 43 | + |
| 44 | +_Ackermann Steering Geometry_ |
| 45 | + |
| 46 | +### Nonlinearity of Bellcrank System |
| 47 | + |
| 48 | +In RC cars, Ackermann Steering Geometry is approximately implemented through bellcrank systems, tie rods, and knuckle arms. Due to this complex kinematic structure, the relationship between servo angle and actual wheel steering angle is **nonlinear**. |
| 49 | + |
| 50 | +|  |  | |
| 51 | +|:---:|:---:| |
| 52 | +| Traxxas Fiesta Steering System (Bellcrank) | Traxxas Fiesta Ackermann Steering Geometry | |
| 53 | + |
| 54 | +In other words, the `steering_angle_to_servo_gain` we set is actually a linear approximation that works well around the center (straight ahead) but may have errors near maximum steering angles. Therefore, it's common to calibrate Servo Parameters experimentally for the range you frequently use rather than through theoretical calculations. |
| 55 | + |
| 56 | +## Characteristics of Servo Parameters |
| 57 | + |
| 58 | +### Servo Range Based on Hardware |
| 59 | + |
| 60 | +While the servo receives commands between 0 and 1, depending on hardware specifications, steering commands (radians) may use the entire range or only a portion of it. |
| 61 | + |
| 62 | +### Nonlinearity and Calibration Range |
| 63 | + |
| 64 | +Due to the bellcrank linkage structure, the relationship between servo value and actual wheel steering angle is nonlinear. Therefore, it doesn't map accurately to the required turning radius at all steering angles. For this reason, it's recommended to map servo gain within the steering angle range you frequently use. |
| 65 | + |
| 66 | +For example, if most steering in F1tenth driving occurs within ±0.25 radians (approximately ±14 degrees), it's effective to match accuracy within that range. Extreme steering angles are only used in low-speed emergency situations, so slight errors are acceptable. |
| 67 | + |
| 68 | +### Importance of Servo Horn Initial Position |
| 69 | + |
| 70 | +When applying servo gain and offset, care must be taken to ensure that maximum steering commands don't constrain only one direction (left or right). In other words, even with maximum steering commands, servo commands must always be between 0 and 1. |
| 71 | + |
| 72 | +For this purpose, it's important to position the servo horn initial position well at the center of the operating range. When the servo horn is properly installed, the offset is measured close to 0.5. |
| 73 | + |
| 74 | +## Finding Servo Parameters Experimentally |
| 75 | + |
| 76 | +### Finding Offset (Straight Alignment) |
| 77 | + |
| 78 | +The offset is the servo value when the steering angle is 0. You just need to find the servo value when the wheels point exactly straight ahead. |
| 79 | + |
| 80 | +### Measurement Procedure |
| 81 | + |
| 82 | +1. To minimize the effects of tire friction or floor texture, use the joystick to give left and right steering commands before measurement so the servo motor is well positioned at center. |
| 83 | +2. Start slowly to avoid tire slipping and drive straight. |
| 84 | +3. Observe the direction the vehicle is traveling to check if it goes straight without drifting left or right. |
| 85 | +4. If it doesn't go straight, adjust the offset value slightly and repeat. |
| 86 | +5. Set the value when the vehicle goes exactly straight as `steering_angle_to_servo_offset`. |
| 87 | + |
| 88 | +> If the servo horn is properly installed, the offset will be near 0.5. If it deviates significantly from 0.5, it's recommended to remove and reinstall the servo horn to center it. |
| 89 | +{: .prompt-tip } |
| 90 | + |
| 91 | +### Finding Gain |
| 92 | + |
| 93 | +Gain is the ratio of servo value change to steering angle change. Measure the turning radius through accumulated odometry in rviz and tune the gain using the Ackermann formula. |
| 94 | + |
| 95 | +### Ackermann Turning Radius Formula |
| 96 | + |
| 97 | +In Ackermann steering geometry, the relationship between steering angle and turning radius is as follows. The wheelbase is the distance between the front and rear axles, which can be measured directly with a ruler or referenced from manufacturer information. |
| 98 | + |
| 99 | +$$ |
| 100 | +turning\_radius = \frac{wheelbase}{\tan(steering\_angle)} |
| 101 | +$$ |
| 102 | + |
| 103 | +Calculate the expected turning radius from the commanded steering angle and adjust the gain by comparing it with the actual measured turning radius. |
| 104 | + |
| 105 | + |
| 106 | +_Measuring turning radius using Rviz_ |
| 107 | + |
| 108 | +### Measurement Procedure |
| 109 | + |
| 110 | +1. Start with odometry visualization available in rviz. |
| 111 | +2. Drive in a circle at low speed without slip while giving a constant steering angle command (e.g., 0.2 rad). |
| 112 | +3. When the accumulated odometry trajectory in rviz forms a circle, use the Measure function to measure the circle's diameter and obtain the turning radius (R). |
| 113 | +4. Compare the expected turning radius calculated from the commanded steering angle with the actual turning radius and adjust the gain. |
| 114 | + |
| 115 | +### Calculation Example (Based on Traxxas Fiesta) |
| 116 | + |
| 117 | +| Item | Value | |
| 118 | +|------|-------| |
| 119 | +| Wheelbase | 0.33m | |
| 120 | +| Commanded steering angle | 0.2 rad | |
| 121 | +| Expected turning radius | 0.33 / tan(0.2) ≈ 1.62m | |
| 122 | +| Actually measured turning radius | 1.8m | |
| 123 | + |
| 124 | +In this case, since the actual (1.8m) is larger than expected (1.62m), it means the actual steering angle is smaller than commanded. Therefore, the absolute value of gain should be increased. |
| 125 | + |
| 126 | +### Correction Method |
| 127 | + |
| 128 | +| Situation | Action | |
| 129 | +|-----------|--------| |
| 130 | +| Actual turning radius > Expected turning radius | Increase the absolute value of gain | |
| 131 | +| Actual turning radius < Expected turning radius | Decrease the absolute value of gain | |
| 132 | + |
| 133 | +### Precautions |
| 134 | + |
| 135 | +- Test multiple points within the frequently used steering angle range (e.g., ±0.25 rad) to find a gain that works well overall. |
| 136 | +- When measuring, drive at sufficiently low speed to avoid slip to obtain an accurate turning radius. |
| 137 | + |
| 138 | +## Conclusion |
| 139 | + |
| 140 | +Servo Parameters must be measured experimentally, but since the values don't change unless the hardware is modified, you only need to measure them accurately once. It's recommended to take time for precise calibration. These parameters map the user's intended steering angle to be accurately transmitted to the vehicle, so be careful not to manipulate them arbitrarily after calibration. |
0 commit comments