mirror of https://github.com/ArduPilot/ardupilot
Copter: Guided: support terrain following
This commit is contained in:
parent
b2032ee2e3
commit
6ff5913aa1
|
@ -563,7 +563,14 @@ void ModeGuided::pos_control_run()
|
|||
// send position and velocity targets to position controller
|
||||
guided_accel_target_cmss.zero();
|
||||
guided_vel_target_cms.zero();
|
||||
pos_control->input_pos_xyz(guided_pos_target_cm, terr_offset);
|
||||
|
||||
// todo: Randy to convert to parameter TERRAIN_MARGIN (in m)
|
||||
float TERRAIN_MARGIN = 10;
|
||||
float pos_offset_z_buffer = 0.0; // Vertical buffer size in m
|
||||
if (guided_pos_terrain_alt) {
|
||||
pos_offset_z_buffer = MIN(TERRAIN_MARGIN * 100.0, 0.5 * fabsf(guided_pos_target_cm.z));
|
||||
}
|
||||
pos_control->input_pos_xyz(guided_pos_target_cm, terr_offset, pos_offset_z_buffer);
|
||||
|
||||
// run position controllers
|
||||
pos_control->update_xy_controller();
|
||||
|
|
Loading…
Reference in New Issue