mirror of https://github.com/ArduPilot/ardupilot
Copter: replace use of TERRAIN_MARGIN with WPNAV_TER_MARGIN
This commit is contained in:
parent
fb5c458132
commit
d39581f996
|
@ -884,7 +884,6 @@ private:
|
|||
// terrain.cpp
|
||||
void terrain_update();
|
||||
void terrain_logging();
|
||||
float get_terrain_margin() const;
|
||||
|
||||
// tuning.cpp
|
||||
void tuning();
|
||||
|
|
|
@ -1079,16 +1079,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
AP_GROUPINFO("GUID_TIMEOUT", 46, ParametersG2, guided_timeout, 3.0),
|
||||
#endif
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
// @Param: TERRAIN_MARGIN
|
||||
// @DisplayName: Terrain following altitude margin
|
||||
// @Description: Terrain following altitude margin. Vehicle will stop if distance from target altitude is larger than this margin (in meters)
|
||||
// @Units: m
|
||||
// @Range: 0.1 100
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TERRAIN_MARGIN", 47, ParametersG2, terrain_margin, 10.0),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -652,10 +652,6 @@ public:
|
|||
#if MODE_GUIDED_ENABLED == ENABLED
|
||||
AP_Float guided_timeout;
|
||||
#endif
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
AP_Float terrain_margin;
|
||||
#endif
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
|
|
@ -553,7 +553,7 @@ void ModeGuided::pos_control_run()
|
|||
|
||||
float pos_offset_z_buffer = 0.0; // Vertical buffer size in m
|
||||
if (guided_pos_terrain_alt) {
|
||||
pos_offset_z_buffer = MIN(copter.get_terrain_margin() * 100.0, 0.5 * fabsf(guided_pos_target_cm.z));
|
||||
pos_offset_z_buffer = MIN(copter.wp_nav->get_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);
|
||||
|
||||
|
|
|
@ -26,13 +26,3 @@ void Copter::terrain_logging()
|
|||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// return terrain following altitude margin. Vehicle will stop if distance from target altitude is larger than this margin (in meters)
|
||||
float Copter::get_terrain_margin() const
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
return MAX(g2.terrain_margin.get(), 0.1);
|
||||
#else
|
||||
return 10;
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue