PX4-Autopilot/boards/zeroone/x6/init/rc.board_defaults

27 lines
732 B
Bash

#!/bin/sh
#
# board specific defaults
#------------------------------------------------------------------------------
if ver hwbasecmp 009 010 011
then
# Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client
param set-default UXRCE_DDS_PTCFG 2
param set-default UXRCE_DDS_AG_IP 170461697
param set-default UXRCE_DDS_CFG 1000
else
# Mavlink ethernet (CFG 1000)
param set-default MAV_2_CONFIG 1000
param set-default MAV_2_BROADCAST 1
param set-default MAV_2_MODE 0
param set-default MAV_2_RADIO_CTL 0
param set-default MAV_2_RATE 100000
param set-default MAV_2_REMOTE_PRT 14550
param set-default MAV_2_UDP_PRT 14550
fi
safety_button start
# pwm voltage 3.3V/5V switch
pwm_voltage_apply start