Skip to content
Snippets Groups Projects
Commit 3b078903 authored by Thomas Gubler's avatar Thomas Gubler
Browse files

update sitl default params, make posctrl very slow for now

parent e547176b
No related branches found
No related tags found
No related merge requests found
......@@ -3,17 +3,14 @@
<include file="$(find px4)/launch/multicopter_x.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="5.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="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>
<node pkg="rosbag" type="record" name="record" output="screen" args="-a -O multicopter"/>
</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>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment