2014-01-19 21:57:39 -04:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
/*
* AP_BoardConfig - board specific configuration
*/
2015-08-11 03:28:42 -03:00
# include <AP_HAL/AP_HAL.h>
# include <AP_Common/AP_Common.h>
2017-05-01 23:05:47 -03:00
# include <GCS_MAVLink/GCS.h>
2015-08-11 03:28:42 -03:00
# include "AP_BoardConfig.h"
2017-05-01 23:05:47 -03:00
# include <stdio.h>
2018-04-17 00:53:47 -03:00
# include <AP_RTC/AP_RTC.h>
2014-01-19 21:57:39 -04:00
2017-06-01 12:19:51 -03:00
# if HAL_WITH_UAVCAN
# include <AP_UAVCAN/AP_UAVCAN.h>
# if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
# include <AP_HAL_Linux/CAN.h>
# endif
# endif
2016-07-05 12:50:34 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4
# define BOARD_SAFETY_ENABLE_DEFAULT 1
2016-07-18 13:25:01 -03:00
# if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
2014-01-19 21:57:39 -04:00
# define BOARD_PWM_COUNT_DEFAULT 2
2014-02-10 21:10:55 -04:00
# define BOARD_SER1_RTSCTS_DEFAULT 0 // no flow control on UART5 on FMUv1
2016-07-18 13:25:01 -03:00
# elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
2016-04-13 08:45:43 -03:00
# define BOARD_PWM_COUNT_DEFAULT 6
# define BOARD_SER1_RTSCTS_DEFAULT 2
2017-01-27 05:21:12 -04:00
# elif defined(CONFIG_ARCH_BOARD_AEROFC_V1)
# define BOARD_PWM_COUNT_DEFAULT 0
# define BOARD_SER1_RTSCTS_DEFAULT 0
# undef BOARD_SAFETY_ENABLE_DEFAULT
# define BOARD_SAFETY_ENABLE_DEFAULT 0
2016-04-13 08:45:43 -03:00
# else // V2
2014-01-19 21:57:39 -04:00
# define BOARD_PWM_COUNT_DEFAULT 4
2014-02-10 21:10:55 -04:00
# define BOARD_SER1_RTSCTS_DEFAULT 2
2016-08-04 14:17:29 -03:00
# endif
2018-07-11 22:26:58 -03:00
# ifndef BOARD_TYPE_DEFAULT
2016-08-10 10:48:50 -03:00
# define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO
2018-07-11 22:26:58 -03:00
# endif
2018-01-05 03:00:09 -04:00
2014-03-31 14:53:16 -03:00
# elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
2016-07-05 12:50:34 -03:00
# define BOARD_SAFETY_ENABLE_DEFAULT 0
# define BOARD_PWM_COUNT_DEFAULT 8
2016-08-10 10:48:50 -03:00
# if defined(CONFIG_ARCH_BOARD_VRBRAIN_V51)
# define BOARD_TYPE_DEFAULT VRX_BOARD_BRAIN51
# elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52)
# define BOARD_TYPE_DEFAULT VRX_BOARD_BRAIN52
2018-02-03 10:19:25 -04:00
# elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52E)
# define BOARD_TYPE_DEFAULT VRX_BOARD_BRAIN52E
2016-08-10 10:48:50 -03:00
# elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51)
# define BOARD_TYPE_DEFAULT VRX_BOARD_UBRAIN51
# elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
# define BOARD_TYPE_DEFAULT VRX_BOARD_UBRAIN52
# elif defined(CONFIG_ARCH_BOARD_VRCORE_V10)
# define BOARD_TYPE_DEFAULT VRX_BOARD_CORE10
# elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V54)
# define BOARD_TYPE_DEFAULT VRX_BOARD_BRAIN54
# endif
2018-01-05 03:00:09 -04:00
# elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
# define BOARD_SAFETY_ENABLE_DEFAULT 1
2018-04-06 22:31:15 -03:00
# ifndef BOARD_PWM_COUNT_DEFAULT
2018-01-05 03:00:09 -04:00
# define BOARD_PWM_COUNT_DEFAULT 6
2018-04-06 22:31:15 -03:00
# endif
# ifndef BOARD_SER1_RTSCTS_DEFAULT
2018-01-05 03:00:09 -04:00
# define BOARD_SER1_RTSCTS_DEFAULT 2
2018-04-06 22:31:15 -03:00
# endif
2018-07-11 22:26:58 -03:00
# ifndef BOARD_TYPE_DEFAULT
2018-01-05 03:00:09 -04:00
# define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO
# endif
2018-07-11 22:26:58 -03:00
# endif
2018-01-05 03:00:09 -04:00
# ifndef HAL_IMU_TEMP_DEFAULT
# define HAL_IMU_TEMP_DEFAULT -1 // disabled
2014-01-19 21:57:39 -04:00
# endif
2018-08-01 20:46:59 -03:00
# if HAL_HAVE_SAFETY_SWITCH
2018-06-29 14:42:42 -03:00
# ifndef BOARD_SAFETY_OPTION_DEFAULT
# define BOARD_SAFETY_OPTION_DEFAULT (BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)
# endif
# ifndef BOARD_SAFETY_ENABLE
# define BOARD_SAFETY_ENABLE 1
# endif
2018-04-13 02:56:40 -03:00
# endif
2018-05-25 07:52:41 -03:00
# ifndef BOARD_PWM_COUNT_DEFAULT
# define BOARD_PWM_COUNT_DEFAULT 8
# endif
2018-11-10 17:42:24 -04:00
# ifndef BOARD_CONFIG_BOARD_VOLTAGE_MIN
# define BOARD_CONFIG_BOARD_VOLTAGE_MIN 4.3f
# endif
2014-01-19 21:57:39 -04:00
extern const AP_HAL : : HAL & hal ;
2018-01-05 04:54:42 -04:00
AP_BoardConfig * AP_BoardConfig : : instance ;
2014-01-19 21:57:39 -04:00
// table of user settable parameters
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AP_BoardConfig : : var_info [ ] = {
2014-01-19 21:57:39 -04:00
// @Param: PWM_COUNT
2016-05-12 13:56:59 -03:00
// @DisplayName: Auxiliary pin config
2018-10-30 00:09:41 -03:00
// @Description: Controls number of FMU outputs which are setup for PWM. All unassigned pins can be used for GPIO
// @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
2016-05-22 20:58:58 -03:00
// @RebootRequired: True
2016-07-26 02:35:15 -03:00
// @User: Advanced
2018-05-25 07:52:41 -03:00
AP_GROUPINFO ( " PWM_COUNT " , 0 , AP_BoardConfig , pwm_count , BOARD_PWM_COUNT_DEFAULT ) ,
2014-02-09 21:57:19 -04:00
2018-01-05 03:00:09 -04:00
# if AP_FEATURE_RTSCTS
2014-02-09 21:57:19 -04:00
// @Param: SER1_RTSCTS
// @DisplayName: Serial 1 flow control
2014-02-10 21:10:55 -04:00
// @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.
2014-02-10 20:22:27 -04:00
// @Values: 0:Disabled,1:Enabled,2:Auto
2016-05-22 20:58:58 -03:00
// @RebootRequired: True
2016-07-26 02:35:15 -03:00
// @User: Advanced
2018-01-05 03:00:09 -04:00
AP_GROUPINFO ( " SER1_RTSCTS " , 1 , AP_BoardConfig , state . ser1_rtscts , BOARD_SER1_RTSCTS_DEFAULT ) ,
2014-02-09 21:57:19 -04:00
// @Param: SER2_RTSCTS
// @DisplayName: Serial 2 flow control
2018-01-05 03:00:09 -04:00
// @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.
2014-02-10 20:22:27 -04:00
// @Values: 0:Disabled,1:Enabled,2:Auto
2016-05-22 20:58:58 -03:00
// @RebootRequired: True
2016-07-26 02:35:15 -03:00
// @User: Advanced
2018-01-05 03:00:09 -04:00
AP_GROUPINFO ( " SER2_RTSCTS " , 2 , AP_BoardConfig , state . ser2_rtscts , 2 ) ,
2016-08-07 07:54:02 -03:00
# endif
2017-04-02 11:56:37 -03:00
2018-08-01 20:46:59 -03:00
# if HAL_HAVE_SAFETY_SWITCH
2014-02-11 00:58:02 -04:00
// @Param: SAFETYENABLE
2016-06-27 20:58:55 -03:00
// @DisplayName: Enable use of safety arming switch
// @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.
2014-02-11 00:58:02 -04:00
// @Values: 0:Disabled,1:Enabled
2016-05-22 20:58:58 -03:00
// @RebootRequired: True
2016-07-26 02:35:15 -03:00
// @User: Standard
2018-01-05 03:00:09 -04:00
AP_GROUPINFO ( " SAFETYENABLE " , 3 , AP_BoardConfig , state . safety_enable , BOARD_SAFETY_ENABLE_DEFAULT ) ,
2016-08-07 07:54:02 -03:00
# endif
2015-02-11 03:35:34 -04:00
2018-01-05 03:00:09 -04:00
# if AP_FEATURE_SBUS_OUT
2015-02-11 03:35:34 -04:00
// @Param: SBUS_OUT
2016-03-10 00:26:47 -04:00
// @DisplayName: SBUS output rate
// @Description: This sets the SBUS output frame rate in Hz
// @Values: 0:Disabled,1:50Hz,2:75Hz,3:100Hz,4:150Hz,5:200Hz,6:250Hz,7:300Hz
2016-05-22 20:58:58 -03:00
// @RebootRequired: True
2016-07-26 02:35:15 -03:00
// @User: Advanced
2018-01-05 03:00:09 -04:00
AP_GROUPINFO ( " SBUS_OUT " , 4 , AP_BoardConfig , state . sbus_out_rate , 0 ) ,
2014-01-19 21:57:39 -04:00
# endif
2015-04-29 23:02:27 -03:00
// @Param: SERIAL_NUM
// @DisplayName: User-defined serial number
// @Description: User-defined serial number of this vehicle, it can be any arbitrary number you want and has no effect on the autopilot
2017-02-10 20:25:48 -04:00
// @Range: -32768 32767
2015-04-29 23:02:27 -03:00
// @User: Standard
AP_GROUPINFO ( " SERIAL_NUM " , 5 , AP_BoardConfig , vehicleSerialNumber , 0 ) ,
2018-08-01 20:46:59 -03:00
# if HAL_HAVE_SAFETY_SWITCH
2016-05-22 20:58:58 -03:00
// @Param: SAFETY_MASK
2018-07-20 00:56:07 -03:00
// @DisplayName: Channels which ignore the safety switch state
2016-06-27 19:21:50 -03:00
// @Description: A bitmask which controls what channels can move while the safety switch has not been pressed
2016-05-22 20:58:58 -03:00
// @Values: 0:Disabled,1:Enabled
2016-10-17 03:58:53 -03:00
// @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
2016-05-22 20:58:58 -03:00
// @RebootRequired: True
2016-07-26 02:35:15 -03:00
// @User: Advanced
2018-01-05 03:00:09 -04:00
AP_GROUPINFO ( " SAFETY_MASK " , 7 , AP_BoardConfig , state . ignore_safety_channels , 0 ) ,
2016-05-22 20:58:58 -03:00
# endif
2016-07-02 23:54:27 -03:00
# if HAL_HAVE_IMU_HEATER
// @Param: IMU_TARGTEMP
// @DisplayName: Target IMU temperature
2017-05-16 01:50:36 -03:00
// @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
2016-07-02 23:54:27 -03:00
// @Range: -1 80
2017-05-02 10:42:12 -03:00
// @Units: degC
2016-07-26 02:35:15 -03:00
// @User: Advanced
2016-07-02 23:54:27 -03:00
AP_GROUPINFO ( " IMU_TARGTEMP " , 8 , AP_BoardConfig , _imu_target_temperature , HAL_IMU_TEMP_DEFAULT ) ,
# endif
2016-08-03 04:56:04 -03:00
2018-01-05 03:00:09 -04:00
# if AP_FEATURE_BOARD_DETECT
2016-08-03 04:56:04 -03:00
// @Param: TYPE
// @DisplayName: Board type
2016-08-10 10:48:50 -03:00
// @Description: This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)
2017-09-08 04:59:00 -03:00
// @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
2016-08-03 04:56:04 -03:00
// @RebootRequired: True
2016-10-26 07:50:02 -03:00
// @User: Advanced
2018-01-05 03:00:09 -04:00
AP_GROUPINFO ( " TYPE " , 9 , AP_BoardConfig , state . board_type , BOARD_TYPE_DEFAULT ) ,
2016-08-03 04:56:04 -03:00
# endif
2017-03-09 19:43:10 -04:00
2018-01-05 03:00:09 -04:00
# if AP_FEATURE_BOARD_DETECT
2018-01-06 03:39:28 -04:00
# if HAL_PX4_HAVE_PX4IO || HAL_WITH_IO_MCU
2017-05-29 22:21:15 -03:00
// @Param: IO_ENABLE
2017-03-09 19:43:10 -04:00
// @DisplayName: Enable IO co-processor
// @Description: This allows for the IO co-processor on FMUv1 and FMUv2 to be disabled
// @Values: 0:Disabled,1:Enabled
// @RebootRequired: True
// @User: Advanced
2018-01-05 03:00:09 -04:00
AP_GROUPINFO ( " IO_ENABLE " , 10 , AP_BoardConfig , state . io_enable , 1 ) ,
2017-04-09 21:02:42 -03:00
# endif
2017-03-09 19:43:10 -04:00
# endif
2017-04-02 11:56:37 -03:00
2018-03-11 11:47:28 -03:00
# if HAL_RCINPUT_WITH_AP_RADIO
2018-01-05 04:58:17 -04:00
// @Group: RADIO
// @Path: ../AP_Radio/AP_Radio.cpp
AP_SUBGROUPINFO ( _radio , " RADIO " , 11 , AP_BoardConfig , AP_Radio ) ,
# endif
2018-02-02 16:48:29 -04:00
# if defined(HAL_NEEDS_PARAM_HELPER)
// @Group: ""
// @Path: ../libraries/AP_Param_Helper/AP_Param_Helper.cpp
AP_SUBGROUPINFO ( param_helper , " " , 12 , AP_BoardConfig , AP_Param_Helper ) ,
# endif
2018-04-13 02:56:40 -03:00
2018-08-01 20:46:59 -03:00
# if HAL_HAVE_SAFETY_SWITCH
2018-04-13 02:56:40 -03:00
// @Param: SAFETYOPTION
// @DisplayName: Options for safety button behavior
// @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
2018-05-08 03:04:55 -03:00
// @Bitmask: 0:ActiveForSafetyEnable,1:ActiveForSafetyDisable,2:ActiveWhenArmed
2018-04-13 02:56:40 -03:00
// @User: Standard
AP_GROUPINFO ( " SAFETYOPTION " , 13 , AP_BoardConfig , state . safety_option , BOARD_SAFETY_OPTION_DEFAULT ) ,
# endif
2018-06-13 23:15:55 -03:00
// @Group: RTC
// @Path: ../AP_RTC/AP_RTC.cpp
AP_SUBGROUPINFO ( rtc , " RTC " , 14 , AP_BoardConfig , AP_RTC ) ,
2018-11-10 17:42:24 -04:00
# if HAL_HAVE_BOARD_VOLTAGE
// @Param: VBUS_MIN
// @DisplayName: Autopilot board voltage requirement
// @Description: Minimum voltage on the autopilot power rail to allow the aircraft to arm. 0 to disable the check.
// @Units: V
// @Range: 4.0 5.5
// Increment 0.1
// @User: Advanced
AP_GROUPINFO ( " VBUS_MIN " , 15 , AP_BoardConfig , _vbus_min , BOARD_CONFIG_BOARD_VOLTAGE_MIN ) ,
# endif
# if HAL_HAVE_SERVO_VOLTAGE
// @Param: VSERVO_MIN
// @DisplayName: Servo voltage requirement
// @Description: Minimum voltage on the servo rail to allow the aircraft to arm. 0 to disable the check.
// @Units: V
// @Range: 3.3 12.0
// Increment 0.1
// @User: Advanced
AP_GROUPINFO ( " VSERVO_MIN " , 16 , AP_BoardConfig , _vservo_min , 0 ) ,
# endif
2014-01-19 21:57:39 -04:00
AP_GROUPEND
} ;
void AP_BoardConfig : : init ( )
{
2018-01-05 03:00:09 -04:00
board_setup ( ) ;
2017-04-02 11:56:37 -03:00
2016-08-07 07:54:02 -03:00
# if HAL_HAVE_IMU_HEATER
2016-06-15 05:28:18 -03:00
// let the HAL know the target temperature. We pass a pointer as
// we want the user to be able to change the parameter without
// rebooting
hal . util - > set_imu_target_temp ( ( int8_t * ) & _imu_target_temperature ) ;
2016-08-07 07:54:02 -03:00
# endif
2018-04-17 00:53:47 -03:00
AP : : rtc ( ) . set_utc_usec ( hal . util - > get_hw_rtc ( ) , AP_RTC : : SOURCE_HW ) ;
2014-01-19 21:57:39 -04:00
}
2016-10-20 21:53:34 -03:00
// set default value for BRD_SAFETY_MASK
void AP_BoardConfig : : set_default_safety_ignore_mask ( uint16_t mask )
{
2018-08-01 20:46:59 -03:00
# if HAL_HAVE_SAFETY_SWITCH
2018-01-05 03:00:09 -04:00
state . ignore_safety_channels . set_default ( mask ) ;
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4
2016-10-20 21:53:34 -03:00
px4_setup_safety_mask ( ) ;
# endif
2018-01-05 03:00:09 -04:00
# endif
2016-10-20 21:53:34 -03:00
}
2017-04-29 21:47:27 -03:00
void AP_BoardConfig : : init_safety ( )
{
2018-01-05 03:00:09 -04:00
board_init_safety ( ) ;
2017-04-29 21:47:27 -03:00
}
2017-05-01 23:05:47 -03:00
/*
notify user of a fatal startup error related to available sensors .
*/
2017-06-06 04:18:15 -03:00
bool AP_BoardConfig : : _in_sensor_config_error ;
2017-05-01 23:05:47 -03:00
void AP_BoardConfig : : sensor_config_error ( const char * reason )
{
2017-06-06 04:18:15 -03:00
_in_sensor_config_error = true ;
2017-05-01 23:05:47 -03:00
/*
to give the user the opportunity to connect to USB we keep
repeating the error . The mavlink delay callback is initialised
before this , so the user can change parameters ( and in
particular BRD_TYPE if needed )
*/
while ( true ) {
printf ( " Sensor failure: %s \n " , reason ) ;
2017-07-09 01:07:34 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_ERROR , " Check BRD_TYPE: %s " , reason ) ;
2017-05-01 23:05:47 -03:00
hal . scheduler - > delay ( 3000 ) ;
}
}