aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorPavel Kirienko <pavel.kirienko@gmail.com>2014-10-13 17:01:34 +0400
committerPavel Kirienko <pavel.kirienko@gmail.com>2014-10-13 17:01:34 +0400
commit1bf4270e3ee6f33f8adf0027c1a59f3fc0b35263 (patch)
tree1792240a25145c5cdbe2dad91f230e192655e0bd /src/modules
parente5a77a638a53aa9baec2ffe9d8ad96fb095b0966 (diff)
downloadpx4-firmware-1bf4270e3ee6f33f8adf0027c1a59f3fc0b35263.tar.gz
px4-firmware-1bf4270e3ee6f33f8adf0027c1a59f3fc0b35263.tar.bz2
px4-firmware-1bf4270e3ee6f33f8adf0027c1a59f3fc0b35263.zip
Update ORB topic 'esc_status'
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h14
-rw-r--r--src/modules/uORB/topics/esc_status.h19
-rw-r--r--src/modules/uavcan/actuators/esc.cpp14
3 files changed, 23 insertions, 24 deletions
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index d2845eb75..aeff4fd30 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -241,15 +241,15 @@ struct log_GPSP_s {
#define LOG_ESC_MSG 18
struct log_ESC_s {
uint16_t counter;
- uint8_t esc_count;
- uint8_t esc_connectiontype;
- uint8_t esc_num;
+ uint8_t esc_count;
+ uint8_t esc_connectiontype;
+ uint8_t esc_num;
uint16_t esc_address;
uint16_t esc_version;
- uint16_t esc_voltage;
- uint16_t esc_current;
+ float esc_voltage;
+ float esc_current;
uint16_t esc_rpm;
- uint16_t esc_temperature;
+ float esc_temperature;
float esc_setpoint;
uint16_t esc_setpoint_raw;
};
@@ -452,7 +452,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
LOG_FORMAT(GPOS, "LLfffffff", "Lat,Lon,Alt,VelN,VelE,VelD,EPH,EPV,TALT"),
LOG_FORMAT(GPSP, "BLLffBfbf", "NavState,Lat,Lon,Alt,Yaw,Type,LoitR,LoitDir,PitMin"),
- LOG_FORMAT(ESC, "HBBBHHHHHHfH", "count,nESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
+ LOG_FORMAT(ESC, "HBBBHHffHffH", "count,nESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"),
LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"),
LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"),
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];
};
diff --git a/src/modules/uavcan/actuators/esc.cpp b/src/modules/uavcan/actuators/esc.cpp
index 0601d9fa2..249ffba07 100644
--- a/src/modules/uavcan/actuators/esc.cpp
+++ b/src/modules/uavcan/actuators/esc.cpp
@@ -134,14 +134,12 @@ void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure<
ref.esc_address = msg.getSrcNodeID().get();
- // >0 checks allow to weed out NaNs and negative values that aren't supported.
- ref.esc_voltage = (msg.voltage > 0) ? msg.voltage * 10.0F : 0;
- ref.esc_current = (msg.current > 0) ? msg.current * 10.0F : 0;
- ref.esc_temperature = (msg.temperature > 0) ? msg.temperature * 10.0F : 0;
-
- ref.esc_setpoint = msg.power_rating_pct;
- ref.esc_rpm = abs(msg.rpm);
- ref.esc_errorcount = msg.error_count;
+ ref.esc_voltage = msg.voltage;
+ ref.esc_current = msg.current;
+ ref.esc_temperature = msg.temperature;
+ ref.esc_setpoint = msg.power_rating_pct;
+ ref.esc_rpm = abs(msg.rpm);
+ ref.esc_errorcount = msg.error_count;
}
}