mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Copter: log target alt in meters
This commit is contained in:
parent
095505129c
commit
0a148cce19
@ -550,7 +550,7 @@ static int16_t throttle_accel_target_ef; // earth frame throttle acceleration
|
|||||||
static bool throttle_accel_controller_active; // true when accel based throttle controller is active, false when higher level throttle controllers are providing throttle output directly
|
static bool throttle_accel_controller_active; // true when accel based throttle controller is active, false when higher level throttle controllers are providing throttle output directly
|
||||||
static float throttle_avg; // g.throttle_cruise as a float
|
static float throttle_avg; // g.throttle_cruise as a float
|
||||||
static int16_t desired_climb_rate; // pilot desired climb rate - for logging purposes only
|
static int16_t desired_climb_rate; // pilot desired climb rate - for logging purposes only
|
||||||
static float target_alt_for_reporting; // target altitude for reporting (logs and ground station)
|
static float target_alt_for_reporting; // target altitude in cm for reporting (logs and ground station)
|
||||||
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
@ -1916,13 +1916,13 @@ void update_throttle_mode(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// set_target_alt_for_reporting - set target altitude for reporting purposes (logs and gcs)
|
// set_target_alt_for_reporting - set target altitude in cm for reporting purposes (logs and gcs)
|
||||||
static void set_target_alt_for_reporting(float alt)
|
static void set_target_alt_for_reporting(float alt_cm)
|
||||||
{
|
{
|
||||||
target_alt_for_reporting = alt;
|
target_alt_for_reporting = alt_cm;
|
||||||
}
|
}
|
||||||
|
|
||||||
// get_target_alt_for_reporting - returns target altitude for reporting purposes (logs and gcs)
|
// get_target_alt_for_reporting - returns target altitude in cm for reporting purposes (logs and gcs)
|
||||||
static float get_target_alt_for_reporting()
|
static float get_target_alt_for_reporting()
|
||||||
{
|
{
|
||||||
return target_alt_for_reporting;
|
return target_alt_for_reporting;
|
||||||
|
@ -324,7 +324,7 @@ static void Log_Write_Control_Tuning()
|
|||||||
throttle_in : g.rc_3.control_in,
|
throttle_in : g.rc_3.control_in,
|
||||||
sonar_alt : sonar_alt,
|
sonar_alt : sonar_alt,
|
||||||
baro_alt : baro_alt,
|
baro_alt : baro_alt,
|
||||||
next_wp_alt : get_target_alt_for_reporting(),
|
next_wp_alt : get_target_alt_for_reporting() / 100.0f,
|
||||||
nav_throttle : nav_throttle,
|
nav_throttle : nav_throttle,
|
||||||
angle_boost : angle_boost,
|
angle_boost : angle_boost,
|
||||||
climb_rate : climb_rate,
|
climb_rate : climb_rate,
|
||||||
|
Loading…
Reference in New Issue
Block a user