ros sim: use ardrone model

This commit is contained in:
Thomas Gubler
2015-01-10 19:14:23 +01:00
parent aa8555c02b
commit 6580d66d45
4 changed files with 8 additions and 8 deletions

View File

@@ -1,6 +1,6 @@
<launch>
<include file="$(find mav_gazebo)/launch/vtol_empty_world_with_joy.launch" />
<include file="$(find mav_gazebo)/launch/ardrone_empty_world_with_joy.launch" />
<include file="$(find px4)/launch/multicopter.launch" />
</launch>

View File

@@ -14,9 +14,9 @@
<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.0" />
<param name="MC_YAW_P" type="double" value="1.0" />
<param name="MC_YAWRATE_P" type="double" value="0.2" />
<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" />
</group>