PX4 Firmware
PX4 Autopilot Software http://px4.io
atxxxx.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #pragma once
35 
36 /**
37  * @file atxxxx.h
38  * @author Daniele Pettenuzzo
39  *
40  * Driver for the ATXXXX chip on the omnibus fcu connected via SPI.
41  */
42 #include <drivers/device/spi.h>
43 #include <drivers/drv_hrt.h>
44 #include <parameters/param.h>
45 #include <px4_platform_common/px4_config.h>
46 #include <px4_platform_common/getopt.h>
47 #include <px4_platform_common/module.h>
48 #include <px4_platform_common/module_params.h>
49 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
50 #include <uORB/Subscription.hpp>
54 
55 /* Configuration Constants */
56 #ifdef PX4_SPI_BUS_OSD
57 #define OSD_BUS PX4_SPI_BUS_OSD
58 #else
59 #error "add the required spi bus from board_config.h here"
60 #endif
61 
62 #ifdef PX4_SPIDEV_OSD
63 #define OSD_SPIDEV PX4_SPIDEV_OSD
64 #else
65 #error "add the required spi device from board_config.h here"
66 #endif
67 
68 #define OSD_SPI_BUS_SPEED (2000000L) /* 2 MHz */
69 
70 #define DIR_READ(a) ((a) | (1 << 7))
71 #define DIR_WRITE(a) ((a) & 0x7f)
72 
73 #define OSD_CHARS_PER_ROW 30
74 #define OSD_NUM_ROWS_PAL 16
75 #define OSD_NUM_ROWS_NTSC 13
76 #define OSD_ZERO_BYTE 0x00
77 #define OSD_PAL_TX_MODE 0x40
78 
79 extern "C" __EXPORT int atxxxx_main(int argc, char *argv[]);
80 
81 class OSDatxxxx : public device::SPI, public ModuleBase<OSDatxxxx>, public ModuleParams, public px4::ScheduledWorkItem
82 {
83 public:
84  OSDatxxxx(int bus = OSD_BUS);
85 
86  ~OSDatxxxx();
87 
88  virtual int init();
89 
90  /**
91  * @see ModuleBase::custom_command
92  */
93  static int custom_command(int argc, char *argv[]);
94 
95  /**
96  * @see ModuleBase::print_usage
97  */
98  static int print_usage(const char *reason = nullptr);
99 
100  /**
101  * @see ModuleBase::task_spawn
102  */
103  static int task_spawn(int argc, char *argv[]);
104 
105 protected:
106  virtual int probe();
107 
108 private:
109  void Run() override;
110 
111  int start();
112 
113  int reset();
114 
115  int init_osd();
116 
117  int readRegister(unsigned reg, uint8_t *data, unsigned count);
118  int writeRegister(unsigned reg, uint8_t data);
119 
120  int add_character_to_screen(char c, uint8_t pos_x, uint8_t pos_y);
121  void add_string_to_screen_centered(const char *str, uint8_t pos_y, int max_length);
122  void clear_line(uint8_t pos_x, uint8_t pos_y, int length);
123 
124  int add_battery_info(uint8_t pos_x, uint8_t pos_y);
125  int add_altitude(uint8_t pos_x, uint8_t pos_y);
126  int add_flighttime(float flight_time, uint8_t pos_x, uint8_t pos_y);
127 
128  static const char *get_flight_mode(uint8_t nav_state);
129 
130  int enable_screen();
131  int disable_screen();
132 
133  int update_topics();
134  int update_screen();
135 
139 
140  // battery
143  bool _battery_valid{false};
144 
145  // altitude
146  float _local_position_z{0.f};
148 
149  // flight time
150  uint8_t _arming_state{0};
151  uint64_t _arming_timestamp{0};
152 
153  // flight mode
154  uint8_t _nav_state{0};
155 
156  DEFINE_PARAMETERS(
157  (ParamInt<px4::params::OSD_ATXXXX_CFG>) _param_osd_atxxxx_cfg
158  )
159 };
int add_flighttime(float flight_time, uint8_t pos_x, uint8_t pos_y)
Definition: atxxxx.cpp:322
float _battery_voltage_filtered_v
Definition: atxxxx.h:141
int enable_screen()
Definition: atxxxx.cpp:338
uORB::Subscription _local_position_sub
Definition: atxxxx.h:137
bool _local_position_valid
Definition: atxxxx.h:147
int start()
Definition: atxxxx.cpp:132
void Run() override
Definition: atxxxx.cpp:524
__EXPORT int atxxxx_main(int argc, char *argv[])
Definition: atxxxx.cpp:566
virtual int init()
Definition: atxxxx.cpp:98
Definition: I2C.hpp:51
static int print_usage(const char *reason=nullptr)
Definition: atxxxx.cpp:537
int readRegister(unsigned reg, uint8_t *data, unsigned count)
Definition: atxxxx.cpp:174
static int custom_command(int argc, char *argv[])
Definition: atxxxx.cpp:560
~OSDatxxxx()
Definition: atxxxx.cpp:56
High-resolution timer with callouts and timekeeping.
void add_string_to_screen_centered(const char *str, uint8_t pos_y, int max_length)
Definition: atxxxx.cpp:242
int disable_screen()
Definition: atxxxx.cpp:350
Global flash based parameter store.
int add_altitude(uint8_t pos_x, uint8_t pos_y)
Definition: atxxxx.cpp:306
uint8_t _arming_state
Definition: atxxxx.h:150
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
float _local_position_z
Definition: atxxxx.h:146
bool _battery_valid
Definition: atxxxx.h:143
int update_topics()
Definition: atxxxx.cpp:362
uint8_t _nav_state
Definition: atxxxx.h:154
uint8_t * data
Definition: dataman.cpp:149
int reset()
Definition: atxxxx.cpp:515
int update_screen()
Definition: atxxxx.cpp:480
float _battery_discharge_mah
Definition: atxxxx.h:142
void clear_line(uint8_t pos_x, uint8_t pos_y, int length)
Definition: atxxxx.cpp:267
int writeRegister(unsigned reg, uint8_t data)
Definition: atxxxx.cpp:193
static int task_spawn(int argc, char *argv[])
Definition: atxxxx.cpp:62
int add_battery_info(uint8_t pos_x, uint8_t pos_y)
Definition: atxxxx.cpp:275
virtual int probe()
Definition: atxxxx.cpp:140
static const char * get_flight_mode(uint8_t nav_state)
Definition: atxxxx.cpp:414
uint64_t _arming_timestamp
Definition: atxxxx.h:151
uORB::Subscription _vehicle_status_sub
Definition: atxxxx.h:138
int init_osd()
Definition: atxxxx.cpp:156
int add_character_to_screen(char c, uint8_t pos_x, uint8_t pos_y)
Definition: atxxxx.cpp:211
OSDatxxxx(int bus=OSD_BUS)
Definition: atxxxx.cpp:49
uORB::Subscription _battery_sub
Definition: atxxxx.h:136