Skip to content

Commit

Permalink
Copter: Fix payload place bug
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall authored and peterbarker committed Aug 8, 2024
1 parent f9fde66 commit 16aa2ed
Showing 1 changed file with 3 additions and 4 deletions.
7 changes: 3 additions & 4 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1439,24 +1439,23 @@ void PayloadPlace::run()
copter.flightmode->land_run_horizontal_control();
// update altitude target and call position controller
pos_control->land_at_climb_rate_cm(-descent_speed_cms, true);
pos_control->update_z_controller();
return;
break;
case State::Release:
case State::Releasing:
case State::Delay:
case State::Ascent_Start:
copter.flightmode->land_run_horizontal_control();
// update altitude target and call position controller
pos_control->land_at_climb_rate_cm(0.0, false);
pos_control->update_z_controller();
return;
break;
case State::Ascent:
case State::Done:
float vel = 0.0;
copter.flightmode->land_run_horizontal_control();
pos_control->input_pos_vel_accel_z(descent_start_altitude_cm, vel, 0.0);
break;
}
pos_control->update_z_controller();
}
#endif

Expand Down

0 comments on commit 16aa2ed

Please sign in to comment.