PX4-Autopilot/launch/multicopter.launch
2015-01-10 19:14:23 +01:00

25 lines
1.0 KiB
XML

<launch>
<group ns="px4_multicopter">
<node pkg="joy" name="joy_node" type="joy_node"/>
<node pkg="px4" name="manual_input" type="manual_input"/>
<node pkg="px4" name="commander" type="commander"/>
<node pkg="px4" name="mc_mixer" type="mc_mixer"/>
<node pkg="px4" name="attitude_estimator" type="attitude_estimator"/>
<node pkg="px4" name="mc_att_control" type="mc_att_control"/>
<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" />
</group>
</launch>