2 changed files with 137 additions and 0 deletions
@ -0,0 +1,120 @@
@@ -0,0 +1,120 @@
|
||||
#!nsh |
||||
|
||||
# |
||||
# Load default params for this platform |
||||
# |
||||
if param compare SYS_AUTOCONFIG 1 |
||||
then |
||||
# Set all params here, then disable autoconfig |
||||
param set SYS_AUTOCONFIG 0 |
||||
|
||||
param set MC_ATTRATE_D 0.002 |
||||
param set MC_ATTRATE_I 0.0 |
||||
param set MC_ATTRATE_P 0.09 |
||||
param set MC_ATT_D 0.0 |
||||
param set MC_ATT_I 0.0 |
||||
param set MC_ATT_P 6.8 |
||||
param set MC_YAWPOS_D 0.0 |
||||
param set MC_YAWPOS_I 0.0 |
||||
param set MC_YAWPOS_P 2.0 |
||||
param set MC_YAWRATE_D 0.005 |
||||
param set MC_YAWRATE_I 0.2 |
||||
param set MC_YAWRATE_P 0.3 |
||||
param set NAV_TAKEOFF_ALT 3.0 |
||||
param set MPC_TILT_MAX 0.5 |
||||
param set MPC_THR_MAX 0.7 |
||||
param set MPC_THR_MIN 0.3 |
||||
param set MPC_XY_D 0 |
||||
param set MPC_XY_P 0.5 |
||||
param set MPC_XY_VEL_D 0 |
||||
param set MPC_XY_VEL_I 0 |
||||
param set MPC_XY_VEL_MAX 3 |
||||
param set MPC_XY_VEL_P 0.2 |
||||
param set MPC_Z_D 0 |
||||
param set MPC_Z_P 1 |
||||
param set MPC_Z_VEL_D 0 |
||||
param set MPC_Z_VEL_I 0.1 |
||||
param set MPC_Z_VEL_MAX 2 |
||||
param set MPC_Z_VEL_P 0.20 |
||||
|
||||
param save |
||||
fi |
||||
|
||||
echo "RC script for PX4FMU + PX4IO + PPM-ESCs running" |
||||
|
||||
# |
||||
# Force some key parameters to sane values |
||||
# MAV_TYPE 2 = quadrotor |
||||
# |
||||
param set MAV_TYPE 2 |
||||
|
||||
set EXIT_ON_END no |
||||
|
||||
usleep 10000 |
||||
|
||||
# |
||||
# Start and configure PX4IO or FMU interface |
||||
# |
||||
if px4io detect |
||||
then |
||||
# Start MAVLink (depends on orb) |
||||
mavlink start -d /dev/ttyS1 -b 115200 |
||||
usleep 5000 |
||||
|
||||
sh /etc/init.d/rc.io |
||||
|
||||
if [ $ESC_MAKER = afro ] |
||||
then |
||||
# Set PWM values for Afro ESCs |
||||
px4io idle 1050 1050 1050 1050 |
||||
px4io min 1080 1080 1080 1080 |
||||
px4io max 1860 1860 1860 1860 |
||||
else |
||||
# Set PWM values for typical ESCs |
||||
px4io idle 900 900 900 900 |
||||
px4io min 1110 1100 1100 1100 |
||||
px4io max 1800 1800 1800 1800 |
||||
fi |
||||
else |
||||
fmu mode_pwm |
||||
# Start MAVLink (on UART1 / ttyS0) |
||||
mavlink start -d /dev/ttyS1 -b 115200 |
||||
usleep 5000 |
||||
param set BAT_V_SCALING 0.004593 |
||||
set EXIT_ON_END yes |
||||
fi |
||||
|
||||
# |
||||
# Load mixer |
||||
# |
||||
if [ $FRAME_GEOMETRY == x ] |
||||
then |
||||
echo "Frame geometry X" |
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix |
||||
else |
||||
if [ $FRAME_GEOMETRY == w ] |
||||
then |
||||
echo "Frame geometry W" |
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix |
||||
else |
||||
echo "Frame geometry +" |
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix |
||||
fi |
||||
fi |
||||
|
||||
# |
||||
# Set PWM output frequency |
||||
# |
||||
pwm -u 400 -m 0xff |
||||
|
||||
# |
||||
# Start common for all multirotors apps |
||||
# |
||||
sh /etc/init.d/rc.multirotor |
||||
|
||||
if [ $EXIT_ON_END == yes ] |
||||
then |
||||
exit |
||||
fi |
||||
|
||||
echo "Script end" |
Loading…
Reference in new issue