Class SteeringOdometry

Class Documentation

class SteeringOdometry

Deprecated Odometry class for backward ABI compatibility. Internally calling steering_kinematics::SteeringKinematics.

Public Functions

explicit SteeringOdometry(size_t velocity_rolling_window_size = 10)
void init(const rclcpp::Time &time)
bool update_from_position(const double traction_wheel_pos, const double steer_pos, const double dt)
bool update_from_position(const double right_traction_wheel_pos, const double left_traction_wheel_pos, const double steer_pos, const double dt)
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)
bool update_from_velocity(const double traction_wheel_vel, const double steer_pos, const double dt)
bool update_from_velocity(const double right_traction_wheel_vel, const double left_traction_wheel_vel, const double steer_pos, const double dt)
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)
void update_open_loop(const double v_bx, const double omega_bz, const double dt)
void set_odometry_type(const unsigned int type)
unsigned int get_odometry_type() const
double get_heading() const
double get_x() const
double get_y() const
double get_linear() const
double get_angular() const
void set_wheel_params(const double wheel_radius, const double wheel_base, const double wheel_track)
void set_wheel_params(const double wheel_radius, const double wheel_base, const double wheel_track_steering, const double wheel_track_traction)
void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size)
std::tuple<std::vector<double>, std::vector<double>> get_commands(double v_bx, double omega_bz, bool open_loop = true, bool reduce_wheel_speed_until_steering_reached = false)
void reset_odometry()