AP_Landing: fixed use of double precision maths
and rename log() to Log() to prevent name collision with libm function
This commit is contained in:
parent
3b8ec3a2a0
commit
48e27ab242
@ -172,7 +172,7 @@ AP_Landing::AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_
|
||||
|
||||
void AP_Landing::do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude)
|
||||
{
|
||||
log(); // log old state so we get a nice transition from old to new here
|
||||
Log(); // log old state so we get a nice transition from old to new here
|
||||
|
||||
flags.commanded_go_around = false;
|
||||
|
||||
@ -188,7 +188,7 @@ void AP_Landing::do_land(const AP_Mission::Mission_Command& cmd, const float rel
|
||||
break;
|
||||
}
|
||||
|
||||
log();
|
||||
Log();
|
||||
}
|
||||
|
||||
/*
|
||||
@ -216,7 +216,7 @@ bool AP_Landing::verify_land(const Location &prev_WP_loc, Location &next_WP_loc,
|
||||
success = true;
|
||||
break;
|
||||
}
|
||||
log();
|
||||
Log();
|
||||
return success;
|
||||
}
|
||||
|
||||
@ -245,7 +245,7 @@ bool AP_Landing::verify_abort_landing(const Location &prev_WP_loc, Location &nex
|
||||
// else we're in AUTO with a stopped mission and handle_auto_mode() will set RTL
|
||||
}
|
||||
|
||||
log();
|
||||
Log();
|
||||
|
||||
// make sure to always return false so it leaves the mission index alone
|
||||
return false;
|
||||
@ -447,7 +447,7 @@ bool AP_Landing::restart_landing_sequence()
|
||||
update_flight_stage_fn();
|
||||
}
|
||||
|
||||
log();
|
||||
Log();
|
||||
return success;
|
||||
}
|
||||
|
||||
@ -547,16 +547,16 @@ bool AP_Landing::request_go_around(void)
|
||||
break;
|
||||
}
|
||||
|
||||
log();
|
||||
Log();
|
||||
return success;
|
||||
}
|
||||
|
||||
void AP_Landing::handle_flight_stage_change(const bool _in_landing_stage)
|
||||
{
|
||||
log(); // log old value to plot discrete transitions
|
||||
Log(); // log old value to plot discrete transitions
|
||||
flags.in_progress = _in_landing_stage;
|
||||
flags.commanded_go_around = false;
|
||||
log();
|
||||
Log();
|
||||
}
|
||||
|
||||
/*
|
||||
@ -574,14 +574,14 @@ bool AP_Landing::is_complete(void) const
|
||||
}
|
||||
}
|
||||
|
||||
void AP_Landing::log(void) const
|
||||
void AP_Landing::Log(void) const
|
||||
{
|
||||
switch (type) {
|
||||
case TYPE_STANDARD_GLIDE_SLOPE:
|
||||
type_slope_log();
|
||||
break;
|
||||
case TYPE_DEEPSTALL:
|
||||
deepstall.log();
|
||||
deepstall.Log();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
|
@ -100,7 +100,7 @@ public:
|
||||
bool is_complete(void) const;
|
||||
void set_initial_slope(void) { initial_slope = slope; }
|
||||
bool is_expecting_impact(void) const;
|
||||
void log(void) const;
|
||||
void Log(void) const;
|
||||
const DataFlash_Class::PID_Info * get_pid_info(void) const;
|
||||
|
||||
// landing altitude offset (meters)
|
||||
|
@ -428,7 +428,7 @@ const DataFlash_Class::PID_Info& AP_Landing_Deepstall::get_pid_info(void) const
|
||||
return ds_PID.get_pid_info();
|
||||
}
|
||||
|
||||
void AP_Landing_Deepstall::log(void) const {
|
||||
void AP_Landing_Deepstall::Log(void) const {
|
||||
const DataFlash_Class::PID_Info& pid_info = ds_PID.get_pid_info();
|
||||
struct log_DSTL pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DSTL_MSG),
|
||||
|
@ -105,7 +105,7 @@ private:
|
||||
bool is_flying_forward(void) const;
|
||||
bool is_on_approach(void) const;
|
||||
bool terminate(void);
|
||||
void log(void) const;
|
||||
void Log(void) const;
|
||||
|
||||
bool send_deepstall_message(mavlink_channel_t chan) const;
|
||||
|
||||
|
@ -191,8 +191,8 @@ void AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle
|
||||
// offset and "perfect" slope.
|
||||
|
||||
// calculate projected slope with projected alt
|
||||
float new_slope_deg = degrees(atan(slope));
|
||||
float initial_slope_deg = degrees(atan(initial_slope));
|
||||
float new_slope_deg = degrees(atanf(slope));
|
||||
float initial_slope_deg = degrees(atanf(initial_slope));
|
||||
|
||||
// is projected slope too steep?
|
||||
if (new_slope_deg - initial_slope_deg > slope_recalc_steep_threshold_to_abort) {
|
||||
@ -201,7 +201,7 @@ void AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle
|
||||
alt_offset = rangefinder_state.correction;
|
||||
flags.commanded_go_around = true;
|
||||
type_slope_flags.has_aborted_due_to_slope_recalc = true; // only allow this once.
|
||||
log();
|
||||
Log();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user