Browse Source

Plane: always log QPOS when changing control state

gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
fd5faa866f
  1. 17
      ArduPlane/quadplane.cpp
  2. 1
      ArduPlane/quadplane.h

17
ArduPlane/quadplane.cpp

@ -2090,6 +2090,17 @@ void QuadPlane::poscontrol_init_approach(void) @@ -2090,6 +2090,17 @@ void QuadPlane::poscontrol_init_approach(void)
}
}
/*
log the QPOS message
*/
void QuadPlane::log_QPOS(void)
{
AP::logger().WriteStreaming("QPOS", "TimeUS,State,Dist", "QBf",
AP_HAL::micros64(),
poscontrol.get_state(),
plane.auto_state.wp_distance);
}
/*
change position control state
*/
@ -2116,6 +2127,7 @@ void QuadPlane::PosControlState::set_state(enum position_control_state s) @@ -2116,6 +2127,7 @@ void QuadPlane::PosControlState::set_state(enum position_control_state s)
// reset throttle descent control
qp.thr_ctrl_land = false;
}
qp.log_QPOS();
}
state = s;
last_state_change_ms = AP_HAL::millis();
@ -2551,10 +2563,7 @@ void QuadPlane::vtol_position_controller(void) @@ -2551,10 +2563,7 @@ void QuadPlane::vtol_position_controller(void)
if (now_ms - poscontrol.last_log_ms >= 40) {
// log poscontrol at 25Hz
poscontrol.last_log_ms = now_ms;
AP::logger().WriteStreaming("QPOS", "TimeUS,State,Dist", "QBf",
AP_HAL::micros64(),
poscontrol.get_state(),
plane.auto_state.wp_distance);
log_QPOS();
}
}

1
ArduPlane/quadplane.h

@ -249,6 +249,7 @@ private: @@ -249,6 +249,7 @@ private:
bool should_relax(void);
void motors_output(bool run_rate_controller = true);
void Log_Write_QControl_Tuning();
void log_QPOS(void);
float landing_descent_rate_cms(float height_above_ground);
// setup correct aux channels for frame class

Loading…
Cancel
Save