#!/bin/sh
#
# @name Ignition Gazebo X3
#
# @type Quadrotor
#

. ${R}etc/init.d/rc.mc_defaults

PX4_SIMULATOR=${PX4_SIMULATOR:=ignition}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500}
PX4_SIM_WORLD=${PX4_SIM_WORLD:=default}

param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4

param set-default CA_ROTOR0_PX 0.13
param set-default CA_ROTOR0_PY 0.22
param set-default CA_ROTOR0_KM  0.05

param set-default CA_ROTOR1_PX -0.13
param set-default CA_ROTOR1_PY -0.20
param set-default CA_ROTOR1_KM  0.05

param set-default CA_ROTOR2_PX 0.13
param set-default CA_ROTOR2_PY -0.22
param set-default CA_ROTOR2_KM -0.05

param set-default CA_ROTOR3_PX -0.13
param set-default CA_ROTOR3_PY 0.20
param set-default CA_ROTOR3_KM -0.05

param set-default SIM_IGN_FUNC1 101
param set-default SIM_IGN_FUNC2 102
param set-default SIM_IGN_FUNC3 103
param set-default SIM_IGN_FUNC4 104

param set-default SIM_IGN_MIN1 150
param set-default SIM_IGN_MIN2 150
param set-default SIM_IGN_MIN3 150
param set-default SIM_IGN_MIN4 150

param set-default SIM_IGN_MAX1 1000
param set-default SIM_IGN_MAX2 1000
param set-default SIM_IGN_MAX3 1000
param set-default SIM_IGN_MAX4 1000

param set-default MPC_THR_HOVER 0.60
