-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathmapviz.launch
41 lines (32 loc) · 1.76 KB
/
mapviz.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
<?xml version="1.0"?>
<launch>
<!-- XXX if you cant get tile_map to work try buidling from source this will solve any hidden dependency issues XXX-->
<!-- https://github.com/swri-robotics/mapviz -->.
<!--https://github.com/danielsnider/MapViz-Tile-Map-Google-Maps-Satellite -->
### sudo docker run -p 8080:8080 -d -t -v ~/mapproxy:/mapproxy danielsnider/mapproxy
### Then put this URL into the MapViz option "Custom WMTS Source..." http://localhost:8080/wmts/gm_layer/gm_grid/{level}/{x}/{y}.png
<arg name="xy_origin_initilization" default="auto"/> <!-- "auto"(will use gps) "stutz"(if indoors) -->
<arg name="mapvizconfig" default="$(find agbot_0)/config/test0_mapviz.mvc" />
<node pkg="mapviz" type="mapviz" name="$(anon mapviz)" args="-d $(arg mapvizconfig)" required="true" output="log"/>
<node pkg="swri_transform_util" type="initialize_origin.py" name="initialize_origin" >
<param name="local_xy_frame" value="map"/>
<param name="local_xy_origin" value="$(arg xy_origin_initilization)"/> "auto" setting will set the origin to the first gps fix that it recieves
### if using auto consider the following:
### GPSFix message type subscribes to message topic 'gps'
### NavSatFix message type subscribes to message topic 'fix'
<remap from="fix" to="/gps/fix"/>
<rosparam param="local_xy_origins">
[{ name: stutz,
latitude: 39.78020,
longitude: -86.16289,
altitude: 33.719,
heading: 0.0},
{ name: beck_ag_center,
latitude: 40.4692641,
longitude: -86.9929879,
altitude: 200.0,
heading: 0.0}]
</rosparam>
</node>
<!--node pkg="tf2_ros" type="static_transform_publisher" name="swri_transform" args="0 0 0 0 0 0 world map 100" -->
</launch>