Skip to content

Commit fca4e32

Browse files
committed
Tarot v1.50 support
1 parent e4e461d commit fca4e32

7 files changed

Lines changed: 80 additions & 63 deletions

File tree

Firmware/Bootloader/.project

Lines changed: 0 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -23,11 +23,4 @@
2323
<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
2424
<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
2525
</natures>
26-
<linkedResources>
27-
<link>
28-
<name>libs/spiffs</name>
29-
<type>2</type>
30-
<locationURI>PARENT-1-PROJECT_LOC/shared/Middleware/spiffs</locationURI>
31-
</link>
32-
</linkedResources>
3326
</projectDescription>

Firmware/Pro/include/Board.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
#include <Timer.h>
1919
#include <I2C.h>
2020

21-
#define FIRMWARE_VERSION 0x02020100
21+
#define FIRMWARE_VERSION 0x02020200
2222
#define HARDWARE_VERSION 0x01
2323

2424
namespace Board

Firmware/Releases/AnySensePro.bin

48 Bytes
Binary file not shown.

Firmware/shared/Application/include/FCTarot.h

Lines changed: 47 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -30,62 +30,69 @@ class FCTarot: public FCAdapter, public HAL::InterruptHandler
3030

3131
enum PaketType
3232
{
33-
GPS = 1,
34-
RC = 2,
35-
HomeData = 3,
33+
RC = 1, GPS = 2, Battery = 3, Time = 4,
3634
};
3735

38-
struct GPSType
36+
struct RCType //Paket 1
3937
{
40-
int32_t Longitude;
41-
int32_t Latitude;
42-
int16_t Altitude;
43-
int16_t Speed;
44-
int16_t Speed2;
45-
int16_t Climb;
46-
uint8_t unk1[2];
47-
uint16_t Voltage;
48-
uint8_t unk2[9];
49-
uint8_t Failsafe;
50-
uint8_t Flightmode;
51-
uint8_t unk3[2];
52-
uint8_t Satellites;
53-
uint8_t unk4[4];
54-
}__attribute__((packed, aligned(1)));
55-
56-
struct RCType
57-
{
58-
int16_t GyroX;
59-
int16_t GyroY;
60-
int16_t GyroZ;
61-
int16_t AccX;
62-
int16_t AccY;
63-
int16_t AccZ;
64-
int16_t Altitude;
6538
int8_t Aileron;
6639
int8_t Elevator;
6740
int8_t Throttle;
6841
int8_t Rudder;
6942
int8_t Mode;
70-
int8_t unk1;
43+
int8_t unused;
7144
int8_t GoHome;
7245
int8_t IOC;
7346
int8_t Gear;
7447
int8_t GimbalTilt;
7548
int8_t CamSwitch;
7649
int8_t InfoSwitch;
77-
int8_t unk2[4];
78-
uint8_t RCConnected;
50+
uint8_t unk1[15];
7951
uint8_t Armed;
80-
uint8_t unk3[6];
52+
uint8_t Failsafe;
53+
uint8_t unk2;
54+
uint8_t Flightmode;
55+
uint8_t unk3[2];
56+
uint8_t Satellites;
57+
uint8_t unk4[4];
8158
}__attribute__((packed, aligned(1)));
8259

83-
struct HomeDataType
60+
struct GPSType //Paket 2
8461
{
62+
int32_t HomeLongitude;
63+
int32_t HomeLatitude;
64+
int16_t HomeAltitude;
8565
int32_t Longitude;
8666
int32_t Latitude;
8767
int16_t Altitude;
88-
uint8_t unk1[28];
68+
int16_t Speed;
69+
int16_t Speed2;
70+
int16_t Climb;
71+
72+
int16_t GyroX;
73+
int16_t GyroY;
74+
int16_t GyroZ;
75+
int16_t AccX;
76+
int16_t AccY;
77+
int16_t AccZ;
78+
79+
}__attribute__((packed, aligned(1)));
80+
81+
struct BatteryType
82+
{
83+
uint8_t unk1[18];
84+
int16_t RawAltitude1;
85+
uint8_t unk2[2];
86+
int16_t Voltage;
87+
int16_t RawAltitude2;
88+
uint8_t unk3[12];
89+
}__attribute__((packed, aligned(1)));
90+
91+
struct TimeType
92+
{
93+
uint32_t Time;
94+
uint16_t unk2;
95+
uint8_t unk1[32];
8996
}__attribute__((packed, aligned(1)));
9097

9198
struct Paket
@@ -107,7 +114,8 @@ class FCTarot: public FCAdapter, public HAL::InterruptHandler
107114
uint8_t ContentData[PacketContentSize];
108115
GPSType GPS;
109116
RCType RC;
110-
HomeDataType HomeData;
117+
BatteryType Battery;
118+
TimeType Time;
111119
};
112120
uint16_t CRC;
113121
}__attribute__((packed, aligned(1)));
@@ -121,9 +129,10 @@ class FCTarot: public FCAdapter, public HAL::InterruptHandler
121129
uint8_t m_processIndex;
122130

123131
void Process(Paket& paket);
124-
void Process(GPSType& data);
125132
void Process(RCType& data);
126-
void Process(HomeDataType& data);
133+
void Process(GPSType& data);
134+
void Process(BatteryType& data);
135+
void Process(TimeType& data);
127136

128137
uint16_t calculateChecksum(const uint8_t* data, uint8_t size);
129138

Firmware/shared/Application/source/FCTarot.cpp

Lines changed: 30 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,8 @@ void FCTarot::Init()
2121
{
2222
static_assert (sizeof(FCTarot::GPSType) == FCTarot::PacketContentSize, "Tarot GPS PaketSize does not match!");
2323
static_assert (sizeof(FCTarot::RCType) == FCTarot::PacketContentSize, "Tarot RC PaketSize does not match!");
24-
static_assert (sizeof(FCTarot::HomeDataType) == FCTarot::PacketContentSize, "Tarot HomeData PaketSize does not match!");
24+
static_assert (sizeof(FCTarot::BatteryType) == FCTarot::PacketContentSize, "Tarot Battery PaketSize does not match!");
25+
static_assert (sizeof(FCTarot::TimeType) == FCTarot::PacketContentSize, "Tarot Time PaketSize does not match!");
2526

2627
static_assert (sizeof(FCTarot::Paket) == FCTarot::PaketSize, "Tarot PaketSize does not match!");
2728

@@ -117,18 +118,20 @@ void FCTarot::Process(Paket& paket)
117118
case PaketType::RC:
118119
Process(paket.RC);
119120
break;
120-
case PaketType::HomeData:
121-
Process(paket.HomeData);
121+
case PaketType::Battery:
122+
Process(paket.Battery);
123+
break;
124+
case PaketType::Time:
125+
Process(paket.Time);
126+
break;
122127
}
123128
}
124129

125-
void FCTarot::Process(GPSType& data)
130+
void FCTarot::Process(RCType& data)
126131
{
127-
SensorData.SetPositionCurrent(data.Latitude / 10000000.f, data.Longitude / 10000000.f);
128-
SensorData.SetAltitude(data.Altitude / 10.f);
129-
SensorData.SetSpeed(data.Speed / 10.f);
130-
SensorData.SetVerticalSpeed(data.Climb / 10.f);
131-
SensorData.SetBattery(data.Voltage * 10);
132+
SensorData.SetThrottle(data.Throttle * 10);
133+
134+
SensorData.SetArmed(data.Armed);
132135

133136
if (data.Failsafe != 0)
134137
SensorData.SetFlightMode(FlightMode::Failsafe);
@@ -142,18 +145,30 @@ void FCTarot::Process(GPSType& data)
142145
SensorData.SetSatellites(data.Satellites);
143146
SensorData.SetFixType(data.Satellites == 0 ? GPSFixType::FixNo : data.Satellites < 4 ? GPSFixType::Fix2D : GPSFixType::Fix3D);
144147

148+
//TODO: Set RC Channels
145149
}
146150

147-
void FCTarot::Process(RCType& data)
151+
void FCTarot::Process(GPSType& data)
148152
{
149-
SensorData.SetArmed(data.Armed);
150-
//TODO: Set RC Channels
153+
SensorData.SetPositionHome(data.HomeLatitude / 10000000.f, data.HomeLongitude / 10000000.f);
154+
SensorData.SetHomeAltitude(data.HomeAltitude / 10.f);
155+
156+
SensorData.SetPositionCurrent(data.Latitude / 10000000.f, data.Longitude / 10000000.f);
157+
SensorData.SetAltitude(data.Altitude / 10.f);
158+
159+
SensorData.SetSpeed(data.Speed / 10.f);
160+
SensorData.SetVerticalSpeed(data.Climb / 10.f);
161+
}
162+
163+
void FCTarot::Process(BatteryType& data)
164+
{
165+
SensorData.SetBattery(data.Voltage * 10);
151166
}
152167

153-
void FCTarot::Process(HomeDataType& data)
168+
void FCTarot::Process(TimeType& data)
154169
{
155-
SensorData.SetHomeAltitude(data.Altitude / 10.f);
156-
SensorData.SetPositionHome(data.Latitude / 10000000.f, data.Longitude / 10000000.f);
170+
Utils::DateTime dt = Utils::DateTime(1467504000 + data.Time / 1000);
171+
SensorData.SetDateTime(dt);
157172
}
158173

159174
uint16_t FCTarot::calculateChecksum(const uint8_t* data, uint8_t size)

GroundTools/xeniC.AnySense.KonfigurationManager/xeniC.AnySense.KonfigurationManager/xeniC.AnySense.Studio.csproj

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@
3232
<WebPage>publish.htm</WebPage>
3333
<OpenBrowserOnPublish>false</OpenBrowserOnPublish>
3434
<ApplicationRevision>1</ApplicationRevision>
35-
<ApplicationVersion>2.2.1.%2a</ApplicationVersion>
35+
<ApplicationVersion>2.2.2.1</ApplicationVersion>
3636
<UseApplicationTrust>false</UseApplicationTrust>
3737
<CreateDesktopShortcut>true</CreateDesktopShortcut>
3838
<PublishWizardCompleted>true</PublishWizardCompleted>

GroundTools/xeniC.AnySense.Shared/xeniC.AnySense.Library/Devices/AnySensePro.cs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ namespace xeniC.AnySense.Library.Devices
1919
{
2020
public class AnySensePro : DeviceModelBase
2121
{
22-
private const UInt32 LatestVersion = 0x02020100;
22+
private const UInt32 LatestVersion = 0x02020200;
2323

2424
public AnySensePro(BaseMavlinkLayer mv, UInt32 version)
2525
: base(mv, version)

0 commit comments

Comments
 (0)