AP_BoardConfig.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * AP_BoardConfig - board specific configuration
  15. */
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <AP_Common/AP_Common.h>
  18. #include <GCS_MAVLink/GCS.h>
  19. #include "AP_BoardConfig.h"
  20. #include <stdio.h>
  21. #include <AP_RTC/AP_RTC.h>
  22. #if HAL_WITH_UAVCAN
  23. #include <AP_UAVCAN/AP_UAVCAN.h>
  24. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  25. #include <AP_HAL_Linux/CAN.h>
  26. #endif
  27. #endif
  28. #ifndef BOARD_TYPE_DEFAULT
  29. #define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO
  30. #endif
  31. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  32. # define BOARD_SAFETY_ENABLE_DEFAULT 1
  33. #ifndef BOARD_PWM_COUNT_DEFAULT
  34. # define BOARD_PWM_COUNT_DEFAULT 6
  35. #endif
  36. #ifndef BOARD_SER1_RTSCTS_DEFAULT
  37. # define BOARD_SER1_RTSCTS_DEFAULT 2
  38. #endif
  39. #ifndef BOARD_TYPE_DEFAULT
  40. # define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO
  41. #endif
  42. #endif
  43. #ifndef HAL_IMU_TEMP_DEFAULT
  44. #define HAL_IMU_TEMP_DEFAULT -1 // disabled
  45. #endif
  46. #ifndef BOARD_SAFETY_OPTION_DEFAULT
  47. # define BOARD_SAFETY_OPTION_DEFAULT (BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)
  48. #endif
  49. #ifndef BOARD_SAFETY_ENABLE
  50. # define BOARD_SAFETY_ENABLE 1
  51. #endif
  52. #ifndef BOARD_PWM_COUNT_DEFAULT
  53. #define BOARD_PWM_COUNT_DEFAULT 8
  54. #endif
  55. #ifndef BOARD_CONFIG_BOARD_VOLTAGE_MIN
  56. #define BOARD_CONFIG_BOARD_VOLTAGE_MIN 4.3f
  57. #endif
  58. #ifndef HAL_BRD_OPTIONS_DEFAULT
  59. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  60. #define HAL_BRD_OPTIONS_DEFAULT BOARD_OPTION_WATCHDOG
  61. #else
  62. #define HAL_BRD_OPTIONS_DEFAULT 0
  63. #endif
  64. #endif
  65. #ifndef HAL_DEFAULT_BOOT_DELAY
  66. #define HAL_DEFAULT_BOOT_DELAY 0
  67. #endif
  68. extern const AP_HAL::HAL& hal;
  69. AP_BoardConfig *AP_BoardConfig::_singleton;
  70. // table of user settable parameters
  71. const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
  72. // @Param: PWM_COUNT
  73. // @DisplayName: Auxiliary pin config
  74. // @Description: Controls number of FMU outputs which are setup for PWM. All unassigned pins can be used for GPIO
  75. // @Values: 0:No PWMs,1:One PWMs,2:Two PWMs,3:Three PWMs,4:Four PWMs,5:Five PWMs,6:Six PWMs,7:Seven PWMs,8:Eight PWMs
  76. // @RebootRequired: True
  77. // @User: Advanced
  78. AP_GROUPINFO("PWM_COUNT", 0, AP_BoardConfig, pwm_count, BOARD_PWM_COUNT_DEFAULT),
  79. #if AP_FEATURE_RTSCTS
  80. // @Param: SER1_RTSCTS
  81. // @DisplayName: Serial 1 flow control
  82. // @Description: Enable flow control on serial 1 (telemetry 1) on Pixhawk. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. Note that the PX4v1 does not have hardware flow control pins on this port, so you should leave this disabled.
  83. // @Values: 0:Disabled,1:Enabled,2:Auto
  84. // @RebootRequired: True
  85. // @User: Advanced
  86. AP_GROUPINFO("SER1_RTSCTS", 1, AP_BoardConfig, state.ser1_rtscts, BOARD_SER1_RTSCTS_DEFAULT),
  87. // @Param: SER2_RTSCTS
  88. // @DisplayName: Serial 2 flow control
  89. // @Description: Enable flow control on serial 2 (telemetry 2) on Pixhawk and STATE. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
  90. // @Values: 0:Disabled,1:Enabled,2:Auto
  91. // @RebootRequired: True
  92. // @User: Advanced
  93. AP_GROUPINFO("SER2_RTSCTS", 2, AP_BoardConfig, state.ser2_rtscts, 2),
  94. #endif
  95. #if HAL_HAVE_SAFETY_SWITCH
  96. // @Param: SAFETYENABLE
  97. // @DisplayName: Enable use of safety arming switch
  98. // @Description: This controls the default state of the safety switch at startup. When set to 1 the safety switch will start in the safe state (flashing) at boot. When set to zero the safety switch will start in the unsafe state (solid) at startup. Note that if a safety switch is fitted the user can still control the safety state after startup using the switch. The safety state can also be controlled in software using a MAVLink message.
  99. // @Values: 0:Disabled,1:Enabled
  100. // @RebootRequired: True
  101. // @User: Standard
  102. AP_GROUPINFO("SAFETYENABLE", 3, AP_BoardConfig, state.safety_enable, BOARD_SAFETY_ENABLE_DEFAULT),
  103. #endif
  104. #if AP_FEATURE_SBUS_OUT
  105. // @Param: SBUS_OUT
  106. // @DisplayName: SBUS output rate
  107. // @Description: This sets the SBUS output frame rate in Hz
  108. // @Values: 0:Disabled,1:50Hz,2:75Hz,3:100Hz,4:150Hz,5:200Hz,6:250Hz,7:300Hz
  109. // @RebootRequired: True
  110. // @User: Advanced
  111. AP_GROUPINFO("SBUS_OUT", 4, AP_BoardConfig, state.sbus_out_rate, 0),
  112. #endif
  113. // @Param: SERIAL_NUM
  114. // @DisplayName: User-defined serial number
  115. // @Description: User-defined serial number of this vehicle, it can be any arbitrary number you want and has no effect on the autopilot
  116. // @Range: -32768 32767
  117. // @User: Standard
  118. AP_GROUPINFO("SERIAL_NUM", 5, AP_BoardConfig, vehicleSerialNumber, 0),
  119. #if HAL_HAVE_SAFETY_SWITCH
  120. // @Param: SAFETY_MASK
  121. // @DisplayName: Channels which ignore the safety switch state
  122. // @Description: A bitmask which controls what channels can move while the safety switch has not been pressed
  123. // @Values: 0:Disabled,1:Enabled
  124. // @Bitmask: 0:Ch1,1:Ch2,2:Ch3,3:Ch4,4:Ch5,5:Ch6,6:Ch7,7:Ch8,8:Ch9,9:Ch10,10:Ch11,11:Ch12,12:Ch13,13:Ch14
  125. // @RebootRequired: True
  126. // @User: Advanced
  127. AP_GROUPINFO("SAFETY_MASK", 7, AP_BoardConfig, state.ignore_safety_channels, 0),
  128. #endif
  129. #if HAL_HAVE_IMU_HEATER
  130. // @Param: IMU_TARGTEMP
  131. // @DisplayName: Target IMU temperature
  132. // @Description: This sets the target IMU temperature for boards with controllable IMU heating units. DO NOT SET -1 on The Cube. A value of -1 sets PH1 behaviour
  133. // @Range: -1 80
  134. // @Units: degC
  135. // @User: Advanced
  136. AP_GROUPINFO("IMU_TARGTEMP", 8, AP_BoardConfig, _imu_target_temperature, HAL_IMU_TEMP_DEFAULT),
  137. #endif
  138. #if AP_FEATURE_BOARD_DETECT
  139. // @Param: TYPE
  140. // @DisplayName: Board type
  141. // @Description: This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)
  142. // @Values: 0:AUTO,1:PX4V1,2:Pixhawk,3:Cube/Pixhawk2,4:Pixracer,5:PixhawkMini,6:Pixhawk2Slim,7:VRBrain 5.1,8:VRBrain 5.2,9:VR Micro Brain 5.1,10:VR Micro Brain 5.2,11:VRBrain Core 1.0,12:VRBrain 5.4,13:Intel Aero FC,20:AUAV2.1
  143. // @RebootRequired: True
  144. // @User: Advanced
  145. AP_GROUPINFO("TYPE", 9, AP_BoardConfig, state.board_type, BOARD_TYPE_DEFAULT),
  146. #endif
  147. #if AP_FEATURE_BOARD_DETECT
  148. #if HAL_PX4_HAVE_PX4IO || HAL_WITH_IO_MCU
  149. // @Param: IO_ENABLE
  150. // @DisplayName: Enable IO co-processor
  151. // @Description: This allows for the IO co-processor on FMUv1 and FMUv2 to be disabled
  152. // @Values: 0:Disabled,1:Enabled
  153. // @RebootRequired: True
  154. // @User: Advanced
  155. AP_GROUPINFO("IO_ENABLE", 10, AP_BoardConfig, state.io_enable, 1),
  156. #endif
  157. #endif
  158. #if HAL_RCINPUT_WITH_AP_RADIO
  159. // @Group: RADIO
  160. // @Path: ../AP_Radio/AP_Radio.cpp
  161. AP_SUBGROUPINFO(_radio, "RADIO", 11, AP_BoardConfig, AP_Radio),
  162. #endif
  163. // @Param: SAFETYOPTION
  164. // @DisplayName: Options for safety button behavior
  165. // @Description: This controls the activation of the safety button. It allows you to control if the safety button can be used for safety enable and/or disable, and whether the button is only active when disarmed
  166. // @Bitmask: 0:ActiveForSafetyEnable,1:ActiveForSafetyDisable,2:ActiveWhenArmed,3:Force safety on when the aircraft disarms
  167. // @User: Standard
  168. AP_GROUPINFO("SAFETYOPTION", 13, AP_BoardConfig, state.safety_option, BOARD_SAFETY_OPTION_DEFAULT),
  169. // @Group: RTC
  170. // @Path: ../AP_RTC/AP_RTC.cpp
  171. AP_SUBGROUPINFO(rtc, "RTC", 14, AP_BoardConfig, AP_RTC),
  172. #if HAL_HAVE_BOARD_VOLTAGE
  173. // @Param: VBUS_MIN
  174. // @DisplayName: Autopilot board voltage requirement
  175. // @Description: Minimum voltage on the autopilot power rail to allow the aircraft to arm. 0 to disable the check.
  176. // @Units: V
  177. // @Range: 4.0 5.5
  178. // @Increment: 0.1
  179. // @User: Advanced
  180. AP_GROUPINFO("VBUS_MIN", 15, AP_BoardConfig, _vbus_min, BOARD_CONFIG_BOARD_VOLTAGE_MIN),
  181. #endif
  182. #if HAL_HAVE_SERVO_VOLTAGE
  183. // @Param: VSERVO_MIN
  184. // @DisplayName: Servo voltage requirement
  185. // @Description: Minimum voltage on the servo rail to allow the aircraft to arm. 0 to disable the check.
  186. // @Units: V
  187. // @Range: 3.3 12.0
  188. // @Increment: 0.1
  189. // @User: Advanced
  190. AP_GROUPINFO("VSERVO_MIN", 16, AP_BoardConfig, _vservo_min, 0),
  191. #endif
  192. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  193. // @Param: SD_SLOWDOWN
  194. // @DisplayName: microSD slowdown
  195. // @Description: This is a scaling factor to slow down microSD operation. It can be used on flight board and microSD card combinations where full speed is not reliable. For normal full speed operation a value of 0 should be used.
  196. // @Range: 0 32
  197. // @Increment: 1
  198. // @User: Advanced
  199. AP_GROUPINFO("SD_SLOWDOWN", 17, AP_BoardConfig, _sdcard_slowdown, 0),
  200. #endif
  201. #ifdef HAL_GPIO_PWM_VOLT_PIN
  202. // @Param: PWM_VOLT_SEL
  203. // @DisplayName: Set PWM Out Voltage
  204. // @Description: This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output.
  205. // @Values: 0:3.3V,1:5V
  206. // @User: Advanced
  207. AP_GROUPINFO("PWM_VOLT_SEL", 18, AP_BoardConfig, _pwm_volt_sel, 0),
  208. #endif
  209. // @Param: OPTIONS
  210. // @DisplayName: Board options
  211. // @Description: Board specific option flags
  212. // @Bitmask: 0:Enable hardware watchdog
  213. // @User: Advanced
  214. AP_GROUPINFO("OPTIONS", 19, AP_BoardConfig, _options, HAL_BRD_OPTIONS_DEFAULT),
  215. // @Param: BOOT_DELAY
  216. // @DisplayName: Boot delay
  217. // @Description: This adds a delay in milliseconds to boot to ensure peripherals initialise fully
  218. // @Range: 0 10000
  219. // @Units: ms
  220. // @User: Advanced
  221. AP_GROUPINFO("BOOT_DELAY", 20, AP_BoardConfig, _boot_delay_ms, HAL_DEFAULT_BOOT_DELAY),
  222. AP_GROUPEND
  223. };
  224. void AP_BoardConfig::init()
  225. {
  226. board_setup();
  227. #if HAL_HAVE_IMU_HEATER
  228. // let the HAL know the target temperature. We pass a pointer as
  229. // we want the user to be able to change the parameter without
  230. // rebooting
  231. hal.util->set_imu_target_temp((int8_t *)&_imu_target_temperature);
  232. #endif
  233. AP::rtc().set_utc_usec(hal.util->get_hw_rtc(), AP_RTC::SOURCE_HW);
  234. if (_boot_delay_ms > 0) {
  235. uint16_t delay_ms = uint16_t(_boot_delay_ms.get());
  236. if (hal.util->was_watchdog_armed() && delay_ms > 200) {
  237. // don't delay a long time on watchdog reset, the pilot
  238. // may be able to save the vehicle
  239. delay_ms = 200;
  240. }
  241. hal.scheduler->delay(delay_ms);
  242. }
  243. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(USE_POSIX)
  244. uint8_t slowdown = constrain_int16(_sdcard_slowdown.get(), 0, 32);
  245. const uint8_t max_slowdown = 8;
  246. do {
  247. if (hal.util->fs_init()) {
  248. break;
  249. }
  250. slowdown++;
  251. hal.scheduler->delay(5);
  252. } while (slowdown < max_slowdown);
  253. if (slowdown < max_slowdown) {
  254. _sdcard_slowdown.set(slowdown);
  255. } else {
  256. printf("SDCard failed to start\n");
  257. }
  258. #endif
  259. }
  260. // set default value for BRD_SAFETY_MASK
  261. void AP_BoardConfig::set_default_safety_ignore_mask(uint16_t mask)
  262. {
  263. #if HAL_HAVE_SAFETY_SWITCH
  264. state.ignore_safety_channels.set_default(mask);
  265. #endif
  266. }
  267. void AP_BoardConfig::init_safety()
  268. {
  269. board_init_safety();
  270. }
  271. /*
  272. notify user of a fatal startup error related to available sensors.
  273. */
  274. bool AP_BoardConfig::_in_sensor_config_error;
  275. void AP_BoardConfig::sensor_config_error(const char *reason)
  276. {
  277. _in_sensor_config_error = true;
  278. /*
  279. to give the user the opportunity to connect to USB we keep
  280. repeating the error. The mavlink delay callback is initialised
  281. before this, so the user can change parameters (and in
  282. particular BRD_TYPE if needed)
  283. */
  284. uint32_t last_print_ms = 0;
  285. while (true) {
  286. uint32_t now = AP_HAL::millis();
  287. if (now - last_print_ms >= 3000) {
  288. last_print_ms = now;
  289. printf("Sensor failure: %s\n", reason);
  290. #if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !defined(HAL_BUILD_AP_PERIPH)
  291. gcs().send_text(MAV_SEVERITY_ERROR, "Check BRD_TYPE: %s", reason);
  292. #endif
  293. }
  294. #if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !defined(HAL_BUILD_AP_PERIPH)
  295. gcs().update_receive();
  296. gcs().update_send();
  297. #endif
  298. hal.scheduler->delay(5);
  299. }
  300. }
  301. /*
  302. handle logic for safety state button press. This should be called at
  303. 10Hz when the button is pressed. The button can either be directly
  304. on a pin or on a UAVCAN device
  305. This function returns true if the safety state should be toggled
  306. */
  307. bool AP_BoardConfig::safety_button_handle_pressed(uint8_t press_count)
  308. {
  309. if (press_count != 10) {
  310. return false;
  311. }
  312. // get button options
  313. uint16_t safety_options = get_safety_button_options();
  314. if (!(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) &&
  315. hal.util->get_soft_armed()) {
  316. return false;
  317. }
  318. AP_HAL::Util::safety_state safety_state = hal.util->safety_switch_state();
  319. if (safety_state == AP_HAL::Util::SAFETY_DISARMED &&
  320. !(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF)) {
  321. return false;
  322. }
  323. if (safety_state == AP_HAL::Util::SAFETY_ARMED &&
  324. !(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)) {
  325. return false;
  326. }
  327. return true;
  328. }