hand_control/launch/ardrone.launch
Louis-Guillaume DUBOIS 1edbc97844 up to 8 meters high
2015-06-01 17:17:32 +02:00

43 lines
1.5 KiB
XML

<!-- cf ARDrone Developer Guide -->
<launch>
<node name="ardrone_driver" pkg="ardrone_autonomy" type="ardrone_driver" output="screen" clear_params="true">
<!-- indoor -->
<param name="outdoor" value="0" />
<param name="max_bitrate" value="4000" />
<param name="bitrate" value="4000" />
<!-- 0 : 15Hz, drone sends a reduced set
of navigation data (without debugging info) -->
<!-- 1 : 200Hz -->
<param name="navdata_demo" value="0" />
<param name="flight_without_shell" value="0" />
<!-- in mm -->
<param name="altitude_max" value="8000" /><!-- 2 m -->
<param name="altitude_min" value="50" />
<!-- in radians, between 0. and 0.52 (30°) -->
<param name="euler_angle_max" value="0.21" />
<!-- maximum vertical speed, in mm/s -->
<!-- between 200 and 2000 -->
<param name="control_vz_max" value="700" />
<!-- maximum yaw speed, in radians/s -->
<!-- betwenn 0.7 and 6.11 -->
<param name="control_yaw" value="1.75" />
<!-- ROS driver parameters -->
<param name="do_imu_caliberation" value="false" />
<param name="tf_prefix" value="mydrone" />
<!-- Covariance Values (3x3 matrices reshaped to 1x9)-->
<rosparam param="cov/imu_la">[0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1]</rosparam>
<rosparam param="cov/imu_av">[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]</rosparam>
<rosparam param="cov/imu_or">[1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 100000.0]</rosparam>
</node>
</launch>