rename parameters in launch file to match new MP parameters

This commit is contained in:
Andreas Antener
2015-05-15 09:26:07 +02:00
parent fa8dc57236
commit 2bcfd4f6f7
2 changed files with 16 additions and 16 deletions

View File

@@ -6,14 +6,14 @@
</include>
<group ns="$(arg ns)">
<param name="MPC_XY_P" type="double" value="1.0" />
<param name="MPC_XY_FF" type="double" value="0.1" />
<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" />
<param name="MPC_Z_VEL_P" type="double" value="0.3" />
<param name="MPC_Z_P" type="double" value="2" />
<param name="MPP_XY_P" type="double" value="1.0" />
<param name="MPP_XY_FF" type="double" value="0.1" />
<param name="MPP_XY_VEL_P" type="double" value="0.01" />
<param name="MPP_XY_VEL_I" type="double" value="0.0" />
<param name="MPP_XY_VEL_D" type="double" value="0.01" />
<param name="MPP_XY_VEL_MAX" type="double" value="2.0" />
<param name="MPP_Z_VEL_P" type="double" value="0.3" />
<param name="MPP_Z_P" type="double" value="2" />
<param name="vehicle_model" type="string" value="ardrone" />
</group>

View File

@@ -7,14 +7,14 @@
<group ns="$(arg ns)">
<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" />
<param name="MPC_Z_VEL_P" type="double" value="0.3" />
<param name="MPC_Z_P" type="double" value="2" />
<param name="MPP_XY_P" type="double" value="1.0" />
<param name="MPP_XY_FF" type="double" value="0.0" />
<param name="MPP_XY_VEL_P" type="double" value="0.01" />
<param name="MPP_XY_VEL_I" type="double" value="0.0" />
<param name="MPP_XY_VEL_D" type="double" value="0.01" />
<param name="MPP_XY_VEL_MAX" type="double" value="2.0" />
<param name="MPP_Z_VEL_P" type="double" value="0.3" />
<param name="MPP_Z_P" type="double" value="2" />
<param name="vehicle_model" type="string" value="iris" />
</group>