Browse Source

AC_WPNav: compiler warnings: float to double

master
Tom Pittenger 10 years ago committed by Randy Mackay
parent
commit
93c6ed0ea2
  1. 4
      libraries/AC_WPNav/AC_Circle.cpp

4
libraries/AC_WPNav/AC_Circle.cpp

@ -124,7 +124,7 @@ void AC_Circle::update() @@ -124,7 +124,7 @@ void AC_Circle::update()
_angular_vel = min(_angular_vel, _angular_vel_max);
}
if (_angular_vel > _angular_vel_max) {
_angular_vel -= fabs(_angular_accel) * dt;
_angular_vel -= fabsf(_angular_accel) * dt;
_angular_vel = max(_angular_vel, _angular_vel_max);
}
@ -210,7 +210,7 @@ void AC_Circle::calc_velocities(bool init_velocity) @@ -210,7 +210,7 @@ void AC_Circle::calc_velocities(bool init_velocity)
// if we are doing a panorama set the circle_angle to the current heading
if (_radius <= 0) {
_angular_vel_max = ToRad(_rate);
_angular_accel = max(fabs(_angular_vel_max),ToRad(AC_CIRCLE_ANGULAR_ACCEL_MIN)); // reach maximum yaw velocity in 1 second
_angular_accel = max(fabsf(_angular_vel_max),ToRad(AC_CIRCLE_ANGULAR_ACCEL_MIN)); // reach maximum yaw velocity in 1 second
}else{
// calculate max velocity based on waypoint speed ensuring we do not use more than half our max acceleration for accelerating towards the center of the circle
float velocity_max = min(_pos_control.get_speed_xy(), safe_sqrt(0.5f*_pos_control.get_accel_xy()*_radius));

Loading…
Cancel
Save