@@ -61,7 +61,7 @@ class SteeringOdometry
61
61
/* *
62
62
* \brief Updates the odometry class with latest wheels position
63
63
* \param traction_wheel_pos traction wheel position [rad]
64
- * \param steer_pos Front Steer position [rad]
64
+ * \param steer_pos Steer wheel position [rad]
65
65
* \param dt time difference to last call
66
66
* \return true if the odometry is actually updated
67
67
*/
@@ -72,7 +72,7 @@ class SteeringOdometry
72
72
* \brief Updates the odometry class with latest wheels position
73
73
* \param right_traction_wheel_pos Right traction wheel velocity [rad]
74
74
* \param left_traction_wheel_pos Left traction wheel velocity [rad]
75
- * \param front_steer_pos Steer wheel position [rad]
75
+ * \param steer_pos Steer wheel position [rad]
76
76
* \param dt time difference to last call
77
77
* \return true if the odometry is actually updated
78
78
*/
@@ -96,7 +96,7 @@ class SteeringOdometry
96
96
/* *
97
97
* \brief Updates the odometry class with latest wheels position
98
98
* \param traction_wheel_vel Traction wheel velocity [rad/s]
99
- * \param front_steer_pos Steer wheel position [rad]
99
+ * \param steer_pos Steer wheel position [rad]
100
100
* \param dt time difference to last call
101
101
* \return true if the odometry is actually updated
102
102
*/
@@ -107,7 +107,7 @@ class SteeringOdometry
107
107
* \brief Updates the odometry class with latest wheels position
108
108
* \param right_traction_wheel_vel Right traction wheel velocity [rad/s]
109
109
* \param left_traction_wheel_vel Left traction wheel velocity [rad/s]
110
- * \param front_steer_pos Steer wheel position [rad]
110
+ * \param steer_pos Steer wheel position [rad]
111
111
* \param dt time difference to last call
112
112
* \return true if the odometry is actually updated
113
113
*/
@@ -130,11 +130,11 @@ class SteeringOdometry
130
130
131
131
/* *
132
132
* \brief Updates the odometry class with latest velocity command
133
- * \param linear Linear velocity [m/s]
134
- * \param angular Angular velocity [rad/s]
135
- * \param time Current time
133
+ * \param v_bx Linear velocity [m/s]
134
+ * \param omega_bz Angular velocity [rad/s]
135
+ * \param dt time difference to last call
136
136
*/
137
- void update_open_loop (const double linear , const double angular , const double dt);
137
+ void update_open_loop (const double v_bx , const double omega_bz , const double dt);
138
138
139
139
/* *
140
140
* \brief Set odometry type
@@ -175,22 +175,23 @@ class SteeringOdometry
175
175
/* *
176
176
* \brief Sets the wheel parameters: radius, separation and wheelbase
177
177
*/
178
- void set_wheel_params (double wheel_radius, double wheelbase = 0.0 , double wheel_track = 0.0 );
178
+ void set_wheel_params (
179
+ const double wheel_radius, const double wheelbase = 0.0 , const double wheel_track = 0.0 );
179
180
180
181
/* *
181
182
* \brief Velocity rolling window size setter
182
183
* \param velocity_rolling_window_size Velocity rolling window size
183
184
*/
184
- void set_velocity_rolling_window_size (size_t velocity_rolling_window_size);
185
+ void set_velocity_rolling_window_size (const size_t velocity_rolling_window_size);
185
186
186
187
/* *
187
188
* \brief Calculates inverse kinematics for the desired linear and angular velocities
188
- * \param Vx Desired linear velocity [m/s]
189
- * \param theta_dot Desired angular velocity [rad/s]
189
+ * \param v_bx Desired linear velocity of the robot in x_b-axis direction
190
+ * \param omega_bz Desired angular velocity of the robot around x_z-axis
190
191
* \return Tuple of velocity commands and steering commands
191
192
*/
192
193
std::tuple<std::vector<double >, std::vector<double >> get_commands (
193
- const double Vx , const double theta_dot );
194
+ const double v_bx , const double omega_bz );
194
195
195
196
/* *
196
197
* \brief Reset poses, heading, and accumulators
@@ -199,35 +200,35 @@ class SteeringOdometry
199
200
200
201
private:
201
202
/* *
202
- * \brief Uses precomputed linear and angular velocities to compute dometry and update
203
- * accumulators \param linear Linear velocity [m] (linear displacement, i.e. m/s * dt)
204
- * computed by previous odometry method \param angular Angular velocity [rad] (angular
205
- * displacement, i.e. m/s * dt) computed by previous odometry method
203
+ * \brief Uses precomputed linear and angular velocities to compute odometry
204
+ * \param v_bx Linear velocity [m/s]
205
+ * \param omega_bz Angular velocity [rad/s]
206
+ * \param dt time difference to last call
206
207
*/
207
- bool update_odometry (const double linear_velocity , const double angular , const double dt);
208
+ bool update_odometry (const double v_bx , const double omega_bz , const double dt);
208
209
209
210
/* *
210
211
* \brief Integrates the velocities (linear and angular) using 2nd order Runge-Kutta
211
- * \param linear Linear velocity [m] (linear displacement, i.e. m/s * dt) computed by
212
- * encoders \param angular Angular velocity [rad] (angular displacement, i.e. m/s * dt) computed
213
- * by encoders
212
+ * \param v_bx Linear velocity [m/s]
213
+ * \param omega_bz Angular velocity [rad/s]
214
+ * \param dt time difference to last call
214
215
*/
215
- void integrate_runge_kutta_2 (double linear, double angular );
216
+ void integrate_runge_kutta_2 (const double v_bx, const double omega_bz, const double dt );
216
217
217
218
/* *
218
- * \brief Integrates the velocities (linear and angular) using exact method
219
- * \param linear Linear velocity [m] (linear displacement, i.e. m/s * dt) computed by
220
- * encoders \param angular Angular velocity [rad] (angular displacement, i.e. m/s * dt) computed
221
- * by encoders
219
+ * \brief Integrates the velocities (linear and angular)
220
+ * \param v_bx Linear velocity [m/s]
221
+ * \param omega_bz Angular velocity [rad/s]
222
+ * \param dt time difference to last call
222
223
*/
223
- void integrate_exact ( double linear, double angular );
224
+ void integrate_fk ( const double v_bx, const double omega_bz, const double dt );
224
225
225
226
/* *
226
- * \brief Calculates steering angle from the desired translational and rotational velocity
227
- * \param Vx Linear velocity [m]
228
- * \param theta_dot Angular velocity [rad]
227
+ * \brief Calculates steering angle from the desired twist
228
+ * \param v_bx Linear velocity of the robot in x_b-axis direction
229
+ * \param omega_bz Angular velocity of the robot around x_z-axis
229
230
*/
230
- double convert_trans_rot_vel_to_steering_angle ( double Vx, double theta_dot );
231
+ double convert_twist_to_steering_angle ( const double v_bx, const double omega_bz );
231
232
232
233
/* *
233
234
* \brief Reset linear and angular accumulators
0 commit comments