forked from Archive/PX4-Autopilot
esc_report: remove unused fields to reduce message size
esc_setpoint in UAVCAN was just wrong, this is what it really is: uint7 power_rating_pct # Instant demand factor in percent (percent of maximum power); range 0% to 127%.
This commit is contained in:
parent
0db0981b1b
commit
6854b14dd6
|
@ -4,7 +4,5 @@ int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if support
|
|||
float32 esc_voltage # Voltage measured from current ESC [V] - 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_setpoint # setpoint of current ESC
|
||||
uint16 esc_setpoint_raw # setpoint of current ESC (Value sent to ESC)
|
||||
uint16 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
|
||||
|
|
|
@ -219,7 +219,6 @@ int DfBebopBusWrapper::_publish(struct bebop_state_data &data)
|
|||
for (int i = 0; i < 4; i++) {
|
||||
esc_status.esc[_esc_map[i]].timestamp = esc_status.timestamp;
|
||||
esc_status.esc[_esc_map[i]].esc_rpm = data.rpm[i];
|
||||
esc_status.esc[_esc_map[i]].esc_setpoint_raw = esc_speed_setpoint_rpm[i];
|
||||
}
|
||||
|
||||
// TODO: when is this ever blocked?
|
||||
|
|
|
@ -617,16 +617,6 @@ MK::task_main()
|
|||
esc.esc[i].esc_voltage = 0.0F;
|
||||
esc.esc[i].esc_current = static_cast<float>(Motor[i].Current) * 0.1F;
|
||||
esc.esc[i].esc_rpm = (uint16_t) 0;
|
||||
esc.esc[i].esc_setpoint = (float) Motor[i].SetPoint_PX4;
|
||||
|
||||
if (Motor[i].Version == 1) {
|
||||
// BLCtrl 2.0 (11Bit)
|
||||
esc.esc[i].esc_setpoint_raw = (uint16_t)(Motor[i].SetPoint << 3) | Motor[i].SetPointLowerBits;
|
||||
|
||||
} else {
|
||||
// BLCtrl < 2.0 (8Bit)
|
||||
esc.esc[i].esc_setpoint_raw = (uint16_t) Motor[i].SetPoint;
|
||||
}
|
||||
|
||||
esc.esc[i].esc_temperature = static_cast<uint8_t>(Motor[i].Temperature);
|
||||
esc.esc[i].esc_state = (uint8_t) Motor[i].State;
|
||||
|
|
|
@ -129,7 +129,6 @@ UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
|
|||
|
||||
msg.cmd.push_back(static_cast<int>(scaled));
|
||||
|
||||
_esc_status.esc[i].esc_setpoint_raw = abs(static_cast<int>(scaled));
|
||||
actuator_outputs.output[i] = scaled;
|
||||
|
||||
} else {
|
||||
|
@ -201,7 +200,6 @@ UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure<uavca
|
|||
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 = msg.rpm;
|
||||
ref.esc_errorcount = msg.error_count;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue