ros2_control - rolling
|
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) More...
#include <steering_odometry.hpp>
Public Member Functions | |
SteeringOdometry (size_t velocity_rolling_window_size=10) | |
Constructor Timestamp will get the current time value Value will be set to zero. More... | |
void | init (const rclcpp::Time &time) |
Initialize the odometry. More... | |
bool | update_from_position (const double traction_wheel_pos, const double steer_pos, const double dt) |
Updates the odometry class with latest wheels position. More... | |
bool | update_from_position (const double right_traction_wheel_pos, const double left_traction_wheel_pos, const double steer_pos, const double dt) |
Updates the odometry class with latest wheels position. More... | |
bool | update_from_position (const double right_traction_wheel_pos, const double left_traction_wheel_pos, const double right_steer_pos, const double left_steer_pos, const double dt) |
Updates the odometry class with latest wheels position. More... | |
bool | update_from_velocity (const double traction_wheel_vel, const double steer_pos, const double dt) |
Updates the odometry class with latest wheels position. More... | |
bool | update_from_velocity (const double right_traction_wheel_vel, const double left_traction_wheel_vel, const double steer_pos, const double dt) |
Updates the odometry class with latest wheels position. More... | |
bool | update_from_velocity (const double right_traction_wheel_vel, const double left_traction_wheel_vel, const double right_steer_pos, const double left_steer_pos, const double dt) |
Updates the odometry class with latest wheels position. More... | |
void | update_open_loop (const double v_bx, const double omega_bz, const double dt) |
Updates the odometry class with latest velocity command. More... | |
void | set_odometry_type (const unsigned int type) |
Set odometry type. More... | |
double | get_heading () const |
heading getter More... | |
double | get_x () const |
x position getter More... | |
double | get_y () const |
y position getter More... | |
double | get_linear () const |
linear velocity getter More... | |
double | get_angular () const |
angular velocity getter More... | |
void | set_wheel_params (const double wheel_radius, const double wheelbase=0.0, const double wheel_track=0.0) |
Sets the wheel parameters: radius, separation and wheelbase. | |
void | set_velocity_rolling_window_size (const size_t velocity_rolling_window_size) |
Velocity rolling window size setter. More... | |
std::tuple< std::vector< double >, std::vector< double > > | get_commands (const double v_bx, const double omega_bz, const bool open_loop=true, const bool reduce_wheel_speed_until_steering_reached=false) |
Calculates inverse kinematics for the desired linear and angular velocities. More... | |
void | reset_odometry () |
Reset poses, heading, and accumulators. | |
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
|
explicit |
Constructor Timestamp will get the current time value Value will be set to zero.
velocity_rolling_window_size | Rolling window size used to compute the velocity mean |
|
inline |
angular velocity getter
std::tuple< std::vector< double >, std::vector< double > > steering_odometry::SteeringOdometry::get_commands | ( | const double | v_bx, |
const double | omega_bz, | ||
const bool | open_loop = true , |
||
const bool | reduce_wheel_speed_until_steering_reached = false |
||
) |
Calculates inverse kinematics for the desired linear and angular velocities.
v_bx | Desired linear velocity of the robot in x_b-axis direction |
omega_bz | Desired angular velocity of the robot around x_z-axis |
open_loop | If false, the IK will be calculated using measured steering angle |
reduce_wheel_speed_until_steering_reached | Reduce wheel speed until the steering angle has been reached |
|
inline |
heading getter
|
inline |
linear velocity getter
|
inline |
x position getter
|
inline |
y position getter
void steering_odometry::SteeringOdometry::init | ( | const rclcpp::Time & | time | ) |
Initialize the odometry.
time | Current time |
void steering_odometry::SteeringOdometry::set_odometry_type | ( | const unsigned int | type | ) |
Set odometry type.
type | odometry type |
void steering_odometry::SteeringOdometry::set_velocity_rolling_window_size | ( | const size_t | velocity_rolling_window_size | ) |
Velocity rolling window size setter.
velocity_rolling_window_size | Velocity rolling window size |
bool steering_odometry::SteeringOdometry::update_from_position | ( | const double | right_traction_wheel_pos, |
const double | left_traction_wheel_pos, | ||
const double | right_steer_pos, | ||
const double | left_steer_pos, | ||
const double | dt | ||
) |
Updates the odometry class with latest wheels position.
right_traction_wheel_pos | Right traction wheel position [rad] |
left_traction_wheel_pos | Left traction wheel position [rad] |
right_steer_pos | Right steer wheel position [rad] |
left_steer_pos | Left steer wheel position [rad] |
dt | time difference to last call |
Update old position with current:
bool steering_odometry::SteeringOdometry::update_from_position | ( | const double | right_traction_wheel_pos, |
const double | left_traction_wheel_pos, | ||
const double | steer_pos, | ||
const double | dt | ||
) |
Updates the odometry class with latest wheels position.
right_traction_wheel_pos | Right traction wheel velocity [rad] |
left_traction_wheel_pos | Left traction wheel velocity [rad] |
steer_pos | Steer wheel position [rad] |
dt | time difference to last call |
Update old position with current:
bool steering_odometry::SteeringOdometry::update_from_position | ( | const double | traction_wheel_pos, |
const double | steer_pos, | ||
const double | dt | ||
) |
Updates the odometry class with latest wheels position.
traction_wheel_pos | traction wheel position [rad] |
steer_pos | Steer wheel position [rad] |
dt | time difference to last call |
Update old position with current:
bool steering_odometry::SteeringOdometry::update_from_velocity | ( | const double | right_traction_wheel_vel, |
const double | left_traction_wheel_vel, | ||
const double | right_steer_pos, | ||
const double | left_steer_pos, | ||
const double | dt | ||
) |
Updates the odometry class with latest wheels position.
right_traction_wheel_vel | Right traction wheel velocity [rad/s] |
left_traction_wheel_vel | Left traction wheel velocity [rad/s] |
right_steer_pos | Right steer wheel position [rad] |
left_steer_pos | Left steer wheel position [rad] |
dt | time difference to last call |
bool steering_odometry::SteeringOdometry::update_from_velocity | ( | const double | right_traction_wheel_vel, |
const double | left_traction_wheel_vel, | ||
const double | steer_pos, | ||
const double | dt | ||
) |
Updates the odometry class with latest wheels position.
right_traction_wheel_vel | Right traction wheel velocity [rad/s] |
left_traction_wheel_vel | Left traction wheel velocity [rad/s] |
steer_pos | Steer wheel position [rad] |
dt | time difference to last call |
bool steering_odometry::SteeringOdometry::update_from_velocity | ( | const double | traction_wheel_vel, |
const double | steer_pos, | ||
const double | dt | ||
) |
Updates the odometry class with latest wheels position.
traction_wheel_vel | Traction wheel velocity [rad/s] |
steer_pos | Steer wheel position [rad] |
dt | time difference to last call |
void steering_odometry::SteeringOdometry::update_open_loop | ( | const double | v_bx, |
const double | omega_bz, | ||
const double | dt | ||
) |
Updates the odometry class with latest velocity command.
v_bx | Linear velocity [m/s] |
omega_bz | Angular velocity [rad/s] |
dt | time difference to last call |
Save last linear and angular velocity:
Integrate odometry: