Firmware
px4io.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2017 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 
42 #pragma once
43 
44 #include <px4_config.h>
45 
46 #include <stdbool.h>
47 #include <stdint.h>
48 
49 #include <board_config.h>
50 
51 #include "protocol.h"
52 
53 #include <pwm_limit/pwm_limit.h>
54 
55 /*
56  hotfix: we are critically short of memory in px4io and this is the
57  easiest way to reclaim about 800 bytes.
58  */
59 #define perf_alloc(a,b) NULL
60 
61 /*
62  * Constants and limits.
63  */
64 #define PX4IO_BL_VERSION 3
65 #define PX4IO_SERVO_COUNT 8
66 #define PX4IO_CONTROL_CHANNELS 8
67 #define PX4IO_CONTROL_GROUPS 4
68 #define PX4IO_RC_INPUT_CHANNELS 18
69 #define PX4IO_RC_MAPPED_CONTROL_CHANNELS 8
71 /*
72  * Debug logging
73  */
74 
75 #ifdef DEBUG
76 # include <debug.h>
77 # define debug(fmt, args...) syslog(LOG_DEBUG,fmt "\n", ##args)
78 #else
79 # define debug(fmt, args...) do {} while(0)
80 #endif
81 
82 /*
83  * Registers.
84  */
85 extern volatile uint16_t r_page_status[]; /* PX4IO_PAGE_STATUS */
86 extern uint16_t r_page_actuators[]; /* PX4IO_PAGE_ACTUATORS */
87 extern uint16_t r_page_servos[]; /* PX4IO_PAGE_SERVOS */
88 extern uint16_t r_page_direct_pwm[]; /* PX4IO_PAGE_DIRECT_PWM */
89 extern uint16_t r_page_raw_rc_input[]; /* PX4IO_PAGE_RAW_RC_INPUT */
90 extern uint16_t r_page_rc_input[]; /* PX4IO_PAGE_RC_INPUT */
91 extern uint16_t r_page_adc[]; /* PX4IO_PAGE_RAW_ADC_INPUT */
92 
93 extern volatile uint16_t r_page_setup[]; /* PX4IO_PAGE_SETUP */
94 extern uint16_t r_page_controls[]; /* PX4IO_PAGE_CONTROLS */
95 extern uint16_t r_page_rc_input_config[]; /* PX4IO_PAGE_RC_INPUT_CONFIG */
96 extern uint16_t r_page_servo_failsafe[]; /* PX4IO_PAGE_FAILSAFE_PWM */
97 extern uint16_t r_page_servo_control_min[]; /* PX4IO_PAGE_CONTROL_MIN_PWM */
98 extern uint16_t r_page_servo_control_max[]; /* PX4IO_PAGE_CONTROL_MAX_PWM */
99 extern int16_t r_page_servo_control_trim[]; /* PX4IO_PAGE_CONTROL_TRIM_PWM */
100 extern uint16_t r_page_servo_disarmed[]; /* PX4IO_PAGE_DISARMED_PWM */
101 
102 /*
103  * Register aliases.
104  *
105  * Handy aliases for registers that are widely used.
106  */
107 #define r_status_flags r_page_status[PX4IO_P_STATUS_FLAGS]
108 #define r_status_alarms r_page_status[PX4IO_P_STATUS_ALARMS]
109 
110 #define r_raw_rc_count r_page_raw_rc_input[PX4IO_P_RAW_RC_COUNT]
111 #define r_raw_rc_values (&r_page_raw_rc_input[PX4IO_P_RAW_RC_BASE])
112 #define r_raw_rc_flags r_page_raw_rc_input[PX4IO_P_RAW_RC_FLAGS]
113 #define r_rc_valid r_page_rc_input[PX4IO_P_RC_VALID]
114 #define r_rc_values (&r_page_rc_input[PX4IO_P_RC_BASE])
115 #define r_mixer_limits r_page_status[PX4IO_P_STATUS_MIXER]
116 
117 #define r_setup_features r_page_setup[PX4IO_P_SETUP_FEATURES]
118 #define r_setup_arming r_page_setup[PX4IO_P_SETUP_ARMING]
119 #define r_setup_pwm_rates r_page_setup[PX4IO_P_SETUP_PWM_RATES]
120 #define r_setup_pwm_defaultrate r_page_setup[PX4IO_P_SETUP_PWM_DEFAULTRATE]
121 #define r_setup_pwm_altrate r_page_setup[PX4IO_P_SETUP_PWM_ALTRATE]
122 #define r_setup_rc_thr_failsafe r_page_setup[PX4IO_P_SETUP_RC_THR_FAILSAFE_US]
123 
124 #define r_setup_pwm_reverse r_page_setup[PX4IO_P_SETUP_PWM_REVERSE]
125 
126 #define r_setup_trim_roll r_page_setup[PX4IO_P_SETUP_TRIM_ROLL]
127 #define r_setup_trim_pitch r_page_setup[PX4IO_P_SETUP_TRIM_PITCH]
128 #define r_setup_trim_yaw r_page_setup[PX4IO_P_SETUP_TRIM_YAW]
129 #define r_setup_scale_roll r_page_setup[PX4IO_P_SETUP_SCALE_ROLL]
130 #define r_setup_scale_pitch r_page_setup[PX4IO_P_SETUP_SCALE_PITCH]
131 #define r_setup_scale_yaw r_page_setup[PX4IO_P_SETUP_SCALE_YAW]
132 #define r_setup_sbus_rate r_page_setup[PX4IO_P_SETUP_SBUS_RATE]
133 #define r_setup_thr_fac r_page_setup[PX4IO_P_SETUP_THR_MDL_FAC]
134 #define r_setup_slew_max r_page_setup[PX4IO_P_SETUP_MOTOR_SLEW_MAX]
135 #define r_setup_airmode r_page_setup[PX4IO_P_SETUP_AIRMODE]
136 
137 #define r_control_values (&r_page_controls[0])
138 
139 /*
140  * System state structure.
141  */
142 struct sys_state_s {
143 
144  volatile uint64_t rc_channels_timestamp_received;
145  volatile uint64_t rc_channels_timestamp_valid;
146 
150  volatile uint64_t fmu_data_received_time;
151 
152 };
153 
154 extern struct sys_state_s system_state;
155 extern float dt;
156 extern bool update_mc_thrust_param;
157 extern bool update_trims;
158 
159 /*
160  * PWM limit structure
161  */
162 extern pwm_limit_t pwm_limit;
163 
164 /*
165  * GPIO handling.
166  */
167 #define LED_BLUE(_s) px4_arch_gpiowrite(GPIO_LED1, !(_s))
168 #define LED_AMBER(_s) px4_arch_gpiowrite(GPIO_LED2, !(_s))
169 #define LED_SAFETY(_s) px4_arch_gpiowrite(GPIO_LED3, !(_s))
170 #define LED_RING(_s) px4_arch_gpiowrite(GPIO_LED4, (_s))
171 
172 
173 # define PX4IO_RELAY_CHANNELS 0
174 # define ENABLE_SBUS_OUT(_s) px4_arch_gpiowrite(GPIO_SBUS_OENABLE, !(_s))
175 
176 # define VDD_SERVO_FAULT (!px4_arch_gpioread(GPIO_SERVO_FAULT_DETECT))
177 
178 # define PX4IO_ADC_CHANNEL_COUNT 2
179 # define ADC_VSERVO 4
180 # define ADC_RSSI 5
181 
182 #define BUTTON_SAFETY px4_arch_gpioread(GPIO_BTN_SAFETY)
183 
184 #define CONTROL_PAGE_INDEX(_group, _channel) (_group * PX4IO_CONTROL_CHANNELS + _channel)
185 
186 #define PX4_CRITICAL_SECTION(cmd) { irqstate_t flags = px4_enter_critical_section(); cmd; px4_leave_critical_section(flags); }
187 
188 #define PX4_ATOMIC_MODIFY_OR(target, modification) { if ((target | (modification)) != target) { PX4_CRITICAL_SECTION(target |= (modification)); } }
189 
190 #define PX4_ATOMIC_MODIFY_CLEAR(target, modification) { if ((target & ~(modification)) != target) { PX4_CRITICAL_SECTION(target &= ~(modification)); } }
191 
192 #define PX4_ATOMIC_MODIFY_AND(target, modification) { if ((target & (modification)) != target) { PX4_CRITICAL_SECTION(target &= (modification)); } }
193 
194 /*
195  * Mixer
196  */
197 extern void mixer_tick(void);
198 extern int mixer_handle_text_create_mixer(void);
199 extern int mixer_handle_text(const void *buffer, size_t length);
200 /* Set the failsafe values of all mixed channels (based on zero throttle, controls centered) */
201 extern void mixer_set_failsafe(void);
202 
206 extern void safety_init(void);
207 extern void failsafe_led_init(void);
208 
212 extern void interface_init(void);
213 extern void interface_tick(void);
214 
218 extern int registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values);
219 extern int registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_values);
220 
224 extern int adc_init(void);
225 extern uint16_t adc_measure(unsigned channel);
226 
232 extern void controls_init(void);
233 extern void controls_tick(void);
234 
236 extern volatile uint8_t debug_level;
237 
239 extern void isr_debug(uint8_t level, const char *fmt, ...);
240 
242 extern void schedule_reboot(uint32_t time_delta_usec);
243 
volatile uint16_t r_page_setup[]
PAGE 100.
Definition: registers.c:155
Configuration flags used in code.
void schedule_reboot(uint32_t time_delta_usec)
schedule a reboot
Definition: px4io.c:225
PX4IO interface protocol.
void controls_init(void)
R/C receiver handling.
Definition: controls.c:173
uint16_t r_page_servo_control_max[]
PAGE 107.
Definition: registers.c:254
int adc_init(void)
Sensors/misc inputs.
Definition: adc.c:82
volatile uint8_t debug_level
global debug level for isr_debug()
void safety_init(void)
Safety switch/LED.
Definition: safety.c:84
uint16_t r_page_controls[]
PAGE 101.
Definition: registers.c:211
uint16_t r_page_servo_disarmed[]
PAGE 109.
Definition: registers.c:270
void interface_init(void)
FMU communications.
Definition: i2c.c:99
uint16_t r_page_servo_control_min[]
PAGE 106.
Definition: registers.c:246
uint16_t r_page_rc_input_config[]
PAGE 103.
Definition: registers.c:222
uint16_t r_page_servos[]
PAGE 3.
Definition: registers.c:108
Definition: video_device.h:50
uint16_t r_page_actuators[]
PAGE 2.
Definition: registers.c:101
uint16_t r_page_rc_input[]
PAGE 5.
Definition: registers.c:130
int16_t r_page_servo_control_trim[]
PAGE 108.
Definition: registers.c:262
volatile uint16_t r_page_status[]
PAGE 1.
Definition: registers.c:85
uint16_t r_page_direct_pwm[]
PAGE 8.
Definition: registers.c:148
uint16_t r_page_raw_rc_input[]
PAGE 4.
Definition: registers.c:115
int registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values)
Register space.
Definition: registers.c:273
uint16_t r_page_servo_failsafe[]
PAGE 105.
Definition: registers.c:238
Definition: pwm_limit.h:67
Definition: px4io.h:142
volatile uint64_t fmu_data_received_time
Last FMU receive time, in microseconds since system boot.
Definition: px4io.h:150
void isr_debug(uint8_t level, const char *fmt,...)
send a debug message to the console
Definition: px4io.c:99