1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 04:15:44 +03:00
betaflight/src/main/sensors/esc_sensor.h
iso9660 0dd6d4d47a Unified all eRPM calculations into one single function
Fixed some review findings

Unified dshot average rpm calculations into one single function

Renamed calcEscRpm to erpmToRpm, and moved function to dshot.c

Removed unused esc_sensor.h header file from dshot.c

Removed esc_sensor.h header from modules that no longer needs it

Average RPM calculated by demmand only when rpm data is updated

Renamed rpm to averageRpm and fixed a bug

Update average rpm when telemetry data is received

Removed blank line

Fixed review findings

Fixed return values for erpmToRpm and getDshotAverageRpm so rpm value doesn't truncate

Restored osd_esc_rmp_alarm setting. This setting is used to set an alarm to notify when rpm  goes down a specified threshold. Rpm can go over 109krpm (1s 26kv motors setup), but a low rpm alarm doesn't have to be set to a so high value so at this time [0-32767] seems an acceptable range

Rebased to master
2022-09-17 00:26:17 +02:00

56 lines
1.7 KiB
C

/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "common/time.h"
typedef struct escSensorConfig_s {
uint8_t halfDuplex; // Set to false to listen on the TX pin for telemetry data
uint16_t offset; // offset consumed by the flight controller / VTX / cam / ... in milliampere
} escSensorConfig_t;
PG_DECLARE(escSensorConfig_t, escSensorConfig);
typedef struct {
uint8_t dataAge;
int8_t temperature; // C degrees
int16_t voltage; // 0.01V
int32_t current; // 0.01A
int32_t consumption; // mAh
int16_t rpm; // 0.01erpm
} escSensorData_t;
#define ESC_DATA_INVALID 255
#define ESC_BATTERY_AGE_MAX 10
bool escSensorInit(void);
void escSensorProcess(timeUs_t currentTime);
#define ESC_SENSOR_COMBINED 255
escSensorData_t *getEscSensorData(uint8_t motorNumber);
void startEscDataRead(uint8_t *frameBuffer, uint8_t frameLength);
uint8_t getNumberEscBytesRead(void);
uint8_t calculateCrc8(const uint8_t *Buf, const uint8_t BufLen);