mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: mark CSRV non-streaming
the rate of CAN servo messages is controlled by the servo. Having this streaming means we can miss logging when there is more than one CAN servo. In the future we will move to holding the CAN servo data in a data structure like we do for ESCs, and then log at a regular rate, but for now this fixes the issue
This commit is contained in:
parent
3ec92731d4
commit
8053c40993
|
@ -1218,7 +1218,7 @@ LOG_STRUCTURE_FROM_AVOIDANCE \
|
|||
"TERR","QBLLHffHHf","TimeUS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded,ROfs", "s-DU-mm--m", "F-GG-00--0", true }, \
|
||||
LOG_STRUCTURE_FROM_ESC_TELEM \
|
||||
{ LOG_CSRV_MSG, sizeof(log_CSRV), \
|
||||
"CSRV","QBfffBfffffB","TimeUS,Id,Pos,Force,Speed,Pow,PosCmd,V,A,MotT,PCBT,Err", "s#---%dvAOO-", "F-000000000-", true }, \
|
||||
"CSRV","QBfffBfffffB","TimeUS,Id,Pos,Force,Speed,Pow,PosCmd,V,A,MotT,PCBT,Err", "s#---%dvAOO-", "F-000000000-", false }, \
|
||||
{ LOG_PIDR_MSG, sizeof(log_PID), \
|
||||
"PIDR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS, true }, \
|
||||
{ LOG_PIDP_MSG, sizeof(log_PID), \
|
||||
|
|
Loading…
Reference in New Issue