ardupilot/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp
Andy Piper 8df4e0f127 AP_ESC_Telem: generalise ESC telemetry to allow harmonic notch handling with other ESCs
refactor to capture and output slewed rpm values
enable with HAL_WITH_ESC_TELEM
move notch calculation to front end
refactor telemetry data into frontend
cope with blended data
add mavlink send function
log telemetry data in frontend
add SITL ESC telemetry
record volts, amps and consumption as floats
report telemetry transmission errors
disable ESC Telemetry inclusion when there is no need for it
move ESC_Telem logging to the AP_ESC_Telem class (by amilcar.lucas@iav.de)
various cleanups (by amilcar.lucas@iav.de)
add support for raw ESC rpm
check RPM validity for mavlink output
Use const when applicable
2021-05-12 17:01:11 +10:00

43 lines
1.6 KiB
C++

/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_ESC_Telem_Backend.h"
#include "AP_ESC_Telem.h"
#include <AP_HAL/AP_HAL.h>
#if HAL_WITH_ESC_TELEM
#include <AP_Math/AP_Math.h>
extern const AP_HAL::HAL& hal;
AP_ESC_Telem_Backend::AP_ESC_Telem_Backend() {
_frontend = AP_ESC_Telem::_singleton;
if (_frontend == nullptr) {
AP_HAL::panic("No ESC frontend");
}
}
// callback to update the rpm in the frontend, should be called by the driver when new data is available
void AP_ESC_Telem_Backend::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate) {
_frontend->update_rpm(esc_index, new_rpm, error_rate);
}
// callback to update the data in the frontend, should be called by the driver when new data is available
void AP_ESC_Telem_Backend::update_telem_data(const uint8_t esc_index, const TelemetryData& new_data, const uint16_t data_present_mask) {
_frontend->update_telem_data(esc_index, new_data, data_present_mask);
}
#endif