-
Notifications
You must be signed in to change notification settings - Fork 13
/
Copy pathmecanumrover_move_base_dwa.launch
153 lines (132 loc) · 7.62 KB
/
mecanumrover_move_base_dwa.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
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
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
<!--
MECANUMROVER move base demo launch
USE STATIC MAP
-->
<launch>
<!-- 引数 -->
<arg name="rover_type" default="mecanum2" doc="mecanum2 / g120" />
<arg name="lrf" default="urg" doc="urg / tg30 / sim"/>
<!-- オドメトリの配信ノード -->
<node pkg="mecanumrover_samples" type="pub_odom" name="pub_odom" />
<!-- URG-04LX-UG01の場合 -->
<group if="$(eval lrf=='urg')">
<!-- LRFのデバイスファイルパス -->
<arg name="port_urg" default="/dev/ttyACM0" /> <!-- LRFのデバイスファイルパスを設定してください -->
<!-- メカナムローバーの旋回中心からLRFまでの座標変換の設定 -->
<group if="$(eval rover_type=='mecanum2')">
<!-- メカナムローバーVer2.0 or Ver2.1の場合 -->
<!-- argsの項でLRFの位置を調整できます。 args="x y z y p r" -->
<node pkg="tf" type="static_transform_publisher" name="stp_laser" args="0.199 0 0.08 0 0 3.14159 base_link lidar_link 1" />
</group>
<group if="$(eval rover_type=='g120')">
<!-- メカナムローバーG120の場合 -->
<node pkg="tf" type="static_transform_publisher" name="stp_laser" args="0.285 0 0.24 0 0 0 base_link lidar_link 1" />
</group>
<!-- LRFのデバイスドライバノード -->
<node pkg="urg_node" type="urg_node" name="urg_node">
<param name="serial_port" value="$(arg port_urg)" />
<param name="frame_id" value="lidar_link" />
<param name="angle_min" value="-1.57" /> <!-- 視野角の指定(最小値) -->
<param name="angle_max" value="1.57" /> <!-- 視野角の指定(最大値) -->
</node>
</group>
<!-- YDLiDAR TG30の場合 -->
<group if="$(eval lrf=='tg30')">
<!-- メカナムローバーの旋回中心からLRFまでの座標変換の設定 -->
<group if="$(eval rover_type=='mecanum2')">
<!-- メカナムローバーVer2.0 or Ver2.1の場合 -->
<!-- argsの項でLRFの位置を調整できます。 args="x y z y p r" -->
<node pkg="tf" type="static_transform_publisher" name="stp_laser" args="0.22 0 0.08 0 0 0 base_link lidar_link 1" />
</group>
<group if="$(eval rover_type=='g120')">
<!-- メカナムローバーG120の場合 -->
<node pkg="tf" type="static_transform_publisher" name="stp_laser" args="0.305 0 0.24 0 0 0 base_link lidar_link 1" />
</group>
<!-- YDLiDARデバイスドライバノード-->
<node name="ydlidar_lidar_publisher" pkg="ydlidar_ros_driver" type="ydlidar_ros_driver_node" output="screen" respawn="false" >
<!-- string property -->
<param name="port" type="string" value="/dev/ydlidar"/>
<param name="frame_id" type="string" value="lidar_link"/>
<param name="ignore_array" type="string" value=""/>
<!-- int property -->
<param name="baudrate" type="int" value="512000"/>
<!-- 0:TYPE_TOF, 1:TYPE_TRIANGLE, 2:TYPE_TOF_NET -->
<param name="lidar_type" type="int" value="0"/>
<!-- 0:YDLIDAR_TYPE_SERIAL, 1:YDLIDAR_TYPE_TCP -->
<param name="device_type" type="int" value="0"/>
<param name="sample_rate" type="int" value="20"/>
<param name="abnormal_check_count" type="int" value="4"/>
<!-- bool property -->
<param name="resolution_fixed" type="bool" value="true"/>
<param name="auto_reconnect" type="bool" value="true"/>
<param name="reversion" type="bool" value="true"/>
<param name="inverted" type="bool" value="true"/>
<param name="isSingleChannel" type="bool" value="false"/>
<param name="intensity" type="bool" value="false"/>
<param name="support_motor_dtr" type="bool" value="false"/>
<param name="invalid_range_is_inf" type="bool" value="false"/>
<param name="point_cloud_preservative" type="bool" value="false"/>
<!-- float property -->
<param name="angle_min" type="double" value="-180" /> <!-- センサの正面を0度する視野角の指定(最小値) -->
<param name="angle_max" type="double" value="180" /> <!-- センサの正面を0度する視野角の指定(最大値) -->
<param name="range_min" type="double" value="0.01" />
<param name="range_max" type="double" value="50.0" />
<param name="frequency" type="double" value="10.0"/>
</node>
</group>
<!-- シミュレータの場合 -->
<group if="$(eval lrf=='sim')">
</group>
<!-- mapサーバー -->
<arg name="map_file" default="$(find mecanumrover_samples)/map/vmecanumrover_samplemap.yaml"/> <!--マップファイルのパスの指定 -->
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" />
<!--
自己位置推定ノード amcl
各パラメータについては http://wiki.ros.org/amcl
を参照してください。
-->
<!--<include file="$(find amcl)/examples/amcl_diff.launch" />-->
<node pkg="amcl" type="amcl" name="amcl" output="screen" args="/scan:=/scan">
<param name="gui_publish_rate" value="5.0"/>
<param name="odom_model_type" value="omni"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="2000"/>
<param name="kld_err" value="0.05"/>
<param name="kld_z" value="0.95"/>
<param name="odom_alpha1" value="7.0"/>
<param name="odom_alpha2" value="10.0"/>
<param name="odom_alpha3" value="7.0"/>
<param name="odom_alpha4" value="10.0"/>
<param name="laser_max_beams" value="60"/>
<param name="laser_z_hit" value="0.7"/>
<param name="laser_z_short" value="0.05"/>
<param name="laser_z_max" value="0.05"/>
<param name="laser_z_rand" value="0.3"/>
<param name="laser_sigma_hit" value="0.2"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_lambda_short" value="0.1"/>
<param name="laser_model_type" value="likelihood_field"/>
<!-- <param name="laser_model_type" value="beam"/> -->
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="update_min_d" value="0.05"/>
<param name="update_min_a" value="0.03"/>
<param name="odom_frame_id" value="odom"/>
<param name="base_frame_id" value="base_link" />
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.2"/>
<param name="recovery_alpha_slow" value="0.001"/>
<param name="recovery_alpha_fast" value="0.01"/>
<param name="use_map_topic" value="false" />
</node>
<!--- 経路計画,指令値生成ノード move_base -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" args="/cmd_vel:=/rover_twist">
<rosparam file="$(find mecanumrover_samples)/configuration_files/mecanumrover_costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find mecanumrover_samples)/configuration_files/mecanumrover_costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find mecanumrover_samples)/configuration_files/mecanumrover_local_costmap_params.yaml" command="load" />
<rosparam file="$(find mecanumrover_samples)/configuration_files/mecanumrover_global_costmap_params.yaml" command="load" />
<rosparam file="$(find mecanumrover_samples)/configuration_files/mecanumrover_dwa_local_planner_params.yaml" command="load" />
<rosparam file="$(find mecanumrover_samples)/configuration_files/mecanumrover_move_base_params.yaml" command="load" />
</node>
<!-- Rviz -->
<node pkg="rviz" type="rviz" args="-d '$(find mecanumrover_samples)/configuration_files/rviz/navigation.rviz'" name="visualizer" respawn="true" />
</launch>