PX4 Firmware
PX4 Autopilot Software http://px4.io
sPort_data.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
4  * Author: Stefan Rado <px4@sradonia.net>
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions
8  * are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * 2. Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in
14  * the documentation and/or other materials provided with the
15  * distribution.
16  * 3. Neither the name PX4 nor the names of its contributors may be
17  * used to endorse or promote products derived from this software
18  * without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
27  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
28  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  ****************************************************************************/
34 
35 /**
36  * @file sPort_data.h
37  * @author Mark Whitehorn <kd0aij@github.com>
38  *
39  * FrSky SmartPort telemetry implementation.
40  *
41  */
42 #ifndef _SPORT_DATA_H
43 #define _SPORT_DATA_H
44 
45 #include <sys/types.h>
46 #include <stdbool.h>
47 
48 /* FrSky SmartPort polling IDs captured from X4R */
49 #define SMARTPORT_POLL_1 0x1B
50 #define SMARTPORT_POLL_2 0x34
51 #define SMARTPORT_POLL_3 0x95
52 #define SMARTPORT_POLL_4 0x16
53 #define SMARTPORT_POLL_5 0xB7
54 #define SMARTPORT_POLL_6 0x00
55 #define SMARTPORT_POLL_7 0x83
56 #define SMARTPORT_POLL_8 0xBA
57 #define SMARTPORT_SENSOR_ID_SP2UR 0xC6 // Sensor ID 6
58 
59 /* FrSky SmartPort sensor IDs. See more here: https://github.com/opentx/opentx/blob/2.2/radio/src/telemetry/frsky.h */
60 #define SMARTPORT_ID_RSSI 0xf101
61 #define SMARTPORT_ID_RXA1 0xf102 // supplied by RX
62 #define SMARTPORT_ID_RXA2 0xf103 // supplied by RX
63 #define SMARTPORT_ID_BATV 0xf104
64 #define SMARTPORT_ID_SWR 0xf105 // Standing Wave Ratio
65 #define SMARTPORT_ID_T1 0x0400
66 #define SMARTPORT_ID_T2 0x0410
67 #define SMARTPORT_ID_RPM 0x0500
68 #define SMARTPORT_ID_FUEL 0x0600
69 #define SMARTPORT_ID_ALT 0x0100
70 #define SMARTPORT_ID_VARIO 0x0110 //VSPEED
71 #define SMARTPORT_ID_ACCX 0x0700
72 #define SMARTPORT_ID_ACCY 0x0710
73 #define SMARTPORT_ID_ACCZ 0x0720
74 #define SMARTPORT_ID_CURR 0x0200
75 #define SMARTPORT_ID_VFAS 0x0210 //Volt per Cell
76 #define SMARTPORT_ID_CELLS 0x0300
77 #define SMARTPORT_ID_GPS_LON_LAT 0x0800
78 #define SMARTPORT_ID_GPS_ALT 0x0820
79 #define SMARTPORT_ID_GPS_SPD 0x0830
80 #define SMARTPORT_ID_GPS_CRS 0x0840
81 #define SMARTPORT_ID_GPS_TIME 0x0850
82 #define SMARTPORT_ID_DIY_FIRST 0x5000
83 #define SMARTPORT_ID_DIY_LAST 0x50ff //We have 256 possible ID's for custom values :)
84 #define SMARTPORT_ID_DIY_NAVSTATE 0x5000
85 #define SMARTPORT_ID_DIY_GPSFIX 0x5001
86 
87 // Public functions
88 bool sPort_init(void);
89 void sPort_deinit(void);
90 void sPort_update_topics(void);
91 void sPort_send_data(int uart, uint16_t id, uint32_t data);
92 void sPort_send_BATV(int uart);
93 void sPort_send_CUR(int uart);
94 void sPort_send_ALT(int uart);
95 void sPort_send_SPD(int uart);
96 void sPort_send_VSPD(int uart, float speed);
97 void sPort_send_FUEL(int uart);
98 void sPort_send_GPS_LON(int uart);
99 void sPort_send_GPS_LAT(int uart);
100 void sPort_send_GPS_ALT(int uart);
101 void sPort_send_GPS_SPD(int uart);
102 void sPort_send_GPS_CRS(int uart);
103 void sPort_send_GPS_TIME(int uart);
104 void sPort_send_flight_mode(int uart);
105 void sPort_send_GPS_info(int uart);
106 
107 void sPort_send_NAV_STATE(int uart);
108 void sPort_send_GPS_FIX(int uart);
109 
110 #endif /* _SPORT_TELEMETRY_H */
void sPort_send_GPS_LAT(int uart)
Definition: sPort_data.cpp:245
void sPort_send_NAV_STATE(int uart)
Definition: sPort_data.cpp:311
void sPort_send_GPS_SPD(int uart)
Definition: sPort_data.cpp:298
void sPort_send_data(int uart, uint16_t id, uint32_t data)
Sends one data id/value pair.
Definition: sPort_data.cpp:146
void sPort_send_SPD(int uart)
Definition: sPort_data.cpp:205
void sPort_send_GPS_ALT(int uart)
Definition: sPort_data.cpp:256
void sPort_send_GPS_CRS(int uart)
Definition: sPort_data.cpp:263
void sPort_send_GPS_info(int uart)
Definition: sPort_data.cpp:337
void sPort_update_topics(void)
Definition: sPort_data.cpp:102
void sPort_send_CUR(int uart)
Definition: sPort_data.cpp:187
void sPort_send_GPS_LON(int uart)
Definition: sPort_data.cpp:231
uint8_t * data
Definition: dataman.cpp:149
void sPort_deinit(void)
Definition: sPort_data.cpp:94
void sPort_send_GPS_FIX(int uart)
Definition: sPort_data.cpp:321
void sPort_send_ALT(int uart)
Definition: sPort_data.cpp:197
void sPort_send_FUEL(int uart)
Definition: sPort_data.cpp:224
void sPort_send_BATV(int uart)
Definition: sPort_data.cpp:179
bool sPort_init(void)
Initializes the uORB subscriptions.
Definition: sPort_data.cpp:83
void sPort_send_flight_mode(int uart)
Definition: sPort_data.cpp:330
void sPort_send_VSPD(int uart, float speed)
Definition: sPort_data.cpp:216
void sPort_send_GPS_TIME(int uart)
Definition: sPort_data.cpp:275