mirror of https://github.com/ArduPilot/ardupilot
Dataflash: Replace ppm (pulses per minute) with PWM in the RC channels
This commit is contained in:
parent
4fd37d17f0
commit
5de3382ab4
|
@ -99,6 +99,7 @@ const struct UnitStructure log_Units[] = {
|
|||
{ 'r', "rad" }, // radians
|
||||
{ 'U', "deglongitude" }, // degrees of longitude
|
||||
{ 'u', "ppm" }, // pulses per minute
|
||||
{ 'U', "us" }, // pulse width modulation in microseconds
|
||||
{ 'v', "V" }, // Volt
|
||||
{ 'P', "Pa" }, // Pascal
|
||||
{ 'w', "Ohm" }, // Ohm
|
||||
|
@ -1195,9 +1196,9 @@ Format characters in the format string for binary log messages
|
|||
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
||||
"MSG", "QZ", "TimeUS,Message", "s-", "F-"}, \
|
||||
{ LOG_RCIN_MSG, sizeof(log_RCIN), \
|
||||
"RCIN", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "suuuuuuuuuuuuuu", "F--------------" }, \
|
||||
"RCIN", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sUUUUUUUUUUUUUU", "F--------------" }, \
|
||||
{ LOG_RCOUT_MSG, sizeof(log_RCOUT), \
|
||||
"RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "suuuuuuuuuuuuuu", "F--------------" }, \
|
||||
"RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sUUUUUUUUUUUUUU", "F--------------" }, \
|
||||
{ LOG_RSSI_MSG, sizeof(log_RSSI), \
|
||||
"RSSI", "Qf", "TimeUS,RXRSSI", "s-", "F-" }, \
|
||||
{ LOG_BARO_MSG, sizeof(log_BARO), \
|
||||
|
|
Loading…
Reference in New Issue