forked from Archive/PX4-Autopilot
esc_report: change esc_temperature field to allow negative values
Signed-off-by: Claudio Micheli <claudio@auterion.com>
This commit is contained in:
parent
7d7200cf2f
commit
fa4fc5f347
|
@ -3,7 +3,7 @@ uint32 esc_errorcount # Number of reported errors by ESC - if supported
|
||||||
int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if supported
|
int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if supported
|
||||||
float32 esc_voltage # Voltage measured from current ESC [V] - if supported
|
float32 esc_voltage # Voltage measured from current ESC [V] - if supported
|
||||||
float32 esc_current # Current measured from current ESC [A] - if supported
|
float32 esc_current # Current measured from current ESC [A] - if supported
|
||||||
uint8 esc_temperature # Temperature measured from current ESC [degC] - if supported
|
float32 esc_temperature # Temperature measured from current ESC [degC] - if supported
|
||||||
uint8 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver)
|
uint8 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver)
|
||||||
|
|
||||||
uint8 esc_state # State of ESC - depend on Vendor
|
uint8 esc_state # State of ESC - depend on Vendor
|
||||||
|
|
|
@ -203,7 +203,7 @@ void DShot::handle_new_telemetry_data(const int motor_index, const DShotTelemetr
|
||||||
esc_status.esc[motor_index].esc_rpm = (static_cast<int>(data.erpm) * 100) / (_param_mot_pole_count.get() / 2);
|
esc_status.esc[motor_index].esc_rpm = (static_cast<int>(data.erpm) * 100) / (_param_mot_pole_count.get() / 2);
|
||||||
esc_status.esc[motor_index].esc_voltage = static_cast<float>(data.voltage) * 0.01f;
|
esc_status.esc[motor_index].esc_voltage = static_cast<float>(data.voltage) * 0.01f;
|
||||||
esc_status.esc[motor_index].esc_current = static_cast<float>(data.current) * 0.01f;
|
esc_status.esc[motor_index].esc_current = static_cast<float>(data.current) * 0.01f;
|
||||||
esc_status.esc[motor_index].esc_temperature = data.temperature;
|
esc_status.esc[motor_index].esc_temperature = static_cast<float>(data.temperature);
|
||||||
// TODO: accumulate consumption and use for battery estimation
|
// TODO: accumulate consumption and use for battery estimation
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -297,7 +297,7 @@ bool TAP_ESC::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], u
|
||||||
_esc_feedback.esc[feed_back_data.channelID].esc_current = feed_back_data.current;
|
_esc_feedback.esc[feed_back_data.channelID].esc_current = feed_back_data.current;
|
||||||
#endif // ESC_HAVE_CURRENT_SENSOR
|
#endif // ESC_HAVE_CURRENT_SENSOR
|
||||||
#if defined(ESC_HAVE_TEMPERATURE_SENSOR)
|
#if defined(ESC_HAVE_TEMPERATURE_SENSOR)
|
||||||
_esc_feedback.esc[feed_back_data.channelID].esc_temperature = feed_back_data.temperature;
|
_esc_feedback.esc[feed_back_data.channelID].esc_temperature = static_cast<float>(feed_back_data.temperature);
|
||||||
#endif // ESC_HAVE_TEMPERATURE_SENSOR
|
#endif // ESC_HAVE_TEMPERATURE_SENSOR
|
||||||
_esc_feedback.esc[feed_back_data.channelID].esc_state = feed_back_data.ESCStatus;
|
_esc_feedback.esc[feed_back_data.channelID].esc_state = feed_back_data.ESCStatus;
|
||||||
_esc_feedback.esc[feed_back_data.channelID].failures = 0;
|
_esc_feedback.esc[feed_back_data.channelID].failures = 0;
|
||||||
|
|
|
@ -115,7 +115,7 @@ publish_gam_message(const uint8_t *buffer)
|
||||||
esc.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_PPM;
|
esc.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_PPM;
|
||||||
|
|
||||||
esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
|
esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
|
||||||
esc.esc[0].esc_temperature = msg.temperature1 - 20;
|
esc.esc[0].esc_temperature = static_cast<float>(msg.temperature1 - 20);
|
||||||
esc.esc[0].esc_voltage = static_cast<float>((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff)) * 0.1F;
|
esc.esc[0].esc_voltage = static_cast<float>((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff)) * 0.1F;
|
||||||
esc.esc[0].esc_current = static_cast<float>((msg.current_H << 8) | (msg.current_L & 0xff)) * 0.1F;
|
esc.esc[0].esc_current = static_cast<float>((msg.current_H << 8) | (msg.current_L & 0xff)) * 0.1F;
|
||||||
|
|
||||||
|
@ -186,7 +186,9 @@ build_gam_response(uint8_t *buffer, size_t *size)
|
||||||
msg.gam_sensor_id = GAM_SENSOR_ID;
|
msg.gam_sensor_id = GAM_SENSOR_ID;
|
||||||
msg.sensor_text_id = GAM_SENSOR_TEXT_ID;
|
msg.sensor_text_id = GAM_SENSOR_TEXT_ID;
|
||||||
|
|
||||||
msg.temperature1 = esc.esc[0].esc_temperature + 20;
|
const int16_t esc_temp_offset_degC = (esc.esc[0].esc_temperature + 20) > UINT8_MAX ? UINT8_MAX :
|
||||||
|
(esc.esc[0].esc_temperature + 20);
|
||||||
|
msg.temperature1 = (esc_temp_offset_degC < 0) ? 0 : esc_temp_offset_degC;
|
||||||
msg.temperature2 = 20; // 0 deg. C.
|
msg.temperature2 = 20; // 0 deg. C.
|
||||||
|
|
||||||
const uint16_t voltage = (uint16_t)(esc.esc[0].esc_voltage * 10.0F);
|
const uint16_t voltage = (uint16_t)(esc.esc[0].esc_voltage * 10.0F);
|
||||||
|
|
|
@ -82,7 +82,8 @@ private:
|
||||||
for (int esc_index = 0; esc_index < batch_size ; esc_index++) {
|
for (int esc_index = 0; esc_index < batch_size ; esc_index++) {
|
||||||
msg.failure_flags[esc_index] = esc_status.esc[esc_index].failures;
|
msg.failure_flags[esc_index] = esc_status.esc[esc_index].failures;
|
||||||
msg.error_count[esc_index] = esc_status.esc[esc_index].esc_errorcount;
|
msg.error_count[esc_index] = esc_status.esc[esc_index].esc_errorcount;
|
||||||
msg.temperature[esc_index] = esc_status.esc[esc_index].esc_temperature;
|
msg.temperature[esc_index] = static_cast<int16_t>(esc_status.esc[esc_index].esc_temperature *
|
||||||
|
100.f); // convert to centiDegrees
|
||||||
}
|
}
|
||||||
|
|
||||||
mavlink_msg_esc_info_send_struct(_mavlink->get_channel(), &msg);
|
mavlink_msg_esc_info_send_struct(_mavlink->get_channel(), &msg);
|
||||||
|
|
Loading…
Reference in New Issue