@@ -124,7 +124,7 @@ bool SteeringOdometry::update_from_velocity(
124124{
125125 steer_pos_ = steer_pos;
126126 double linear_velocity = traction_wheel_vel * wheel_radius_;
127- const double angular_velocity = tan (steer_pos) * linear_velocity / wheelbase_;
127+ const double angular_velocity = std:: tan (steer_pos) * linear_velocity / wheelbase_;
128128
129129 return update_odometry (linear_velocity, angular_velocity, dt);
130130}
@@ -150,7 +150,7 @@ bool SteeringOdometry::update_from_velocity(
150150 double linear_velocity = get_lin_velocity_double_traction_axle (
151151 right_traction_wheel_vel, left_traction_wheel_vel, steer_pos_);
152152
153- const double angular_velocity = tan (steer_pos_) * linear_velocity / wheelbase_;
153+ const double angular_velocity = std:: tan (steer_pos_) * linear_velocity / wheelbase_;
154154
155155 return update_odometry (linear_velocity, angular_velocity, dt);
156156}
@@ -317,8 +317,8 @@ void SteeringOdometry::integrate_runge_kutta_2(
317317 const double theta_mid = heading_ + omega_bz * 0.5 * dt;
318318
319319 // Use the intermediate values to update the state
320- x_ += v_bx * cos (theta_mid) * dt;
321- y_ += v_bx * sin (theta_mid) * dt;
320+ x_ += v_bx * std:: cos (theta_mid) * dt;
321+ y_ += v_bx * std:: sin (theta_mid) * dt;
322322 heading_ += omega_bz * dt;
323323}
324324
@@ -338,8 +338,8 @@ void SteeringOdometry::integrate_fk(const double v_bx, const double omega_bz, co
338338 const double heading_old = heading_;
339339 const double R = delta_x_b / delta_theta;
340340 heading_ += delta_theta;
341- x_ += R * (sin (heading_) - sin (heading_old));
342- y_ += -R * (cos (heading_) - cos (heading_old));
341+ x_ += R * (sin (heading_) - std:: sin (heading_old));
342+ y_ += -R * (cos (heading_) - std:: cos (heading_old));
343343 }
344344}
345345
0 commit comments