APM:Libraries
HAL_ChibiOS_Class.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #include <AP_HAL/AP_HAL.h>
18 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
19 
20 #include <assert.h>
21 
22 #include "HAL_ChibiOS_Class.h"
25 #include "shared_dma.h"
26 #include "sdcard.h"
27 #include "hwdef/common/usbcfg.h"
28 
29 #include <hwdef.h>
30 
37 
38 #if HAL_USE_I2C == TRUE
40 #else
42 #endif
43 
44 #if HAL_USE_SPI == TRUE
46 #else
48 #endif
49 
50 #if HAL_USE_ADC == TRUE
52 #else
54 #endif
55 
56 #ifdef HAL_USE_EMPTY_STORAGE
58 #else
60 #endif
63 
64 #if HAL_USE_PWM == TRUE
66 #else
68 #endif
69 
73 
74 
75 #if HAL_WITH_IO_MCU
76 HAL_UART_IO_DRIVER;
77 #include <AP_IOMCU/AP_IOMCU.h>
78 AP_IOMCU iomcu(uart_io);
79 #endif
80 
82  AP_HAL::HAL(
83  &uartADriver,
84  &uartBDriver,
85  &uartCDriver,
86  &uartDDriver,
87  &uartEDriver,
88  &uartFDriver,
89  &i2cDeviceManager,
90  &spiDeviceManager,
91  &analogIn,
92  &storageDriver,
93  &uartADriver,
94  &gpioDriver,
95  &rcinDriver,
96  &rcoutDriver,
97  &schedulerInstance,
98  &utilInstance,
99  &opticalFlowDriver,
100  nullptr
101  )
102 {}
103 
104 static bool thread_running = false;
105 static thread_t* daemon_task;
107 extern const AP_HAL::HAL& hal;
108 
109 
110 /*
111  set the priority of the main APM task
112  */
113 void hal_chibios_set_priority(uint8_t priority)
114 {
115  chSysLock();
116 #if CH_CFG_USE_MUTEXES == TRUE
117  if ((daemon_task->prio == daemon_task->realprio) || (priority > daemon_task->prio)) {
118  daemon_task->prio = priority;
119  }
120  daemon_task->realprio = priority;
121 #endif
122  chSchRescheduleS();
123  chSysUnlock();
124 }
125 
126 thread_t* get_main_thread()
127 {
128  return daemon_task;
129 }
130 
133 {
134  daemon_task = chThdGetSelfX();
135 
136 #ifdef HAL_I2C_CLEAR_BUS
137  // Clear all I2C Buses. This can be needed on some boards which
138  // can get a stuck I2C peripheral on boot
140 #endif
141 
143 
144  hal.uartA->begin(115200);
145 
146 #ifdef HAL_SPI_CHECK_CLOCK_FREQ
147  // optional test of SPI clock frequencies
148  ChibiOS::SPIDevice::test_clock_freq();
149 #endif
150 
151  //Setup SD Card and Initialise FATFS bindings
152  sdcard_init();
153 
154  hal.uartB->begin(38400);
155  hal.uartC->begin(57600);
156  hal.analogin->init();
157  hal.scheduler->init();
158 
159  /*
160  run setup() at low priority to ensure CLI doesn't hang the
161  system, and to allow initial sensor read loops to run
162  */
164 
165  schedulerInstance.hal_initialized();
166 
167  g_callbacks->setup();
169 
170  thread_running = true;
171  chRegSetThreadName(SKETCHNAME);
172 
173  /*
174  switch to high priority for main loop
175  */
176  chThdSetPriority(APM_MAIN_PRIORITY);
177 
178  while (true) {
179  g_callbacks->loop();
180 
181  /*
182  give up 250 microseconds of time if the INS loop hasn't
183  called delay_microseconds_boost(), to ensure low priority
184  drivers get a chance to run. Calling
185  delay_microseconds_boost() means we have already given up
186  time from the main loop, so we don't need to do it again
187  here
188  */
189  if (!schedulerInstance.check_called_boost()) {
190  hal.scheduler->delay_microseconds(250);
191  }
192  }
193  thread_running = false;
194 }
195 
196 void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const
197 {
198  /*
199  * System initializations.
200  * - ChibiOS HAL initialization, this also initializes the configured device drivers
201  * and performs the board-specific initializations.
202  * - Kernel initialization, the main() function becomes a thread and the
203  * RTOS is active.
204  */
205 
206 #ifdef HAL_USB_PRODUCT_ID
208 #endif
209 
210 #ifdef HAL_STDOUT_SERIAL
211  //STDOUT Initialistion
212  SerialConfig stdoutcfg =
213  {
214  HAL_STDOUT_BAUDRATE,
215  0,
216  USART_CR2_STOP1_BITS,
217  0
218  };
219  sdStart((SerialDriver*)&HAL_STDOUT_SERIAL, &stdoutcfg);
220 #endif
221 
222  assert(callbacks);
223  g_callbacks = callbacks;
224 
225  void *main_thread_wa = hal.util->malloc_type(THD_WORKING_AREA_SIZE(APM_MAIN_THREAD_STACK_SIZE), AP_HAL::Util::MEM_FAST);
226  chThdCreateStatic(main_thread_wa,
228  APM_MAIN_PRIORITY, /* Initial priority. */
229  main_loop, /* Thread function. */
230  nullptr); /* Thread parameter. */
231  chThdExit(0);
232 }
233 
235  static const HAL_ChibiOS hal_chibios;
236  return hal_chibios;
237 }
238 
239 #endif
static ChibiOS::RCOutput rcoutDriver
virtual void setup()=0
static HAL_UARTB_DRIVER
virtual void loop()=0
static HAL_UARTD_DRIVER
void sdcard_init()
Definition: sdcard.cpp:39
virtual void begin(uint32_t baud)=0
static UARTDriver uartDDriver(false)
static ChibiOS::GPIO gpioDriver
static int main_loop(int argc, char **argv)
static AP_HAL::HAL::Callbacks * g_callbacks
#define APM_MAIN_PRIORITY
Definition: Scheduler.h:25
AP_HAL::Util * util
Definition: HAL.h:115
AP_HAL::UARTDriver * uartB
Definition: HAL.h:101
static UARTDriver uartEDriver(false)
static thread_t * daemon_task
thread_t * get_main_thread()
static ChibiOS::SPIDeviceManager spiDeviceManager
#define APM_MAIN_THREAD_STACK_SIZE
Definition: Scheduler.h:59
static bool thread_running
static ChibiOS::AnalogIn analogIn
static ChibiOS::RCInput rcinDriver
AP_HAL::UARTDriver * uartC
Definition: HAL.h:102
static ChibiOS::Util utilInstance
void hal_chibios_set_priority(uint8_t priority)
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
static THD_FUNCTION(main_loop, arg)
static UARTDriver uartBDriver
virtual void init()=0
static HAL_UARTC_DRIVER
virtual void init()=0
void hal_initialized()
Definition: Scheduler.h:82
bool check_called_boost(void)
Definition: Scheduler.cpp:163
static ChibiOS::I2CDeviceManager i2cDeviceManager
static HAL_UARTF_DRIVER
#define APM_STARTUP_PRIORITY
Definition: Scheduler.h:32
static UARTDriver uartADriver
static HAL_UARTA_DRIVER
const HAL & get_HAL()
virtual void * malloc_type(size_t size, Memory_Type mem_type)
Definition: Util.h:115
AP_HAL::UARTDriver * uartA
Definition: HAL.h:100
static void clear_all(void)
Definition: I2CDevice.cpp:61
static UARTDriver uartCDriver
virtual void delay_microseconds(uint16_t us)=0
static ChibiOS::Scheduler schedulerInstance
static HAL_UARTE_DRIVER
void run(int argc, char *const *argv, Callbacks *callbacks) const override
static void init(void)
Definition: shared_dma.cpp:27
void setup_usb_strings(void)
static UARTDriver uartFDriver(false)
static Empty::OpticalFlow opticalFlowDriver
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
static ChibiOS::Storage storageDriver
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
virtual void system_initialized()=0