AP_ToshibaCAN: rename millivolts to voltage_mv

also add some comments
This commit is contained in:
Randy Mackay 2019-10-30 14:21:50 +09:00
parent 614bb656b7
commit f6b669e3d8
2 changed files with 8 additions and 8 deletions

View File

@ -313,7 +313,7 @@ void AP_ToshibaCAN::loop()
if (esc_id < TOSHIBACAN_MAX_NUM_ESCS) {
WITH_SEMAPHORE(_telem_sem);
_telemetry[esc_id].rpm = be16toh(reply_data.rpm);
_telemetry[esc_id].millivolts = be16toh(reply_data.millivolts);
_telemetry[esc_id].voltage_mv = be16toh(reply_data.voltage_mv);
_telemetry[esc_id].count++;
_telemetry[esc_id].new_data = true;
_esc_present_bitmask |= ((uint32_t)1 << esc_id);
@ -431,7 +431,7 @@ void AP_ToshibaCAN::update()
if (_telemetry[i].new_data) {
logger->Write_ESC(i, time_us,
_telemetry[i].rpm * 100U,
_telemetry[i].millivolts * 0.1f,
_telemetry[i].voltage_mv * 0.1f,
0,
_telemetry[i].temperature * 100.0f,
0);
@ -481,7 +481,7 @@ void AP_ToshibaCAN::send_esc_telemetry_mavlink(uint8_t mav_chan)
for (uint8_t j = 0; j < 4; j++) {
uint8_t esc_id = i * 4 + j;
temperature[j] = _telemetry[esc_id].temperature;
voltage[j] = _telemetry[esc_id].millivolts * 0.1f;
voltage[j] = _telemetry[esc_id].voltage_mv * 0.1f;
rpm[j] = _telemetry[esc_id].rpm;
count[j] = _telemetry[esc_id].count;
}

View File

@ -69,10 +69,10 @@ private:
// telemetry data (rpm, voltage)
HAL_Semaphore _telem_sem;
struct telemetry_info_t {
uint16_t rpm;
uint16_t millivolts;
uint16_t temperature;
uint16_t count;
uint16_t rpm; // rpm
uint16_t voltage_mv; // voltage in millivolts
uint16_t temperature; // temperature in degrees
uint16_t count; // total number of packets sent
bool new_data;
} _telemetry[TOSHIBACAN_MAX_NUM_ESCS];
uint32_t _telemetry_req_ms; // system time (in milliseconds) to request data from escs (updated at 10hz)
@ -137,7 +137,7 @@ private:
uint8_t state:7;
uint16_t rpm;
uint16_t reserved;
uint16_t millivolts;
uint16_t voltage_mv; // voltage in millivolts
uint8_t position_est_error;
};
uint8_t data[8];