diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2015-02-01 11:57:31 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2015-02-01 12:03:32 +0100 |
commit | 3b07890361d56ce80d881e3969ff097b5cd96af4 (patch) | |
tree | 335fe6f103f9cc376a36e0247353477464a932fb /launch/iris.launch | |
parent | e547176ba19da5e27b414bbff4a2ac77e6aa2903 (diff) | |
download | px4-firmware-3b07890361d56ce80d881e3969ff097b5cd96af4.tar.gz px4-firmware-3b07890361d56ce80d881e3969ff097b5cd96af4.tar.bz2 px4-firmware-3b07890361d56ce80d881e3969ff097b5cd96af4.zip |
update sitl default params, make posctrl very slow for now
Diffstat (limited to 'launch/iris.launch')
-rw-r--r-- | launch/iris.launch | 17 |
1 files changed, 6 insertions, 11 deletions
diff --git a/launch/iris.launch b/launch/iris.launch index 44a0ae034..7b5b13250 100644 --- a/launch/iris.launch +++ b/launch/iris.launch @@ -3,18 +3,13 @@ <include file="$(find px4)/launch/multicopter_w.launch" /> <group ns="px4_multicopter"> - <param name="MC_ROLL_P" type="double" value="6.0" /> - <param name="MC_PITCH_P" type="double" value="6.0" /> - <param name="MC_ROLLRATE_P" type="double" value="0.05" /> - <param name="MC_ROLLRATE_D" type="double" value="0.0" /> - <param name="MC_PITCHRATE_P" type="double" value="0.05" /> - <param name="MC_PITCHRATE_D" type="double" value="0.0" /> - <param name="MC_YAW_FF" type="double" value="0" /> - <param name="MC_YAW_P" type="double" value="3.0" /> - <param name="MC_YAWRATE_P" type="double" value="0.5" /> - <param name="MC_MAN_R_MAX" type="double" value="10.0" /> - <param name="MC_MAN_P_MAX" type="double" value="10.0" /> <param name="mixer" type="string" value="i" /> + <param name="MPC_XY_P" type="double" value="1.0" /> + <param name="MPC_XY_FF" type="double" value="0.0" /> + <param name="MPC_XY_VEL_P" type="double" value="0.01" /> + <param name="MPC_XY_VEL_I" type="double" value="0.0" /> + <param name="MPC_XY_VEL_D" type="double" value="0.01" /> + <param name="MPC_XY_VEL_MAX" type="double" value="2.0" /> </group> </launch> |