mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 07:15:18 +03:00
More HoTT code style cleanups.
This commit is contained in:
parent
6a4614e116
commit
993edc4e20
2 changed files with 18 additions and 18 deletions
|
@ -139,7 +139,7 @@ void hottV4GPSUpdate(void)
|
||||||
* Writes cell 1-4 high, low values and if not available
|
* Writes cell 1-4 high, low values and if not available
|
||||||
* calculates vbat.
|
* calculates vbat.
|
||||||
*/
|
*/
|
||||||
static void hottV4EAMUpdateBattery()
|
static void hottV4EAMUpdateBattery(void)
|
||||||
{
|
{
|
||||||
#if 0
|
#if 0
|
||||||
HoTTV4ElectricAirModule.cell1L = 4.2f * 10 * 5; // 2mv step
|
HoTTV4ElectricAirModule.cell1L = 4.2f * 10 * 5; // 2mv step
|
||||||
|
@ -171,7 +171,7 @@ static void hottV4EAMUpdateBattery()
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void hottV4EAMUpdateTemperatures()
|
static void hottV4EAMUpdateTemperatures(void)
|
||||||
{
|
{
|
||||||
HoTTV4ElectricAirModule.temp1 = 20 + 0;
|
HoTTV4ElectricAirModule.temp1 = 20 + 0;
|
||||||
HoTTV4ElectricAirModule.temp2 = 20;
|
HoTTV4ElectricAirModule.temp2 = 20;
|
||||||
|
|
|
@ -8,7 +8,7 @@
|
||||||
#ifndef TELEMETRY_HOTT_H_
|
#ifndef TELEMETRY_HOTT_H_
|
||||||
#define TELEMETRY_HOTT_H_
|
#define TELEMETRY_HOTT_H_
|
||||||
|
|
||||||
/* ###### HoTT module specifications ###### */
|
/* HoTT module specifications */
|
||||||
|
|
||||||
#define HOTTV4_GENERAL_AIR_SENSOR_ID 0xD0
|
#define HOTTV4_GENERAL_AIR_SENSOR_ID 0xD0
|
||||||
|
|
||||||
|
@ -76,14 +76,14 @@ typedef enum {
|
||||||
HoTTv4NotificationReceiver = 0x35,
|
HoTTv4NotificationReceiver = 0x35,
|
||||||
} HoTTv4Notification;
|
} HoTTv4Notification;
|
||||||
|
|
||||||
/*-----------------------------------------------------------
|
/**
|
||||||
GPS
|
* GPS
|
||||||
Receiver -> GPS Sensor (Flightcontrol)
|
* Receiver -> GPS Sensor (Flightcontrol)
|
||||||
Byte 1: 0x80 = Receiver byte
|
* Byte 1: 0x80 = Receiver byte
|
||||||
Byte 2: 0x8A = GPS Sensor byte (witch data Transmitter wants to get)
|
* Byte 2: 0x8A = GPS Sensor byte (witch data Transmitter wants to get)
|
||||||
5ms Idle Line!
|
* 5ms Idle Line!
|
||||||
5ms delay
|
* 5ms delay
|
||||||
-----------------------------------------------------------*/
|
*/
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
uint8_t startByte; // Byte 1: 0x7C = Start byte data
|
uint8_t startByte; // Byte 1: 0x7C = Start byte data
|
||||||
|
@ -144,13 +144,13 @@ struct {
|
||||||
uint8_t endByte; // Byte 44: 0x7D End byte
|
uint8_t endByte; // Byte 44: 0x7D End byte
|
||||||
} HoTTV4GPSModule;
|
} HoTTV4GPSModule;
|
||||||
|
|
||||||
/*-----------------------------------------------------------
|
/**
|
||||||
EAM (Electric Air Module) 33620
|
* EAM (Electric Air Module) 33620
|
||||||
EmpfängerElectric Sensor
|
* EmpfängerElectric Sensor
|
||||||
Byte 1: 80 = Receiver byte
|
* Byte 1: 80 = Receiver byte
|
||||||
Byte 2: 8E = Electric Sensor byte
|
* Byte 2: 8E = Electric Sensor byte
|
||||||
5ms Idle Line!
|
* 5ms Idle Line!
|
||||||
*-----------------------------------------------------------*/
|
*/
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
uint8_t startByte;
|
uint8_t startByte;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue