mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: balance bots log pitch PID
This commit is contained in:
parent
7772279785
commit
e867ef74cc
@ -38,6 +38,11 @@ void Rover::Log_Write_Attitude()
|
||||
// log steering rate controller
|
||||
DataFlash.Log_Write_PID(LOG_PIDS_MSG, g2.attitude_control.get_steering_rate_pid().get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDA_MSG, g2.attitude_control.get_throttle_speed_pid().get_pid_info());
|
||||
|
||||
// log pitch control for balance bots
|
||||
if (is_balancebot()) {
|
||||
DataFlash.Log_Write_PID(LOG_PIDP_MSG, g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info());
|
||||
}
|
||||
}
|
||||
|
||||
// Write a range finder depth message
|
||||
|
Loading…
Reference in New Issue
Block a user