Copter: pass dt to avoidance calls

This commit is contained in:
Randy Mackay 2018-01-13 15:20:36 +09:00
parent 48d0ad26a6
commit e85b1ac740
2 changed files with 2 additions and 2 deletions

View File

@ -283,7 +283,7 @@ float Copter::get_surface_tracking_climb_rate(int16_t target_rate, float current
float Copter::get_avoidance_adjusted_climbrate(float target_rate)
{
#if AC_AVOID_ENABLED == ENABLED
avoid.adjust_velocity_z(pos_control->get_pos_z_kP(), pos_control->get_accel_z(), target_rate);
avoid.adjust_velocity_z(pos_control->get_pos_z_kP(), pos_control->get_accel_z(), target_rate, G_Dt);
return target_rate;
#else
return target_rate;

View File

@ -653,7 +653,7 @@ void Copter::ModeGuided::set_desired_velocity_with_accel_and_fence_limits(const
#if AC_AVOID_ENABLED
// limit the velocity to prevent fence violations
_copter.avoid.adjust_velocity(pos_control->get_pos_xy_kP(), pos_control->get_accel_xy(), curr_vel_des);
_copter.avoid.adjust_velocity(pos_control->get_pos_xy_kP(), pos_control->get_accel_xy(), curr_vel_des, G_Dt);
// get avoidance adjusted climb rate
curr_vel_des.z = get_avoidance_adjusted_climbrate(curr_vel_des.z);
#endif