Skip to content

Commit 499c991

Browse files
Reorganize steering odometry to pass ABI checks for backward compatibility
1 parent 79cd0ed commit 499c991

File tree

1 file changed

+103
-4
lines changed

1 file changed

+103
-4
lines changed

steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp

Lines changed: 103 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -53,12 +53,111 @@ namespace steering_odometry
5353
inline bool is_close_to_zero(double val) { return steering_kinematics::is_close_to_zero(val); }
5454

5555
/**
56-
* \brief The Odometry class handles odometry readings
57-
* (2D pose and velocity with related timestamp)
56+
* \brief Deprecated Odometry class for backward ABI compatibility.
57+
* Internally calling steering_kinematics::SteeringKinematics
5858
*/
59-
using SteeringOdometry [[deprecated("Use steering_kinematics::SteeringKinematics instead.")]] =
60-
steering_kinematics::SteeringKinematics;
6159

60+
class [[deprecated("Use steering_kinematics::SteeringKinematics instead")]] SteeringOdometry
61+
{
62+
public:
63+
explicit SteeringOdometry(size_t velocity_rolling_window_size = 10)
64+
: sk_impl_(velocity_rolling_window_size)
65+
{
66+
}
67+
68+
void init(const rclcpp::Time & time) { sk_impl_.init(time); }
69+
70+
bool update_from_position(
71+
const double traction_wheel_pos, const double steer_pos, const double dt)
72+
{
73+
sk_impl_.update_from_position(traction_wheel_pos, steer_pos, dt);
74+
}
75+
76+
bool update_from_position(
77+
const double right_traction_wheel_pos, const double left_traction_wheel_pos,
78+
const double steer_pos, const double dt)
79+
{
80+
sk_impl_.update_from_position(right_traction_wheel_pos, left_traction_wheel_pos, steer_pos, dt);
81+
}
82+
83+
bool update_from_position(
84+
const double right_traction_wheel_pos, const double left_traction_wheel_pos,
85+
const double right_steer_pos, const double left_steer_pos, const double dt)
86+
{
87+
sk_impl_.update_from_position(
88+
right_traction_wheel_pos, left_traction_wheel_pos, right_steer_pos, left_steer_pos, dt);
89+
}
90+
91+
bool update_from_velocity(
92+
const double traction_wheel_vel, const double steer_pos, const double dt)
93+
{
94+
sk_impl_.update_from_velocity(traction_wheel_vel, steer_pos, dt);
95+
}
96+
97+
bool update_from_velocity(
98+
const double right_traction_wheel_vel, const double left_traction_wheel_vel,
99+
const double steer_pos, const double dt)
100+
{
101+
sk_impl_.update_from_velocity(right_traction_wheel_vel, left_traction_wheel_vel, steer_pos, dt);
102+
}
103+
104+
bool update_from_velocity(
105+
const double right_traction_wheel_vel, const double left_traction_wheel_vel,
106+
const double right_steer_pos, const double left_steer_pos, const double dt)
107+
{
108+
sk_impl_.update_from_velocity(
109+
right_traction_wheel_vel, left_traction_wheel_vel, right_steer_pos, left_steer_pos, dt);
110+
}
111+
112+
void update_open_loop(const double v_bx, const double omega_bz, const double dt)
113+
{
114+
sk_impl_.update_open_loop(v_bx, omega_bz, dt);
115+
}
116+
117+
void set_odometry_type(const unsigned int type) { sk_impl_.set_odometry_type(type); }
118+
119+
unsigned int get_odometry_type() const { sk_impl_.get_odometry_type(); }
120+
121+
double get_heading() const { sk_impl_.get_heading(); }
122+
123+
double get_x() const { sk_impl_.get_x(); }
124+
125+
double get_y() const { sk_impl_.get_y(); }
126+
127+
double get_linear() const { sk_impl_.get_linear(); }
128+
129+
double get_angular() const { sk_impl_.get_angular(); }
130+
131+
void set_wheel_params(
132+
const double wheel_radius, const double wheel_base = 0.0, const double wheel_track = 0.0)
133+
{
134+
sk_impl_.set_wheel_params(wheel_radius, wheel_base, wheel_track);
135+
}
136+
137+
void set_wheel_params(
138+
const double wheel_radius, const double wheel_base, const double wheel_track_steering,
139+
const double wheel_track_traction)
140+
{
141+
sk_impl_.set_wheel_params(wheel_radius, wheel_track_steering, wheel_track_traction);
142+
}
143+
144+
void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size)
145+
{
146+
sk_impl_.set_velocity_rolling_window_size(velocity_rolling_window_size);
147+
}
148+
149+
std::tuple<std::vector<double>, std::vector<double>> get_commands(
150+
double v_bx, double omega_bz, bool open_loop = true,
151+
bool reduce_wheel_speed_until_steering_reached = false)
152+
{
153+
return impl_.get_commands(v_bx, omega_bz, open_loop, reduce_wheel_speed_until_steering_reached);
154+
}
155+
156+
void reset_odometry() { impl_.reset_odometry(); }
157+
158+
private:
159+
steering_kinematics::SteeringKinematics sk_impl_;
160+
};
62161
} // namespace steering_odometry
63162

64163
#endif // STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_

0 commit comments

Comments
 (0)