diff options
author | Pavel Kirienko <pavel.kirienko@gmail.com> | 2014-10-13 17:01:34 +0400 |
---|---|---|
committer | Pavel Kirienko <pavel.kirienko@gmail.com> | 2014-10-13 17:01:34 +0400 |
commit | 1bf4270e3ee6f33f8adf0027c1a59f3fc0b35263 (patch) | |
tree | 1792240a25145c5cdbe2dad91f230e192655e0bd /src/modules/uORB | |
parent | e5a77a638a53aa9baec2ffe9d8ad96fb095b0966 (diff) | |
download | px4-firmware-1bf4270e3ee6f33f8adf0027c1a59f3fc0b35263.tar.gz px4-firmware-1bf4270e3ee6f33f8adf0027c1a59f3fc0b35263.tar.bz2 px4-firmware-1bf4270e3ee6f33f8adf0027c1a59f3fc0b35263.zip |
Update ORB topic 'esc_status'
Diffstat (limited to 'src/modules/uORB')
-rw-r--r-- | src/modules/uORB/topics/esc_status.h | 19 |
1 files changed, 10 insertions, 9 deletions
diff --git a/src/modules/uORB/topics/esc_status.h b/src/modules/uORB/topics/esc_status.h index 628824efa..b82796908 100644 --- a/src/modules/uORB/topics/esc_status.h +++ b/src/modules/uORB/topics/esc_status.h @@ -78,6 +78,7 @@ enum ESC_CONNECTION_TYPE { /** * Electronic speed controller status. + * Unsupported float fields should be assigned NaN. */ struct esc_status_s { /* use of a counter and timestamp recommended (but not necessary) */ @@ -89,17 +90,17 @@ struct esc_status_s { enum ESC_CONNECTION_TYPE esc_connectiontype; /**< how ESCs connected to the system */ struct { - uint16_t esc_address; /**< Address of current ESC (in most cases 1-8 / must be set by driver) */ enum ESC_VENDOR esc_vendor; /**< Vendor of current ESC */ - uint16_t esc_version; /**< Version of current ESC - if supported */ - uint16_t esc_voltage; /**< Voltage measured from current ESC - if supported */ - uint16_t esc_current; /**< Current measured from current ESC (100mA steps) - if supported */ - uint16_t esc_rpm; /**< RPM measured from current ESC - if supported */ - uint16_t esc_temperature; /**< Temperature measured from current ESC - if supported */ - float esc_setpoint; /**< setpoint of current ESC */ + uint32_t esc_errorcount; /**< Number of reported errors by ESC - if supported */ + float esc_voltage; /**< Voltage measured from current ESC [V] - if supported */ + float esc_current; /**< Current measured from current ESC [A] - if supported */ + float esc_temperature; /**< Temperature measured from current ESC [degC] - if supported */ + float esc_setpoint; /**< setpoint of current ESC */ uint16_t esc_setpoint_raw; /**< setpoint of current ESC (Value sent to ESC) */ - uint16_t esc_state; /**< State of ESC - depend on Vendor */ - uint16_t esc_errorcount; /**< Number of reported errors by ESC - if supported */ + uint16_t esc_address; /**< Address of current ESC (in most cases 1-8 / must be set by driver) */ + uint16_t esc_version; /**< Version of current ESC - if supported */ + uint16_t esc_rpm; /**< RPM measured from current ESC [RPM] - if supported */ + uint16_t esc_state; /**< State of ESC - depend on Vendor */ } esc[CONNECTED_ESC_MAX]; }; |