Merge pull request #10479 from iNavFlight/mmosca-fix-arming-flags-display
[inav.git] / src / main / io / gimbal_serial.h
blob6c9a3251f896c7f603dc0cadd01965f4c62d5db8
1 /*
2 * This file is part of INAV.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with INAV. If not, see <http://www.gnu.org/licenses/>.
18 #pragma once
20 #include <stdint.h>
22 #include "platform.h"
24 #include "common/time.h"
25 #include "drivers/gimbal_common.h"
26 #include "drivers/headtracker_common.h"
28 #ifdef __cplusplus
29 extern "C" {
30 #endif
32 #ifdef USE_SERIAL_GIMBAL
35 #define HTKATTITUDE_SYNC0 0xA5
36 #define HTKATTITUDE_SYNC1 0x5A
37 typedef struct gimbalHtkAttitudePkt_s
39 uint8_t sync[2]; //data synchronization 0xA5, 0x5A
40 uint8_t mode:3; //Gimbal Mode [0~7] [Only 0 1 2 modes are supported for the time being]
41 int16_t sensibility:5; // Stabilization sensibility [-16~15]
42 uint8_t reserved:4; //hold on to one's reserve
43 int32_t roll:12; //Roll angle [-2048~2047] => [-180~180]
44 int32_t tilt:12; //Pich angle [-2048~2047] => [-180~180]
45 int32_t pan:12; //Yaw angle [-2048~2047] => [-180~180]
46 uint8_t crch; //Data validation H
47 uint8_t crcl; //Data validation L
48 } __attribute__((packed)) gimbalHtkAttitudePkt_t;
51 #define HEADTRACKER_PAYLOAD_SIZE (sizeof(gimbalHtkAttitudePkt_t) - 4)
53 typedef enum {
54 WAITING_HDR1,
55 WAITING_HDR2,
56 WAITING_PAYLOAD,
57 WAITING_CRCH,
58 WAITING_CRCL,
59 } gimbalHeadtrackerState_e;
61 typedef struct gimbalSerialHtrkState_s {
62 uint8_t payloadSize;
63 gimbalHeadtrackerState_e state;
64 gimbalHtkAttitudePkt_t attitude;
65 } gimbalSerialHtrkState_t;
67 typedef struct gimbalSerialConfig_s {
68 bool singleUart;
69 } gimbalSerialConfig_t;
71 PG_DECLARE(gimbalSerialConfig_t, gimbalSerialConfig);
73 int16_t gimbal_scale12(int16_t inputMin, int16_t inputMax, int16_t value);
75 int16_t gimbal2pwm(int16_t value);
77 bool gimbalSerialInit(void);
78 bool gimbalSerialDetect(void);
79 void gimbalSerialProcess(gimbalDevice_t *gimbalDevice, timeUs_t currentTime);
80 bool gimbalSerialIsReady(const gimbalDevice_t *gimbalDevice);
81 gimbalDevType_e gimbalSerialGetDeviceType(const gimbalDevice_t *gimbalDevice);
82 bool gimbalSerialHasHeadTracker(const gimbalDevice_t *gimbalDevice);
83 void gimbalSerialHeadTrackerReceive(uint16_t c, void *data);
86 #if (defined(USE_HEADTRACKER) && defined(USE_HEADTRACKER_SERIAL))
87 bool gimbalSerialHeadTrackerInit(void);
88 bool gimbalSerialHeadTrackerDetect(void);
89 void headtrackerSerialProcess(headTrackerDevice_t *headTrackerDevice, timeUs_t currentTimeUs);
90 headTrackerDevType_e headtrackerSerialGetDeviceType(const headTrackerDevice_t *headTrackerDevice);
91 bool headTrackerSerialIsReady(const headTrackerDevice_t *headTrackerDevice);
92 bool headTrackerSerialIsValid(const headTrackerDevice_t *headTrackerDevice);
93 int headTrackerSerialGetPanPWM(const headTrackerDevice_t *headTrackerDevice);
94 int headTrackerSerialGetTiltPWM(const headTrackerDevice_t *headTrackerDevice);
95 int headTrackerSerialGetRollPWM(const headTrackerDevice_t *headTrackerDevice);
96 #endif
98 #endif
100 #ifdef __cplusplus
102 #endif