diff --git a/ackermann_steering_controller/src/ackermann_steering_controller.cpp b/ackermann_steering_controller/src/ackermann_steering_controller.cpp index 326f05a579..eccfeb3977 100644 --- a/ackermann_steering_controller/src/ackermann_steering_controller.cpp +++ b/ackermann_steering_controller/src/ackermann_steering_controller.cpp @@ -45,7 +45,7 @@ controller_interface::CallbackReturn AckermannSteeringController::configure_odom odometry_.set_wheel_params( traction_wheels_radius, wheelbase, steering_track_width, traction_track_width); - odometry_.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odometry_.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); set_interface_numbers(NR_STATE_ITFS, NR_CMD_ITFS, NR_REF_ITFS); diff --git a/bicycle_steering_controller/src/bicycle_steering_controller.cpp b/bicycle_steering_controller/src/bicycle_steering_controller.cpp index b10ec445b7..8d114c8aeb 100644 --- a/bicycle_steering_controller/src/bicycle_steering_controller.cpp +++ b/bicycle_steering_controller/src/bicycle_steering_controller.cpp @@ -35,7 +35,7 @@ controller_interface::CallbackReturn BicycleSteeringController::configure_odomet const double traction_wheel_radius = bicycle_params_.traction_wheel_radius; odometry_.set_wheel_params(traction_wheel_radius, wheelbase); - odometry_.set_odometry_type(steering_odometry::BICYCLE_CONFIG); + odometry_.set_odometry_type(steering_kinematics::BICYCLE_CONFIG); set_interface_numbers(NR_STATE_ITFS, NR_CMD_ITFS, NR_REF_ITFS); diff --git a/steering_controllers_library/CMakeLists.txt b/steering_controllers_library/CMakeLists.txt index d57b00d278..aa06d481a0 100644 --- a/steering_controllers_library/CMakeLists.txt +++ b/steering_controllers_library/CMakeLists.txt @@ -39,6 +39,7 @@ add_library( steering_controllers_library SHARED src/steering_controllers_library.cpp + src/steering_kinematics.cpp src/steering_odometry.cpp ) target_compile_features(steering_controllers_library PUBLIC cxx_std_17) diff --git a/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp b/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp index 6deabe8237..b5a670b480 100644 --- a/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp +++ b/steering_controllers_library/include/steering_controllers_library/steering_controllers_library.hpp @@ -33,7 +33,7 @@ #include "tf2_msgs/msg/tf_message.hpp" #include "steering_controllers_library/steering_controllers_library_parameters.hpp" -#include "steering_controllers_library/steering_odometry.hpp" +#include "steering_controllers_library/steering_kinematics.hpp" namespace steering_controllers_library { @@ -106,7 +106,7 @@ class SteeringControllersLibrary : public controller_interface::ChainableControl bool on_set_chained_mode(bool chained_mode) override; /// Odometry: - steering_odometry::SteeringOdometry odometry_; + steering_kinematics::SteeringKinematics odometry_; SteeringControllerStateMsg published_state_; diff --git a/steering_controllers_library/include/steering_controllers_library/steering_kinematics.hpp b/steering_controllers_library/include/steering_controllers_library/steering_kinematics.hpp new file mode 100644 index 0000000000..5021f7342f --- /dev/null +++ b/steering_controllers_library/include/steering_controllers_library/steering_kinematics.hpp @@ -0,0 +1,308 @@ +// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt) +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: dr. sc. Tomislav Petkovic, Dr. Ing. Denis Štogl +// + +#ifndef STEERING_CONTROLLERS_LIBRARY__STEERING_KINEMATICS_HPP_ +#define STEERING_CONTROLLERS_LIBRARY__STEERING_KINEMATICS_HPP_ + +#include +#include +#include + +#include + +// \note The versions conditioning is added here to support the source-compatibility with Humble +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 +#include "rcpputils/rolling_mean_accumulator.hpp" +#else +#include "rcppmath/rolling_mean_accumulator.hpp" +#endif + +namespace steering_kinematics +{ +const unsigned int BICYCLE_CONFIG = 0; +const unsigned int TRICYCLE_CONFIG = 1; +const unsigned int ACKERMANN_CONFIG = 2; + +inline bool is_close_to_zero(double val) { return std::fabs(val) < 1e-6; } + +/** + * \brief The SteeringKinematics class handles forward kinematics (odometry calculations) and + * inverse kinematics (getting commands) (2D pose and velocity with related timestamp) + */ +class SteeringKinematics +{ +public: + /** + * \brief Constructor + * Timestamp will get the current time value + * Value will be set to zero + * \param velocity_rolling_window_size Rolling window size used to compute the velocity mean + * + */ + explicit SteeringKinematics(size_t velocity_rolling_window_size = 10); + + /** + * \brief Initialize the SteeringKinematics class + * \param time Current time + */ + void init(const rclcpp::Time & time); + + /** + * \brief Updates the SteeringKinematics class with latest wheels position + * \param traction_wheel_pos traction wheel position [rad] + * \param steer_pos Steer wheel position [rad] + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ + bool update_from_position( + const double traction_wheel_pos, const double steer_pos, const double dt); + + /** + * \brief Updates the SteeringKinematics class with latest wheels position + * \param right_traction_wheel_pos Right traction wheel velocity [rad] + * \param left_traction_wheel_pos Left traction wheel velocity [rad] + * \param steer_pos Steer wheel position [rad] + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ + bool update_from_position( + const double right_traction_wheel_pos, const double left_traction_wheel_pos, + const double steer_pos, const double dt); + + /** + * \brief Updates the SteeringKinematics class with latest wheels position + * \param right_traction_wheel_pos Right traction wheel position [rad] + * \param left_traction_wheel_pos Left traction wheel position [rad] + * \param right_steer_pos Right steer wheel position [rad] + * \param left_steer_pos Left steer wheel position [rad] + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ + 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); + + /** + * \brief Updates the SteeringKinematics class with latest wheels position + * \param traction_wheel_vel Traction wheel velocity [rad/s] + * \param steer_pos Steer wheel position [rad] + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ + bool update_from_velocity( + const double traction_wheel_vel, const double steer_pos, const double dt); + + /** + * \brief Updates the SteeringKinematics class with latest wheels position + * \param right_traction_wheel_vel Right traction wheel velocity [rad/s] + * \param left_traction_wheel_vel Left traction wheel velocity [rad/s] + * \param steer_pos Steer wheel position [rad] + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ + bool update_from_velocity( + const double right_traction_wheel_vel, const double left_traction_wheel_vel, + const double steer_pos, const double dt); + + /** + * \brief Updates the SteeringKinematics class with latest wheels position + * \param right_traction_wheel_vel Right traction wheel velocity [rad/s] + * \param left_traction_wheel_vel Left traction wheel velocity [rad/s] + * \param right_steer_pos Right steer wheel position [rad] + * \param left_steer_pos Left steer wheel position [rad] + * \param dt time difference to last call + * \return true if the odometry is actually updated + */ + 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); + + /** + * \brief Updates the SteeringKinematics class with latest velocity command + * \param v_bx Linear velocity [m/s] + * \param omega_bz Angular velocity [rad/s] + * \param dt time difference to last call + */ + void update_open_loop(const double v_bx, const double omega_bz, const double dt); + + /** + * \brief Set odometry type + * \param type odometry type + */ + void set_odometry_type(const unsigned int type); + + /** + * \brief Get odometry type + * \return odometry type + */ + unsigned int get_odometry_type() const { return static_cast(config_type_); } + + /** + * \brief heading getter + * \return heading [rad] + */ + double get_heading() const { return heading_; } + + /** + * \brief x position getter + * \return x position [m] + */ + double get_x() const { return x_; } + + /** + * \brief y position getter + * \return y position [m] + */ + double get_y() const { return y_; } + + /** + * \brief linear velocity getter + * \return linear velocity [m/s] + */ + double get_linear() const { return linear_; } + + /** + * \brief angular velocity getter + * \return angular velocity [rad/s] + */ + double get_angular() const { return angular_; } + + /** + * \brief Sets the wheel parameters: radius, wheel_base, and wheel_track + */ + void set_wheel_params( + const double wheel_radius, const double wheel_base = 0.0, const double wheel_track = 0.0); + + /** + * \brief Sets the wheel parameters: radius, wheel_base, and wheel_track for steering and traction + */ + void set_wheel_params( + const double wheel_radius, const double wheel_base, const double wheel_track_steering, + const double wheel_track_traction); + + /** + * \brief Velocity rolling window size setter + * \param velocity_rolling_window_size Velocity rolling window size + */ + void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size); + + /** + * \brief Calculates inverse kinematics for the desired linear and angular velocities + * \param v_bx Desired linear velocity of the robot in x_b-axis direction + * \param omega_bz Desired angular velocity of the robot around x_z-axis + * \param open_loop If false, the IK will be calculated using measured steering angle + * \param reduce_wheel_speed_until_steering_reached Reduce wheel speed until the steering angle + * has been reached + * \return Tuple of velocity commands and steering commands + */ + std::tuple, std::vector> get_commands( + const double v_bx, const double omega_bz, const bool open_loop = true, + const bool reduce_wheel_speed_until_steering_reached = false); + + /** + * \brief Reset poses, heading, and accumulators + */ + void reset_odometry(); + +private: + /** + * \brief Uses precomputed linear and angular velocities to compute odometry + * \param v_bx Linear velocity [m/s] + * \param omega_bz Angular velocity [rad/s] + * \param dt time difference to last call + */ + bool update_odometry(const double v_bx, const double omega_bz, const double dt); + + /** + * \brief Integrates the velocities (linear and angular) using 2nd order Runge-Kutta + * \param v_bx Linear velocity [m/s] + * \param omega_bz Angular velocity [rad/s] + * \param dt time difference to last call + */ + void integrate_runge_kutta_2(const double v_bx, const double omega_bz, const double dt); + + /** + * \brief Integrates the velocities (linear and angular) + * \param v_bx Linear velocity [m/s] + * \param omega_bz Angular velocity [rad/s] + * \param dt time difference to last call + */ + void integrate_fk(const double v_bx, const double omega_bz, const double dt); + + /** + * \brief Calculates steering angle from the desired twist + * \param v_bx Linear velocity of the robot in x_b-axis direction + * \param omega_bz Angular velocity of the robot around x_z-axis + */ + double convert_twist_to_steering_angle(const double v_bx, const double omega_bz); + + /** + * \brief Calculates linear velocity of a robot with double traction axle + * \param right_traction_wheel_vel Right traction wheel velocity [rad/s] + * \param left_traction_wheel_vel Left traction wheel velocity [rad/s] + * \param steer_pos Steer wheel position [rad] + */ + double get_linear_velocity_double_traction_axle( + const double right_traction_wheel_vel, const double left_traction_wheel_vel, + const double steer_pos); + + /** + * \brief Reset linear and angular accumulators + */ + void reset_accumulators(); + +// \note The versions conditioning is added here to support the source-compatibility with Humble +#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 + using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator; +#else + using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator; +#endif + + /// Current timestamp: + rclcpp::Time timestamp_; + + /// Current pose: + double x_; // [m] + double y_; // [m] + double steer_pos_; // [rad] + double heading_; // [rad] + + /// Current velocity: + double linear_; // [m/s] + double angular_; // [rad/s] + + /// Kinematic parameters + double wheel_track_traction_; // [m] + double wheel_track_steering_; // [m] + double wheel_base_; // [m] + double wheel_radius_; // [m] + + /// Configuration type used for the forward kinematics + int config_type_ = -1; + + /// Previous wheel position/state [rad]: + double traction_wheel_old_pos_; + double traction_right_wheel_old_pos_; + double traction_left_wheel_old_pos_; + /// Rolling mean accumulators for the linear and angular velocities: + size_t velocity_rolling_window_size_; + RollingMeanAccumulator linear_acc_; + RollingMeanAccumulator angular_acc_; +}; +} // namespace steering_kinematics + +#endif // STEERING_CONTROLLERS_LIBRARY__STEERING_KINEMATICS_HPP_ diff --git a/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp b/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp index 7b243e795c..9fa95dd45e 100644 --- a/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp +++ b/steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp @@ -18,6 +18,16 @@ #ifndef STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_ #define STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_ +#ifdef _WIN32 +#pragma message( \ + "This header is deprecated. Please update your code to use 'steering_kinematics.hpp' header.") // NOLINT +#else +#warning \ + "This header is deprecated. Please update your code to use 'steering_kinematics.hpp' header." //NOLINT +#endif + +#include "steering_controllers_library/steering_kinematics.hpp" + #include #include #include @@ -33,275 +43,81 @@ namespace steering_odometry { -const unsigned int BICYCLE_CONFIG = 0; -const unsigned int TRICYCLE_CONFIG = 1; -const unsigned int ACKERMANN_CONFIG = 2; +[[deprecated("Use steering_kinematics::BICYCLE_CONFIG")]] const unsigned int BICYCLE_CONFIG = + steering_kinematics::BICYCLE_CONFIG; +[[deprecated("Use steering_kinematics::TRICYCLE_CONFIG")]] const unsigned int TRICYCLE_CONFIG = + steering_kinematics::TRICYCLE_CONFIG; +[[deprecated("Use steering_kinematics::ACKERMANN_CONFIG")]] const unsigned int ACKERMANN_CONFIG = + steering_kinematics::ACKERMANN_CONFIG; -inline bool is_close_to_zero(double val) { return std::fabs(val) < 1e-6; } +inline bool is_close_to_zero(double val) { return steering_kinematics::is_close_to_zero(val); } /** - * \brief The Odometry class handles odometry readings - * (2D pose and velocity with related timestamp) + * \brief Deprecated Odometry class for backward ABI compatibility. + * Internally calling steering_kinematics::SteeringKinematics */ -class SteeringOdometry + +class [[deprecated("Use steering_kinematics::SteeringKinematics instead")]] SteeringOdometry { public: - /** - * \brief Constructor - * Timestamp will get the current time value - * Value will be set to zero - * \param velocity_rolling_window_size Rolling window size used to compute the velocity mean - * - */ explicit SteeringOdometry(size_t velocity_rolling_window_size = 10); - /** - * \brief Initialize the odometry - * \param time Current time - */ void init(const rclcpp::Time & time); - /** - * \brief Updates the odometry class with latest wheels position - * \param traction_wheel_pos traction wheel position [rad] - * \param steer_pos Steer wheel position [rad] - * \param dt time difference to last call - * \return true if the odometry is actually updated - */ bool update_from_position( const double traction_wheel_pos, const double steer_pos, const double dt); - /** - * \brief Updates the odometry class with latest wheels position - * \param right_traction_wheel_pos Right traction wheel velocity [rad] - * \param left_traction_wheel_pos Left traction wheel velocity [rad] - * \param steer_pos Steer wheel position [rad] - * \param dt time difference to last call - * \return true if the odometry is actually updated - */ bool update_from_position( const double right_traction_wheel_pos, const double left_traction_wheel_pos, const double steer_pos, const double dt); - /** - * \brief Updates the odometry class with latest wheels position - * \param right_traction_wheel_pos Right traction wheel position [rad] - * \param left_traction_wheel_pos Left traction wheel position [rad] - * \param right_steer_pos Right steer wheel position [rad] - * \param left_steer_pos Left steer wheel position [rad] - * \param dt time difference to last call - * \return true if the odometry is actually updated - */ 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); - /** - * \brief Updates the odometry class with latest wheels position - * \param traction_wheel_vel Traction wheel velocity [rad/s] - * \param steer_pos Steer wheel position [rad] - * \param dt time difference to last call - * \return true if the odometry is actually updated - */ bool update_from_velocity( const double traction_wheel_vel, const double steer_pos, const double dt); - /** - * \brief Updates the odometry class with latest wheels position - * \param right_traction_wheel_vel Right traction wheel velocity [rad/s] - * \param left_traction_wheel_vel Left traction wheel velocity [rad/s] - * \param steer_pos Steer wheel position [rad] - * \param dt time difference to last call - * \return true if the odometry is actually updated - */ bool update_from_velocity( const double right_traction_wheel_vel, const double left_traction_wheel_vel, const double steer_pos, const double dt); - /** - * \brief Updates the odometry class with latest wheels position - * \param right_traction_wheel_vel Right traction wheel velocity [rad/s] - * \param left_traction_wheel_vel Left traction wheel velocity [rad/s] - * \param right_steer_pos Right steer wheel position [rad] - * \param left_steer_pos Left steer wheel position [rad] - * \param dt time difference to last call - * \return true if the odometry is actually updated - */ 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); - /** - * \brief Updates the odometry class with latest velocity command - * \param v_bx Linear velocity [m/s] - * \param omega_bz Angular velocity [rad/s] - * \param dt time difference to last call - */ void update_open_loop(const double v_bx, const double omega_bz, const double dt); - /** - * \brief Set odometry type - * \param type odometry type - */ void set_odometry_type(const unsigned int type); - /** - * \brief Get odometry type - * \return odometry type - */ - unsigned int get_odometry_type() const { return static_cast(config_type_); } - - /** - * \brief heading getter - * \return heading [rad] - */ - double get_heading() const { return heading_; } + unsigned int get_odometry_type() const; + double get_heading() const; - /** - * \brief x position getter - * \return x position [m] - */ - double get_x() const { return x_; } + double get_x() const; - /** - * \brief y position getter - * \return y position [m] - */ - double get_y() const { return y_; } + double get_y() const; - /** - * \brief linear velocity getter - * \return linear velocity [m/s] - */ - double get_linear() const { return linear_; } + double get_linear() const; - /** - * \brief angular velocity getter - * \return angular velocity [rad/s] - */ - double get_angular() const { return angular_; } + double get_angular() const; - /** - * \brief Sets the wheel parameters: radius, wheel_base, and wheel_track - */ void set_wheel_params( - const double wheel_radius, const double wheel_base = 0.0, const double wheel_track = 0.0); + const double wheel_radius, const double wheel_base, const double wheel_track); - /** - * \brief Sets the wheel parameters: radius, wheel_base, and wheel_track for steering and traction - */ void set_wheel_params( const double wheel_radius, const double wheel_base, const double wheel_track_steering, const double wheel_track_traction); - /** - * \brief Velocity rolling window size setter - * \param velocity_rolling_window_size Velocity rolling window size - */ void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size); - /** - * \brief Calculates inverse kinematics for the desired linear and angular velocities - * \param v_bx Desired linear velocity of the robot in x_b-axis direction - * \param omega_bz Desired angular velocity of the robot around x_z-axis - * \param open_loop If false, the IK will be calculated using measured steering angle - * \param reduce_wheel_speed_until_steering_reached Reduce wheel speed until the steering angle - * has been reached - * \return Tuple of velocity commands and steering commands - */ std::tuple, std::vector> get_commands( - const double v_bx, const double omega_bz, const bool open_loop = true, - const bool reduce_wheel_speed_until_steering_reached = false); + double v_bx, double omega_bz, bool open_loop = true, + bool reduce_wheel_speed_until_steering_reached = false); - /** - * \brief Reset poses, heading, and accumulators - */ void reset_odometry(); private: - /** - * \brief Uses precomputed linear and angular velocities to compute odometry - * \param v_bx Linear velocity [m/s] - * \param omega_bz Angular velocity [rad/s] - * \param dt time difference to last call - */ - bool update_odometry(const double v_bx, const double omega_bz, const double dt); - - /** - * \brief Integrates the velocities (linear and angular) using 2nd order Runge-Kutta - * \param v_bx Linear velocity [m/s] - * \param omega_bz Angular velocity [rad/s] - * \param dt time difference to last call - */ - void integrate_runge_kutta_2(const double v_bx, const double omega_bz, const double dt); - - /** - * \brief Integrates the velocities (linear and angular) - * \param v_bx Linear velocity [m/s] - * \param omega_bz Angular velocity [rad/s] - * \param dt time difference to last call - */ - void integrate_fk(const double v_bx, const double omega_bz, const double dt); - - /** - * \brief Calculates steering angle from the desired twist - * \param v_bx Linear velocity of the robot in x_b-axis direction - * \param omega_bz Angular velocity of the robot around x_z-axis - */ - double convert_twist_to_steering_angle(const double v_bx, const double omega_bz); - - /** - * \brief Calculates linear velocity of a robot with double traction axle - * \param right_traction_wheel_vel Right traction wheel velocity [rad/s] - * \param left_traction_wheel_vel Left traction wheel velocity [rad/s] - * \param steer_pos Steer wheel position [rad] - */ - double get_linear_velocity_double_traction_axle( - const double right_traction_wheel_vel, const double left_traction_wheel_vel, - const double steer_pos); - - /** - * \brief Reset linear and angular accumulators - */ - void reset_accumulators(); - -// \note The versions conditioning is added here to support the source-compatibility with Humble -#if RCPPUTILS_VERSION_MAJOR >= 2 && RCPPUTILS_VERSION_MINOR >= 6 - using RollingMeanAccumulator = rcpputils::RollingMeanAccumulator; -#else - using RollingMeanAccumulator = rcppmath::RollingMeanAccumulator; -#endif - - /// Current timestamp: - rclcpp::Time timestamp_; - - /// Current pose: - double x_; // [m] - double y_; // [m] - double steer_pos_; // [rad] - double heading_; // [rad] - - /// Current velocity: - double linear_; // [m/s] - double angular_; // [rad/s] - - /// Kinematic parameters - double wheel_track_traction_; // [m] - double wheel_track_steering_; // [m] - double wheel_base_; // [m] - double wheel_radius_; // [m] - - /// Configuration type used for the forward kinematics - int config_type_ = -1; - - /// Previous wheel position/state [rad]: - double traction_wheel_old_pos_; - double traction_right_wheel_old_pos_; - double traction_left_wheel_old_pos_; - /// Rolling mean accumulators for the linear and angular velocities: - size_t velocity_rolling_window_size_; - RollingMeanAccumulator linear_acc_; - RollingMeanAccumulator angular_acc_; + steering_kinematics::SteeringKinematics sk_impl_; }; } // namespace steering_odometry diff --git a/steering_controllers_library/src/steering_controllers_library.cpp b/steering_controllers_library/src/steering_controllers_library.cpp index dd57971f30..38e201623e 100644 --- a/steering_controllers_library/src/steering_controllers_library.cpp +++ b/steering_controllers_library/src/steering_controllers_library.cpp @@ -85,7 +85,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( configure_odometry(); // Check if the number of traction joints is correct - if (odometry_.get_odometry_type() == steering_odometry::BICYCLE_CONFIG) + if (odometry_.get_odometry_type() == steering_kinematics::BICYCLE_CONFIG) { if (params_.traction_joints_names.size() != 1) { @@ -96,7 +96,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( return controller_interface::CallbackReturn::ERROR; } } - else if (odometry_.get_odometry_type() == steering_odometry::TRICYCLE_CONFIG) + else if (odometry_.get_odometry_type() == steering_kinematics::TRICYCLE_CONFIG) { if (params_.traction_joints_names.size() != 2) { @@ -107,7 +107,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( return controller_interface::CallbackReturn::ERROR; } } - else if (odometry_.get_odometry_type() == steering_odometry::ACKERMANN_CONFIG) + else if (odometry_.get_odometry_type() == steering_kinematics::ACKERMANN_CONFIG) { if (params_.traction_joints_names.size() != 2) { @@ -119,7 +119,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( } } // Check if the number of steering joints is correct - if (odometry_.get_odometry_type() == steering_odometry::BICYCLE_CONFIG) + if (odometry_.get_odometry_type() == steering_kinematics::BICYCLE_CONFIG) { if (params_.steering_joints_names.size() != 1) { @@ -130,7 +130,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( return controller_interface::CallbackReturn::ERROR; } } - else if (odometry_.get_odometry_type() == steering_odometry::TRICYCLE_CONFIG) + else if (odometry_.get_odometry_type() == steering_kinematics::TRICYCLE_CONFIG) { if (params_.steering_joints_names.size() != 1) { @@ -141,7 +141,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( return controller_interface::CallbackReturn::ERROR; } } - else if (odometry_.get_odometry_type() == steering_odometry::ACKERMANN_CONFIG) + else if (odometry_.get_odometry_type() == steering_kinematics::ACKERMANN_CONFIG) { if (params_.steering_joints_names.size() != 2) { @@ -158,7 +158,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( if (!params_.traction_joints_state_names.empty()) { - if (odometry_.get_odometry_type() == steering_odometry::BICYCLE_CONFIG) + if (odometry_.get_odometry_type() == steering_kinematics::BICYCLE_CONFIG) { if (params_.traction_joints_state_names.size() != 1) { @@ -170,7 +170,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( return controller_interface::CallbackReturn::ERROR; } } - else if (odometry_.get_odometry_type() == steering_odometry::TRICYCLE_CONFIG) + else if (odometry_.get_odometry_type() == steering_kinematics::TRICYCLE_CONFIG) { if (params_.traction_joints_state_names.size() != 2) { @@ -182,7 +182,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( return controller_interface::CallbackReturn::ERROR; } } - else if (odometry_.get_odometry_type() == steering_odometry::ACKERMANN_CONFIG) + else if (odometry_.get_odometry_type() == steering_kinematics::ACKERMANN_CONFIG) { if (params_.traction_joints_state_names.size() != 2) { @@ -203,7 +203,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( if (!params_.steering_joints_state_names.empty()) { - if (odometry_.get_odometry_type() == steering_odometry::BICYCLE_CONFIG) + if (odometry_.get_odometry_type() == steering_kinematics::BICYCLE_CONFIG) { if (params_.steering_joints_state_names.size() != 1) { @@ -215,7 +215,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( return controller_interface::CallbackReturn::ERROR; } } - else if (odometry_.get_odometry_type() == steering_odometry::TRICYCLE_CONFIG) + else if (odometry_.get_odometry_type() == steering_kinematics::TRICYCLE_CONFIG) { if (params_.steering_joints_state_names.size() != 1) { @@ -227,7 +227,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_configure( return controller_interface::CallbackReturn::ERROR; } } - else if (odometry_.get_odometry_type() == steering_odometry::ACKERMANN_CONFIG) + else if (odometry_.get_odometry_type() == steering_kinematics::ACKERMANN_CONFIG) { if (params_.steering_joints_state_names.size() != 2) { diff --git a/steering_controllers_library/src/steering_kinematics.cpp b/steering_controllers_library/src/steering_kinematics.cpp new file mode 100644 index 0000000000..2d5e6640b6 --- /dev/null +++ b/steering_controllers_library/src/steering_kinematics.cpp @@ -0,0 +1,397 @@ +// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt) +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/* + * Author: dr. sc. Tomislav Petkovic + * Author: Dr. Ing. Denis Stogl + */ + +#define _USE_MATH_DEFINES + +#include "steering_controllers_library/steering_kinematics.hpp" + +#include +#include + +namespace steering_kinematics +{ +SteeringKinematics::SteeringKinematics(size_t velocity_rolling_window_size) +: timestamp_(0.0), + x_(0.0), + y_(0.0), + heading_(0.0), + linear_(0.0), + angular_(0.0), + wheel_track_traction_(0.0), + wheel_track_steering_(0.0), + wheel_base_(0.0), + wheel_radius_(0.0), + traction_wheel_old_pos_(0.0), + traction_right_wheel_old_pos_(0.0), + traction_left_wheel_old_pos_(0.0), + velocity_rolling_window_size_(velocity_rolling_window_size), + linear_acc_(velocity_rolling_window_size), + angular_acc_(velocity_rolling_window_size) +{ +} + +void SteeringKinematics::init(const rclcpp::Time & time) +{ + // Reset accumulators and timestamp: + reset_accumulators(); + timestamp_ = time; +} + +bool SteeringKinematics::update_odometry( + const double linear_velocity, const double angular_velocity, const double dt) +{ + /// Integrate odometry: + integrate_fk(linear_velocity, angular_velocity, dt); + + /// We cannot estimate the speed with very small time intervals: + if (dt < 0.0001) + { + return false; // Interval too small to integrate with + } + + /// Estimate speeds using a rolling mean to filter them out: + linear_acc_.accumulate(linear_velocity); + angular_acc_.accumulate(angular_velocity); + + linear_ = linear_acc_.getRollingMean(); + angular_ = angular_acc_.getRollingMean(); + + return true; +} + +bool SteeringKinematics::update_from_position( + const double traction_wheel_pos, const double steer_pos, const double dt) +{ + const double traction_wheel_est_pos_diff = traction_wheel_pos - traction_wheel_old_pos_; + + /// Update old position with current: + traction_wheel_old_pos_ = traction_wheel_pos; + + return update_from_velocity(traction_wheel_est_pos_diff / dt, steer_pos, dt); +} + +bool SteeringKinematics::update_from_position( + const double traction_right_wheel_pos, const double traction_left_wheel_pos, + const double steer_pos, const double dt) +{ + const double traction_right_wheel_est_pos_diff = + traction_right_wheel_pos - traction_right_wheel_old_pos_; + const double traction_left_wheel_est_pos_diff = + traction_left_wheel_pos - traction_left_wheel_old_pos_; + + /// Update old position with current: + traction_right_wheel_old_pos_ = traction_right_wheel_pos; + traction_left_wheel_old_pos_ = traction_left_wheel_pos; + + return update_from_velocity( + traction_right_wheel_est_pos_diff / dt, traction_left_wheel_est_pos_diff / dt, steer_pos, dt); +} + +bool SteeringKinematics::update_from_position( + const double traction_right_wheel_pos, const double traction_left_wheel_pos, + const double right_steer_pos, const double left_steer_pos, const double dt) +{ + const double traction_right_wheel_est_pos_diff = + traction_right_wheel_pos - traction_right_wheel_old_pos_; + const double traction_left_wheel_est_pos_diff = + traction_left_wheel_pos - traction_left_wheel_old_pos_; + + /// Update old position with current: + traction_right_wheel_old_pos_ = traction_right_wheel_pos; + traction_left_wheel_old_pos_ = traction_left_wheel_pos; + + return update_from_velocity( + traction_right_wheel_est_pos_diff / dt, traction_left_wheel_est_pos_diff / dt, right_steer_pos, + left_steer_pos, dt); +} + +bool SteeringKinematics::update_from_velocity( + const double traction_wheel_vel, const double steer_pos, const double dt) +{ + steer_pos_ = steer_pos; + double linear_velocity = traction_wheel_vel * wheel_radius_; + const double angular_velocity = std::tan(steer_pos) * linear_velocity / wheel_base_; + + return update_odometry(linear_velocity, angular_velocity, dt); +} + +double SteeringKinematics::get_linear_velocity_double_traction_axle( + const double right_traction_wheel_vel, const double left_traction_wheel_vel, + const double steer_pos) +{ + double turning_radius = wheel_base_ / std::tan(steer_pos); + const double vel_wheel_r = right_traction_wheel_vel * wheel_radius_; + const double vel_wheel_l = left_traction_wheel_vel * wheel_radius_; + + if (std::isinf(turning_radius)) + { + return (vel_wheel_r + vel_wheel_l) * 0.5; + } + + // overdetermined, we take the average + const double vel_r = + vel_wheel_r * turning_radius / (turning_radius + wheel_track_traction_ * 0.5); + const double vel_l = + vel_wheel_l * turning_radius / (turning_radius - wheel_track_traction_ * 0.5); + return (vel_r + vel_l) * 0.5; +} + +bool SteeringKinematics::update_from_velocity( + const double right_traction_wheel_vel, const double left_traction_wheel_vel, + const double steer_pos, const double dt) +{ + steer_pos_ = steer_pos; + double linear_velocity = get_linear_velocity_double_traction_axle( + right_traction_wheel_vel, left_traction_wheel_vel, steer_pos_); + + const double angular_velocity = std::tan(steer_pos_) * linear_velocity / wheel_base_; + + return update_odometry(linear_velocity, angular_velocity, dt); +} + +bool SteeringKinematics::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) +{ + // overdetermined, we take the average + const double right_steer_pos_est = std::atan( + wheel_base_ * std::tan(right_steer_pos) / + (wheel_base_ - wheel_track_steering_ / 2 * std::tan(right_steer_pos))); + const double left_steer_pos_est = std::atan( + wheel_base_ * std::tan(left_steer_pos) / + (wheel_base_ + wheel_track_steering_ / 2 * std::tan(left_steer_pos))); + steer_pos_ = (right_steer_pos_est + left_steer_pos_est) * 0.5; + + double linear_velocity = get_linear_velocity_double_traction_axle( + right_traction_wheel_vel, left_traction_wheel_vel, steer_pos_); + const double angular_velocity = std::tan(steer_pos_) * linear_velocity / wheel_base_; + + return update_odometry(linear_velocity, angular_velocity, dt); +} + +void SteeringKinematics::update_open_loop(const double v_bx, const double omega_bz, const double dt) +{ + /// Save last linear and angular velocity: + linear_ = v_bx; + angular_ = omega_bz; + + /// Integrate odometry: + integrate_fk(v_bx, omega_bz, dt); +} + +void SteeringKinematics::set_wheel_params( + double wheel_radius, double wheel_base, double wheel_track) +{ + wheel_radius_ = wheel_radius; + wheel_base_ = wheel_base; + wheel_track_traction_ = wheel_track; + wheel_track_steering_ = wheel_track; +} + +void SteeringKinematics::set_wheel_params( + double wheel_radius, double wheel_base, double wheel_track_steering, double wheel_track_traction) +{ + wheel_radius_ = wheel_radius; + wheel_base_ = wheel_base; + wheel_track_traction_ = wheel_track_traction; + wheel_track_steering_ = wheel_track_steering; +} + +void SteeringKinematics::set_velocity_rolling_window_size(size_t velocity_rolling_window_size) +{ + velocity_rolling_window_size_ = velocity_rolling_window_size; + + reset_accumulators(); +} + +void SteeringKinematics::set_odometry_type(const unsigned int type) +{ + config_type_ = static_cast(type); +} + +double SteeringKinematics::convert_twist_to_steering_angle(double v_bx, double omega_bz) +{ + // phi can be nan if both v_bx and omega_bz are zero + const auto phi = std::atan(omega_bz * wheel_base_ / v_bx); + return std::isfinite(phi) ? phi : 0.0; +} + +std::tuple, std::vector> SteeringKinematics::get_commands( + const double v_bx, const double omega_bz, const bool open_loop, + const bool reduce_wheel_speed_until_steering_reached) +{ + // desired wheel speed and steering angle of the middle of traction and steering axis + double Ws, phi, phi_IK = steer_pos_; + +#if 0 + if (v_bx == 0 && omega_bz != 0) + { + // TODO(anyone) this would be only possible if traction is on the steering axis + phi = omega_bz > 0 ? M_PI_2 : -M_PI_2; + Ws = abs(omega_bz) * wheelbase_ / wheel_radius_; + } + else + { + // TODO(anyone) this would be valid only if traction is on the steering axis + Ws = v_bx / (wheel_radius_ * std::cos(phi_IK)); // using the measured steering angle + } +#endif + // steering angle + phi = SteeringKinematics::convert_twist_to_steering_angle(v_bx, omega_bz); + if (open_loop) + { + phi_IK = phi; + } + // wheel speed + Ws = v_bx / wheel_radius_; + + if (!open_loop && reduce_wheel_speed_until_steering_reached) + { + // Reduce wheel speed until the target angle has been reached + double phi_delta = abs(steer_pos_ - phi); + double scale; + const double min_phi_delta = M_PI / 6.; + if (phi_delta < min_phi_delta) + { + scale = 1; + } + else if (phi_delta >= 1.5608) + { + // cos(1.5608) = 0.01 + scale = 0.01 / cos(min_phi_delta); + } + else + { + // TODO(anyone): find the best function, e.g convex power functions + scale = cos(phi_delta) / cos(min_phi_delta); + } + Ws *= scale; + } + + if (config_type_ == BICYCLE_CONFIG) + { + std::vector traction_commands = {Ws}; + std::vector steering_commands = {phi}; + return std::make_tuple(traction_commands, steering_commands); + } + else if (config_type_ == TRICYCLE_CONFIG) + { + std::vector traction_commands; + std::vector steering_commands; + // double-traction axle + if (is_close_to_zero(phi_IK)) + { + // avoid division by zero + traction_commands = {Ws, Ws}; + } + else + { + const double turning_radius = wheel_base_ / std::tan(phi_IK); + const double Wr = Ws * (turning_radius + wheel_track_traction_ * 0.5) / turning_radius; + const double Wl = Ws * (turning_radius - wheel_track_traction_ * 0.5) / turning_radius; + traction_commands = {Wr, Wl}; + } + // simple steering + steering_commands = {phi}; + return std::make_tuple(traction_commands, steering_commands); + } + else if (config_type_ == ACKERMANN_CONFIG) + { + std::vector traction_commands; + std::vector steering_commands; + if (is_close_to_zero(phi_IK)) + { + // avoid division by zero + traction_commands = {Ws, Ws}; + // shortcut, no steering + steering_commands = {phi, phi}; + } + else + { + const double turning_radius = wheel_base_ / std::tan(phi_IK); + const double Wr = Ws * (turning_radius + wheel_track_traction_ * 0.5) / turning_radius; + const double Wl = Ws * (turning_radius - wheel_track_traction_ * 0.5) / turning_radius; + traction_commands = {Wr, Wl}; + + const double numerator = 2 * wheel_base_ * std::sin(phi); + const double denominator_first_member = 2 * wheel_base_ * std::cos(phi); + const double denominator_second_member = wheel_track_steering_ * std::sin(phi); + + const double alpha_r = + std::atan2(numerator, denominator_first_member + denominator_second_member); + const double alpha_l = + std::atan2(numerator, denominator_first_member - denominator_second_member); + steering_commands = {alpha_r, alpha_l}; + } + return std::make_tuple(traction_commands, steering_commands); + } + else + { + throw std::runtime_error("Config not implemented"); + } +} + +void SteeringKinematics::reset_odometry() +{ + x_ = 0.0; + y_ = 0.0; + heading_ = 0.0; + reset_accumulators(); +} + +void SteeringKinematics::integrate_runge_kutta_2( + const double v_bx, const double omega_bz, const double dt) +{ + // Compute intermediate value of the heading + const double theta_mid = heading_ + omega_bz * 0.5 * dt; + + // Use the intermediate values to update the state + x_ += v_bx * std::cos(theta_mid) * dt; + y_ += v_bx * std::sin(theta_mid) * dt; + heading_ += omega_bz * dt; +} + +void SteeringKinematics::integrate_fk(const double v_bx, const double omega_bz, const double dt) +{ + const double delta_x_b = v_bx * dt; + const double delta_theta = omega_bz * dt; + + if (is_close_to_zero(delta_theta)) + { + /// Runge-Kutta 2nd Order (should solve problems when omega_bz is zero): + integrate_runge_kutta_2(v_bx, omega_bz, dt); + } + else + { + /// Exact integration + const double heading_old = heading_; + const double R = delta_x_b / delta_theta; + heading_ += delta_theta; + x_ += R * (sin(heading_) - std::sin(heading_old)); + y_ += -R * (cos(heading_) - std::cos(heading_old)); + } +} + +void SteeringKinematics::reset_accumulators() +{ + linear_acc_ = RollingMeanAccumulator(velocity_rolling_window_size_); + angular_acc_ = RollingMeanAccumulator(velocity_rolling_window_size_); +} + +} // namespace steering_kinematics diff --git a/steering_controllers_library/src/steering_odometry.cpp b/steering_controllers_library/src/steering_odometry.cpp index 0a5367f4bd..f668230d5a 100644 --- a/steering_controllers_library/src/steering_odometry.cpp +++ b/steering_controllers_library/src/steering_odometry.cpp @@ -21,376 +21,93 @@ #include "steering_controllers_library/steering_odometry.hpp" -#include -#include - namespace steering_odometry { SteeringOdometry::SteeringOdometry(size_t velocity_rolling_window_size) -: timestamp_(0.0), - x_(0.0), - y_(0.0), - heading_(0.0), - linear_(0.0), - angular_(0.0), - wheel_track_traction_(0.0), - wheel_track_steering_(0.0), - wheel_base_(0.0), - wheel_radius_(0.0), - traction_wheel_old_pos_(0.0), - traction_right_wheel_old_pos_(0.0), - traction_left_wheel_old_pos_(0.0), - velocity_rolling_window_size_(velocity_rolling_window_size), - linear_acc_(velocity_rolling_window_size), - angular_acc_(velocity_rolling_window_size) -{ -} - -void SteeringOdometry::init(const rclcpp::Time & time) +: sk_impl_(velocity_rolling_window_size) { - // Reset accumulators and timestamp: - reset_accumulators(); - timestamp_ = time; } -bool SteeringOdometry::update_odometry( - const double linear_velocity, const double angular_velocity, const double dt) -{ - /// Integrate odometry: - integrate_fk(linear_velocity, angular_velocity, dt); - - /// We cannot estimate the speed with very small time intervals: - if (dt < 0.0001) - { - return false; // Interval too small to integrate with - } - - /// Estimate speeds using a rolling mean to filter them out: - linear_acc_.accumulate(linear_velocity); - angular_acc_.accumulate(angular_velocity); - - linear_ = linear_acc_.getRollingMean(); - angular_ = angular_acc_.getRollingMean(); - - return true; -} +void SteeringOdometry::init(const rclcpp::Time & time) { sk_impl_.init(time); } bool SteeringOdometry::update_from_position( const double traction_wheel_pos, const double steer_pos, const double dt) { - const double traction_wheel_est_pos_diff = traction_wheel_pos - traction_wheel_old_pos_; - - /// Update old position with current: - traction_wheel_old_pos_ = traction_wheel_pos; - - return update_from_velocity(traction_wheel_est_pos_diff / dt, steer_pos, dt); + return sk_impl_.update_from_position(traction_wheel_pos, steer_pos, dt); } bool SteeringOdometry::update_from_position( const double traction_right_wheel_pos, const double traction_left_wheel_pos, const double steer_pos, const double dt) { - const double traction_right_wheel_est_pos_diff = - traction_right_wheel_pos - traction_right_wheel_old_pos_; - const double traction_left_wheel_est_pos_diff = - traction_left_wheel_pos - traction_left_wheel_old_pos_; - - /// Update old position with current: - traction_right_wheel_old_pos_ = traction_right_wheel_pos; - traction_left_wheel_old_pos_ = traction_left_wheel_pos; - - return update_from_velocity( - traction_right_wheel_est_pos_diff / dt, traction_left_wheel_est_pos_diff / dt, steer_pos, dt); + return sk_impl_.update_from_position( + traction_right_wheel_pos, traction_left_wheel_pos, steer_pos, dt); } bool SteeringOdometry::update_from_position( const double traction_right_wheel_pos, const double traction_left_wheel_pos, const double right_steer_pos, const double left_steer_pos, const double dt) { - const double traction_right_wheel_est_pos_diff = - traction_right_wheel_pos - traction_right_wheel_old_pos_; - const double traction_left_wheel_est_pos_diff = - traction_left_wheel_pos - traction_left_wheel_old_pos_; - - /// Update old position with current: - traction_right_wheel_old_pos_ = traction_right_wheel_pos; - traction_left_wheel_old_pos_ = traction_left_wheel_pos; - - return update_from_velocity( - traction_right_wheel_est_pos_diff / dt, traction_left_wheel_est_pos_diff / dt, right_steer_pos, - left_steer_pos, dt); + return sk_impl_.update_from_position( + traction_right_wheel_pos, traction_left_wheel_pos, right_steer_pos, left_steer_pos, dt); } bool SteeringOdometry::update_from_velocity( const double traction_wheel_vel, const double steer_pos, const double dt) { - steer_pos_ = steer_pos; - double linear_velocity = traction_wheel_vel * wheel_radius_; - const double angular_velocity = std::tan(steer_pos) * linear_velocity / wheel_base_; - - return update_odometry(linear_velocity, angular_velocity, dt); -} - -double SteeringOdometry::get_linear_velocity_double_traction_axle( - const double right_traction_wheel_vel, const double left_traction_wheel_vel, - const double steer_pos) -{ - double turning_radius = wheel_base_ / std::tan(steer_pos); - const double vel_wheel_r = right_traction_wheel_vel * wheel_radius_; - const double vel_wheel_l = left_traction_wheel_vel * wheel_radius_; - - if (std::isinf(turning_radius)) - { - return (vel_wheel_r + vel_wheel_l) * 0.5; - } - - // overdetermined, we take the average - const double vel_r = - vel_wheel_r * turning_radius / (turning_radius + wheel_track_traction_ * 0.5); - const double vel_l = - vel_wheel_l * turning_radius / (turning_radius - wheel_track_traction_ * 0.5); - return (vel_r + vel_l) * 0.5; + return sk_impl_.update_from_velocity(traction_wheel_vel, steer_pos, dt); } bool SteeringOdometry::update_from_velocity( const double right_traction_wheel_vel, const double left_traction_wheel_vel, const double steer_pos, const double dt) { - steer_pos_ = steer_pos; - double linear_velocity = get_linear_velocity_double_traction_axle( - right_traction_wheel_vel, left_traction_wheel_vel, steer_pos_); - - const double angular_velocity = std::tan(steer_pos_) * linear_velocity / wheel_base_; - - return update_odometry(linear_velocity, angular_velocity, dt); + return sk_impl_.update_from_velocity( + right_traction_wheel_vel, left_traction_wheel_vel, steer_pos, dt); } bool 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) { - // overdetermined, we take the average - const double right_steer_pos_est = std::atan( - wheel_base_ * std::tan(right_steer_pos) / - (wheel_base_ - wheel_track_steering_ / 2 * std::tan(right_steer_pos))); - const double left_steer_pos_est = std::atan( - wheel_base_ * std::tan(left_steer_pos) / - (wheel_base_ + wheel_track_steering_ / 2 * std::tan(left_steer_pos))); - steer_pos_ = (right_steer_pos_est + left_steer_pos_est) * 0.5; - - double linear_velocity = get_linear_velocity_double_traction_axle( - right_traction_wheel_vel, left_traction_wheel_vel, steer_pos_); - const double angular_velocity = std::tan(steer_pos_) * linear_velocity / wheel_base_; - - return update_odometry(linear_velocity, angular_velocity, dt); + return sk_impl_.update_from_velocity( + right_traction_wheel_vel, left_traction_wheel_vel, right_steer_pos, left_steer_pos, dt); } void SteeringOdometry::update_open_loop(const double v_bx, const double omega_bz, const double dt) { - /// Save last linear and angular velocity: - linear_ = v_bx; - angular_ = omega_bz; - - /// Integrate odometry: - integrate_fk(v_bx, omega_bz, dt); + sk_impl_.update_open_loop(v_bx, omega_bz, dt); } void SteeringOdometry::set_wheel_params(double wheel_radius, double wheel_base, double wheel_track) { - wheel_radius_ = wheel_radius; - wheel_base_ = wheel_base; - wheel_track_traction_ = wheel_track; - wheel_track_steering_ = wheel_track; + sk_impl_.set_wheel_params(wheel_radius, wheel_base, wheel_track); } void SteeringOdometry::set_wheel_params( double wheel_radius, double wheel_base, double wheel_track_steering, double wheel_track_traction) { - wheel_radius_ = wheel_radius; - wheel_base_ = wheel_base; - wheel_track_traction_ = wheel_track_traction; - wheel_track_steering_ = wheel_track_steering; + sk_impl_.set_wheel_params(wheel_radius, wheel_base, wheel_track_steering, wheel_track_traction); } void SteeringOdometry::set_velocity_rolling_window_size(size_t velocity_rolling_window_size) { - velocity_rolling_window_size_ = velocity_rolling_window_size; - - reset_accumulators(); + sk_impl_.set_velocity_rolling_window_size(velocity_rolling_window_size); } void SteeringOdometry::set_odometry_type(const unsigned int type) { - config_type_ = static_cast(type); -} - -double SteeringOdometry::convert_twist_to_steering_angle(double v_bx, double omega_bz) -{ - // phi can be nan if both v_bx and omega_bz are zero - const auto phi = std::atan(omega_bz * wheel_base_ / v_bx); - return std::isfinite(phi) ? phi : 0.0; + sk_impl_.set_odometry_type(type); } std::tuple, std::vector> SteeringOdometry::get_commands( const double v_bx, const double omega_bz, const bool open_loop, const bool reduce_wheel_speed_until_steering_reached) { - // desired wheel speed and steering angle of the middle of traction and steering axis - double Ws, phi, phi_IK = steer_pos_; - -#if 0 - if (v_bx == 0 && omega_bz != 0) - { - // TODO(anyone) this would be only possible if traction is on the steering axis - phi = omega_bz > 0 ? M_PI_2 : -M_PI_2; - Ws = abs(omega_bz) * wheelbase_ / wheel_radius_; - } - else - { - // TODO(anyone) this would be valid only if traction is on the steering axis - Ws = v_bx / (wheel_radius_ * std::cos(phi_IK)); // using the measured steering angle - } -#endif - // steering angle - phi = SteeringOdometry::convert_twist_to_steering_angle(v_bx, omega_bz); - if (open_loop) - { - phi_IK = phi; - } - // wheel speed - Ws = v_bx / wheel_radius_; - - if (!open_loop && reduce_wheel_speed_until_steering_reached) - { - // Reduce wheel speed until the target angle has been reached - double phi_delta = abs(steer_pos_ - phi); - double scale; - const double min_phi_delta = M_PI / 6.; - if (phi_delta < min_phi_delta) - { - scale = 1; - } - else if (phi_delta >= 1.5608) - { - // cos(1.5608) = 0.01 - scale = 0.01 / cos(min_phi_delta); - } - else - { - // TODO(anyone): find the best function, e.g convex power functions - scale = cos(phi_delta) / cos(min_phi_delta); - } - Ws *= scale; - } - - if (config_type_ == BICYCLE_CONFIG) - { - std::vector traction_commands = {Ws}; - std::vector steering_commands = {phi}; - return std::make_tuple(traction_commands, steering_commands); - } - else if (config_type_ == TRICYCLE_CONFIG) - { - std::vector traction_commands; - std::vector steering_commands; - // double-traction axle - if (is_close_to_zero(phi_IK)) - { - // avoid division by zero - traction_commands = {Ws, Ws}; - } - else - { - const double turning_radius = wheel_base_ / std::tan(phi_IK); - const double Wr = Ws * (turning_radius + wheel_track_traction_ * 0.5) / turning_radius; - const double Wl = Ws * (turning_radius - wheel_track_traction_ * 0.5) / turning_radius; - traction_commands = {Wr, Wl}; - } - // simple steering - steering_commands = {phi}; - return std::make_tuple(traction_commands, steering_commands); - } - else if (config_type_ == ACKERMANN_CONFIG) - { - std::vector traction_commands; - std::vector steering_commands; - if (is_close_to_zero(phi_IK)) - { - // avoid division by zero - traction_commands = {Ws, Ws}; - // shortcut, no steering - steering_commands = {phi, phi}; - } - else - { - const double turning_radius = wheel_base_ / std::tan(phi_IK); - const double Wr = Ws * (turning_radius + wheel_track_traction_ * 0.5) / turning_radius; - const double Wl = Ws * (turning_radius - wheel_track_traction_ * 0.5) / turning_radius; - traction_commands = {Wr, Wl}; - - const double numerator = 2 * wheel_base_ * std::sin(phi); - const double denominator_first_member = 2 * wheel_base_ * std::cos(phi); - const double denominator_second_member = wheel_track_steering_ * std::sin(phi); - - const double alpha_r = - std::atan2(numerator, denominator_first_member + denominator_second_member); - const double alpha_l = - std::atan2(numerator, denominator_first_member - denominator_second_member); - steering_commands = {alpha_r, alpha_l}; - } - return std::make_tuple(traction_commands, steering_commands); - } - else - { - throw std::runtime_error("Config not implemented"); - } + return sk_impl_.get_commands( + v_bx, omega_bz, open_loop, reduce_wheel_speed_until_steering_reached); } -void SteeringOdometry::reset_odometry() -{ - x_ = 0.0; - y_ = 0.0; - heading_ = 0.0; - reset_accumulators(); -} - -void SteeringOdometry::integrate_runge_kutta_2( - const double v_bx, const double omega_bz, const double dt) -{ - // Compute intermediate value of the heading - const double theta_mid = heading_ + omega_bz * 0.5 * dt; - - // Use the intermediate values to update the state - x_ += v_bx * std::cos(theta_mid) * dt; - y_ += v_bx * std::sin(theta_mid) * dt; - heading_ += omega_bz * dt; -} - -void SteeringOdometry::integrate_fk(const double v_bx, const double omega_bz, const double dt) -{ - const double delta_x_b = v_bx * dt; - const double delta_theta = omega_bz * dt; - - if (is_close_to_zero(delta_theta)) - { - /// Runge-Kutta 2nd Order (should solve problems when omega_bz is zero): - integrate_runge_kutta_2(v_bx, omega_bz, dt); - } - else - { - /// Exact integration - const double heading_old = heading_; - const double R = delta_x_b / delta_theta; - heading_ += delta_theta; - x_ += R * (sin(heading_) - std::sin(heading_old)); - y_ += -R * (cos(heading_) - std::cos(heading_old)); - } -} - -void SteeringOdometry::reset_accumulators() -{ - linear_acc_ = RollingMeanAccumulator(velocity_rolling_window_size_); - angular_acc_ = RollingMeanAccumulator(velocity_rolling_window_size_); -} +void SteeringOdometry::reset_odometry() { sk_impl_.reset_odometry(); } } // namespace steering_odometry diff --git a/steering_controllers_library/test/test_steering_controllers_library.hpp b/steering_controllers_library/test/test_steering_controllers_library.hpp index 30b8e36bec..b386e5a85a 100644 --- a/steering_controllers_library/test/test_steering_controllers_library.hpp +++ b/steering_controllers_library/test/test_steering_controllers_library.hpp @@ -121,7 +121,7 @@ class TestableSteeringControllersLibrary { set_interface_numbers(NR_STATE_ITFS, NR_CMD_ITFS, NR_REF_ITFS); odometry_.set_wheel_params(WHEELS_RADIUS_, WHEELBASE_, WHEELS_TRACK_); - odometry_.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odometry_.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); return controller_interface::CallbackReturn::SUCCESS; } diff --git a/steering_controllers_library/test/test_steering_odometry.cpp b/steering_controllers_library/test/test_steering_odometry.cpp index a211ac8bf4..0645f76f0f 100644 --- a/steering_controllers_library/test/test_steering_odometry.cpp +++ b/steering_controllers_library/test/test_steering_odometry.cpp @@ -16,15 +16,15 @@ #include -#include "steering_controllers_library/steering_odometry.hpp" +#include "steering_controllers_library/steering_kinematics.hpp" TEST(TestSteeringOdometry, initialize) { - EXPECT_NO_THROW(steering_odometry::SteeringOdometry()); + EXPECT_NO_THROW(steering_kinematics::SteeringKinematics()); - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 3.); - odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odom.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); EXPECT_DOUBLE_EQ(odom.get_heading(), 0.); EXPECT_DOUBLE_EQ(odom.get_x(), 0.); EXPECT_DOUBLE_EQ(odom.get_y(), 0.); @@ -34,9 +34,9 @@ TEST(TestSteeringOdometry, initialize) TEST(TestSteeringOdometry, ackermann_odometry) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 1., 1.); - odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odom.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); ASSERT_TRUE(odom.update_from_velocity(1., 1., .1, .1, .1)); EXPECT_NEAR(odom.get_linear(), 1.002, 1e-3); EXPECT_NEAR(odom.get_angular(), .1, 1e-3); @@ -46,9 +46,9 @@ TEST(TestSteeringOdometry, ackermann_odometry) TEST(TestSteeringOdometry, ackermann_odometry_openloop_linear) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odom.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); odom.update_open_loop(2., 0., 0.5); EXPECT_DOUBLE_EQ(odom.get_linear(), 2.); EXPECT_DOUBLE_EQ(odom.get_x(), 1.); @@ -57,9 +57,9 @@ TEST(TestSteeringOdometry, ackermann_odometry_openloop_linear) TEST(TestSteeringOdometry, ackermann_odometry_openloop_angular_left) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odom.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); odom.update_open_loop(1., 1., 1.); EXPECT_DOUBLE_EQ(odom.get_linear(), 1.); EXPECT_DOUBLE_EQ(odom.get_angular(), 1.); @@ -70,9 +70,9 @@ TEST(TestSteeringOdometry, ackermann_odometry_openloop_angular_left) TEST(TestSteeringOdometry, ackermann_odometry_openloop_angular_right) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odom.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); odom.update_open_loop(1., -1., 1.); EXPECT_DOUBLE_EQ(odom.get_linear(), 1.); EXPECT_DOUBLE_EQ(odom.get_angular(), -1.); @@ -82,9 +82,9 @@ TEST(TestSteeringOdometry, ackermann_odometry_openloop_angular_right) TEST(TestSteeringOdometry, ackermann_IK_linear) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odom.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); odom.update_open_loop(1., 0., 1.); auto cmd = odom.get_commands(1., 0., true); auto cmd0 = std::get<0>(cmd); // vel @@ -97,9 +97,9 @@ TEST(TestSteeringOdometry, ackermann_IK_linear) TEST(TestSteeringOdometry, ackermann_IK_left) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odom.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); odom.update_from_position(0., 0.2, 1.); // assume already turn auto cmd = odom.get_commands(1., 0.1, false); auto cmd0 = std::get<0>(cmd); // vel @@ -112,9 +112,9 @@ TEST(TestSteeringOdometry, ackermann_IK_left) TEST(TestSteeringOdometry, ackermann_IK_right) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odom.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); odom.update_from_position(0., -0.2, 1.); // assume already turn auto cmd = odom.get_commands(1., -0.1, false); auto cmd0 = std::get<0>(cmd); // vel @@ -127,9 +127,9 @@ TEST(TestSteeringOdometry, ackermann_IK_right) TEST(TestSteeringOdometry, ackermann_IK_right_steering_limited) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG); + odom.set_odometry_type(steering_kinematics::ACKERMANN_CONFIG); { odom.update_from_position(0., -0.785, 1.); // already steered @@ -175,9 +175,9 @@ TEST(TestSteeringOdometry, ackermann_IK_right_steering_limited) TEST(TestSteeringOdometry, bicycle_IK_linear) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::BICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::BICYCLE_CONFIG); odom.update_open_loop(1., 0., 1.); auto cmd = odom.get_commands(1., 0., true); auto cmd0 = std::get<0>(cmd); // vel @@ -188,9 +188,9 @@ TEST(TestSteeringOdometry, bicycle_IK_linear) TEST(TestSteeringOdometry, bicycle_IK_left) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::BICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::BICYCLE_CONFIG); odom.update_from_position(0., 0.2, 1.); // assume already turn auto cmd = odom.get_commands(1., 0.1, false); auto cmd0 = std::get<0>(cmd); // vel @@ -201,9 +201,9 @@ TEST(TestSteeringOdometry, bicycle_IK_left) TEST(TestSteeringOdometry, bicycle_IK_right) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::BICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::BICYCLE_CONFIG); odom.update_from_position(0., -0.2, 1.); // assume already turn auto cmd = odom.get_commands(1., -0.1, false); auto cmd0 = std::get<0>(cmd); // vel @@ -214,9 +214,9 @@ TEST(TestSteeringOdometry, bicycle_IK_right) TEST(TestSteeringOdometry, bicycle_IK_right_steering_limited) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::BICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::BICYCLE_CONFIG); { odom.update_from_position(0., -0.785, 1.); // already steered @@ -270,9 +270,9 @@ TEST(TestSteeringOdometry, bicycle_IK_right_steering_limited) TEST(TestSteeringOdometry, bicycle_odometry) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 1., 1.); - odom.set_odometry_type(steering_odometry::BICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::BICYCLE_CONFIG); ASSERT_TRUE(odom.update_from_velocity(1., .1, .1)); EXPECT_NEAR(odom.get_linear(), 1.0, 1e-3); EXPECT_NEAR(odom.get_angular(), .1, 1e-3); @@ -284,9 +284,9 @@ TEST(TestSteeringOdometry, bicycle_odometry) TEST(TestSteeringOdometry, tricycle_IK_linear) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::TRICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::TRICYCLE_CONFIG); odom.update_open_loop(1., 0., 1.); auto cmd = odom.get_commands(1., 0., true); auto cmd0 = std::get<0>(cmd); // vel @@ -298,9 +298,9 @@ TEST(TestSteeringOdometry, tricycle_IK_linear) TEST(TestSteeringOdometry, tricycle_IK_left) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::TRICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::TRICYCLE_CONFIG); odom.update_from_position(0., 0.2, 1.); // assume already turn auto cmd = odom.get_commands(1., 0.1, false); auto cmd0 = std::get<0>(cmd); // vel @@ -312,9 +312,9 @@ TEST(TestSteeringOdometry, tricycle_IK_left) TEST(TestSteeringOdometry, tricycle_IK_right) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::TRICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::TRICYCLE_CONFIG); odom.update_from_position(0., -0.2, 1.); // assume already turn auto cmd = odom.get_commands(1., -0.1, false); auto cmd0 = std::get<0>(cmd); // vel @@ -326,9 +326,9 @@ TEST(TestSteeringOdometry, tricycle_IK_right) TEST(TestSteeringOdometry, tricycle_IK_right_steering_limited) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 2., 1.); - odom.set_odometry_type(steering_odometry::TRICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::TRICYCLE_CONFIG); { odom.update_from_position(0., -0.785, 1.); // already steered @@ -369,9 +369,9 @@ TEST(TestSteeringOdometry, tricycle_IK_right_steering_limited) TEST(TestSteeringOdometry, tricycle_odometry) { - steering_odometry::SteeringOdometry odom(1); + steering_kinematics::SteeringKinematics odom(1); odom.set_wheel_params(1., 1., 1.); - odom.set_odometry_type(steering_odometry::TRICYCLE_CONFIG); + odom.set_odometry_type(steering_kinematics::TRICYCLE_CONFIG); ASSERT_TRUE(odom.update_from_velocity(1., 1., .1, .1)); EXPECT_NEAR(odom.get_linear(), 1.002, 1e-3); EXPECT_NEAR(odom.get_angular(), .1, 1e-3); diff --git a/tricycle_steering_controller/src/tricycle_steering_controller.cpp b/tricycle_steering_controller/src/tricycle_steering_controller.cpp index 43fdcd4421..d799ac4e5e 100644 --- a/tricycle_steering_controller/src/tricycle_steering_controller.cpp +++ b/tricycle_steering_controller/src/tricycle_steering_controller.cpp @@ -35,7 +35,7 @@ controller_interface::CallbackReturn TricycleSteeringController::configure_odome const double wheelbase = tricycle_params_.wheelbase; odometry_.set_wheel_params(traction_wheels_radius, wheelbase, traction_track_width); - odometry_.set_odometry_type(steering_odometry::TRICYCLE_CONFIG); + odometry_.set_odometry_type(steering_kinematics::TRICYCLE_CONFIG); set_interface_numbers(NR_STATE_ITFS, NR_CMD_ITFS, NR_REF_ITFS);