You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
This has been present in the function land_run_horizontal_control().
if (g2.wp_navalt_min > 0) {
// user has requested an altitude below which navigation
// attitude is limited. This is used to prevent commanded roll
// over on landing, which particularly affects helicopters if
// there is any position estimate drift after touchdown. We
// limit attitude to 7 degrees below this limit and linearly
// interpolate for 1m above that
const float attitude_limit_cd = linear_interpolate(700, copter.aparm.angle_max, get_alt_above_ground_cm(),
g2.wp_navalt_min*100U, (g2.wp_navalt_min+1)*100U);
const float thrust_vector_max = sinf(radians(attitude_limit_cd * 0.01f)) * GRAVITY_MSS * 100.0f;
const float thrust_vector_mag = thrust_vector.xy().length();
if (thrust_vector_mag > thrust_vector_max) {
float ratio = thrust_vector_max / thrust_vector_mag;
thrust_vector.x *= ratio;
thrust_vector.y *= ratio;
// tell position controller we are applying an external limit
pos_control->set_externally_limited_NE();
}
}
g2.wp_navalt_min is:
// altitude at which nav control can start in takeoff
AP_Float wp_navalt_min;
We need to update the discription of the parameter to match WP_NAVALT_MIN:
This is the altitude in meters above which for navigation can begin. This applies in auto takeoff and auto landing
My consern with this parameter is it gets the altitude from:
/*
get a height above ground estimate for landing
*/
int32_t Mode::get_alt_above_ground_cm(void)
{
int32_t alt_above_ground_cm;
if (copter.get_rangefinder_height_interpolated_cm(alt_above_ground_cm)) {
return alt_above_ground_cm;
}
if (!pos_control->is_active_NE()) {
return copter.current_loc.alt;
}
if (copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, alt_above_ground_cm)) {
return alt_above_ground_cm;
}
// Assume the Earth is flat:
return copter.current_loc.alt;
}
My consern is this can remove the ability of the aircraft to maintain control while landing if the local terain altitude database is not accurate. For example, if the terain is actually 5m lower than the database then the aircraft will drift for 10 seconds using the default parameters.
I wonder if we should be using rangefinder only or have a seperate parameter for landing vs takeoff.
The text was updated successfully, but these errors were encountered:
This has been present in the function land_run_horizontal_control().
g2.wp_navalt_min is:
We need to update the discription of the parameter to match WP_NAVALT_MIN:
This is the altitude in meters above which for navigation can begin. This applies in auto takeoff and auto landing
My consern with this parameter is it gets the altitude from:
My consern is this can remove the ability of the aircraft to maintain control while landing if the local terain altitude database is not accurate. For example, if the terain is actually 5m lower than the database then the aircraft will drift for 10 seconds using the default parameters.
I wonder if we should be using rangefinder only or have a seperate parameter for landing vs takeoff.
The text was updated successfully, but these errors were encountered: