forked from HKUST-Aerial-Robotics/FUEL
-
Notifications
You must be signed in to change notification settings - Fork 0
/
simulator.xml
executable file
·114 lines (99 loc) · 5.23 KB
/
simulator.xml
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
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
<launch>
<arg name="init_x"/>
<arg name="init_y"/>
<arg name="init_z"/>
<arg name="map_size_x_"/>
<arg name="map_size_y_"/>
<arg name="map_size_z_"/>
<arg name="box_min_x"/>
<arg name="box_min_y"/>
<arg name="box_min_z"/>
<arg name="box_max_x"/>
<arg name="box_max_y"/>
<arg name="box_max_z"/>
<arg name="c_num"/>
<arg name="p_num"/>
<arg name="odometry_topic"/>
<arg name="obj_num" value="1" />
<!-- map generation 1-->
<!-- Change office.pcd to specify the exploration environment -->
<!-- We provide office2.pcd, office3.pcd and pillar.pcd in this repo -->
<node pkg ="map_generator" name ="map_pub" type ="map_pub" output = "screen" args="$(find map_generator)/resource/office.pcd"/>
<!-- map generation 2-->
<!-- <node pkg ="map_generator" name ="random_forest" type ="random_forest" output = "screen">
<remap from="~odometry" to="$(arg odometry_topic)"/>
<param name="init_state_x" value="$(arg init_x)"/>
<param name="init_state_y" value="$(arg init_y)"/>
<param name="map/x_size" value="$(arg map_size_x_)" />
<param name="map/y_size" value="$(arg map_size_y_)" />
<param name="map/z_size" value="$(arg map_size_z_)" />
<param name="map/resolution" value="0.1"/>
<param name="ObstacleShape/seed" value="1"/>
<param name="map/obs_num" value="0"/>
<param name="map/circle_num" value="0"/>
<param name="ObstacleShape/lower_rad" value="0.9"/>
<param name="ObstacleShape/upper_rad" value="1.6"/>
<param name="ObstacleShape/lower_hei" value="3.5"/>
<param name="ObstacleShape/upper_hei" value="4.0"/>
<param name="ObstacleShape/radius_l" value="0.7"/>
<param name="ObstacleShape/radius_h" value="0.8"/>
<param name="ObstacleShape/z_l" value="0.7"/>
<param name="ObstacleShape/z_h" value="0.8"/>
<param name="ObstacleShape/theta" value="0.5"/>
<param name="sensing/radius" value="5.0"/>
<param name="sensing/rate" value="10.0"/>
</node> -->
<!-- <node pkg ="traj_utils" name ="process_msg" type ="process_msg" output = "screen">
</node> -->
<node pkg="so3_quadrotor_simulator" type="quadrotor_simulator_so3" name="quadrotor_simulator_so3" output="screen">
<param name="rate/odom" value="200.0"/>
<param name="simulator/init_state_x" value="$(arg init_x)"/>
<param name="simulator/init_state_y" value="$(arg init_y)"/>
<param name="simulator/init_state_z" value="$(arg init_z)"/>
<remap from="~odom" to="/visual_slam/odom"/>
<remap from="~cmd" to="so3_cmd"/>
<remap from="~force_disturbance" to="force_disturbance"/>
<remap from="~moment_disturbance" to="moment_disturbance"/>
</node>
<node pkg="nodelet" type="nodelet" args="standalone so3_control/SO3ControlNodelet" name="so3_control" required="true" output="screen">
<remap from="~odom" to="/state_ukf/odom"/>
<remap from="~position_cmd" to="/exploration_node/planning/pos_cmd"/>
<remap from="~motors" to="motors"/>
<remap from="~corrections" to="corrections"/>
<remap from="~so3_cmd" to="so3_cmd"/>
<rosparam file="$(find so3_control)/config/gains_hummingbird.yaml"/>
<rosparam file="$(find so3_control)/config/corrections_hummingbird.yaml"/>
<param name="mass" value="0.98"/>
<param name="use_angle_corrections " value="false"/>
<param name="use_external_yaw " value="false"/>
<param name="gains/rot/z" value="1.0"/>
<param name="gains/ang/z" value="0.1"/>
</node>
<node pkg="so3_disturbance_generator" name="so3_disturbance_generator" type="so3_disturbance_generator" output="screen">
<remap from="~odom" to="/visual_slam/odom"/>
<remap from="~noisy_odom" to="/state_ukf/odom"/>
<remap from="~correction" to="/visual_slam/correction"/>
<remap from="~force_disturbance" to="force_disturbance"/>
<remap from="~moment_disturbance" to="moment_disturbance"/>
</node>
<node pkg="odom_visualization" name="odom_visualization" type="odom_visualization" output="screen">
<remap from="~odom" to="/visual_slam/odom"/>
<param name="color/a" value="1.0"/>
<param name="color/r" value="0.0"/>
<param name="color/g" value="0.0"/>
<param name="color/b" value="1.0"/>
<param name="covariance_scale" value="100.0"/>
<param name="robot_scale" value="1.0"/>
</node>
<node pkg="local_sensing_node" type="pcl_render_node" name="pcl_render_node" output="screen">
<rosparam command="load" file="$(find local_sensing_node)/params/camera.yaml" />
<param name="sensing_horizon" value="5.0" />
<param name="sensing_rate" value="15.0"/>
<param name="estimation_rate" value="15.0"/>
<param name="map/x_size" value="$(arg map_size_x_)"/>
<param name="map/y_size" value="$(arg map_size_y_)"/>
<param name="map/z_size" value="$(arg map_size_z_)"/>
<remap from="~global_map" to="/map_generator/global_cloud"/>
<remap from="~odometry" to="$(arg odometry_topic)"/>
</node>
</launch>