-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathmavros_sitl.launch
79 lines (73 loc) · 2.9 KB
/
mavros_sitl.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
<launch>
<arg name="viz" default="true"/>
<arg name="respawn" default="true"/>
<arg name="gcs_url" default="" />
<node pkg="mavros" type="mavros_node" name="mavros" required="false" clear_params="true" respawn="$(arg respawn)" respawn_delay="5" output="screen">
<param name="fcu_url" value="udp://@192.168.56.1:14580"/>
<param name="gcs_url" value="$(arg gcs_url)" />
<!-- default px4 params -->
<rosparam command="load" file="$(find mavros)/launch/px4_config.yaml"/>
<!-- rangefinders -->
<rosparam>
distance_sensor:
rangefinder_0:
id: 0
frame_id: "rangefinder"
orientation: PITCH_270
field_of_view: 0.5
rangefinder_1:
id: 1
frame_id: "rangefinder"
orientation: PITCH_270
field_of_view: 0.5
rangefinder_2_sub:
subscriber: true
id: 2
orientation: PITCH_270
rangefinder_3_sub:
subscriber: true
id: 3
orientation: PITCH_270
</rosparam>
<!-- additional params -->
<param name="local_position/frame_id" value="local_origin"/>
<param name="local_position/tf/send" value="true"/>
<param name="local_position/tf/frame_id" value="local_origin"/>
<param name="local_position/tf/child_frame_id" value="fcu"/>
<param name="global_position/tf/send" value="false"/>
<param name="imu/frame_id" value="fcu"/>
<rosparam param="plugin_blacklist">
- safety_area
- image_pub
- vibration
- rangefinder
- 3dr_radio
- actuator_control
- hil_controls
- vfr_hud
- vision_speed_estimate
- fake_gps
- cam_imu_sync
- hil
- adsb
- waypoint
- obstacle_distance
- setpoint_accel
- trajectory
- wind_estimation
- home_position
</rosparam>
</node>
<!-- Rangefinders frame -->
<node pkg="tf2_ros" type="static_transform_publisher" name="rangefinder_frame" args="0 0 -0.05 0 1.5707963268 0 fcu rangefinder"/>
<!-- Copter visualization -->
<node name="copter_visualization" pkg="mavros_extras" type="copter_visualization" if="$(arg viz)">
<remap to="mavros/local_position/pose" from="local_position"/>
<remap to="mavros/setpoint_position/local" from="local_setpoint"/>
<param name="fixed_frame_id" value="local_origin"/>
<param name="child_frame_id" value="fcu"/>
<param name="marker_scale" value="1"/>
<param name="max_track_size" value="20"/>
<param name="num_rotors" value="4"/>
</node>
</launch>