11
11
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
- import os
15
14
16
- from ament_index_python .packages import get_package_share_directory
17
15
import launch
18
16
from launch .actions import DeclareLaunchArgument
19
17
from launch .actions import GroupAction
26
24
from launch_ros .actions import Node
27
25
from launch_ros .actions import PushRosNamespace
28
26
from launch_ros .descriptions import ComposableNode
27
+ from launch_ros .substitutions import FindPackageShare
29
28
import yaml
30
29
31
30
32
31
def launch_setup (context , * args , ** kwargs ):
33
- lanelet2_map_origin_path = os . path . join (
34
- get_package_share_directory ( "map_loader" ), "config/lanelet2_map_loader.param.yaml"
32
+ lanelet2_map_loader_param_path = LaunchConfiguration ( "lanelet2_map_loader_param_path" ). perform (
33
+ context
35
34
)
36
35
37
- with open (lanelet2_map_origin_path , "r" ) as f :
38
- lanelet2_map_origin_param = yaml .safe_load (f )["/**" ]["ros__parameters" ]
36
+ with open (lanelet2_map_loader_param_path , "r" ) as f :
37
+ lanelet2_map_loader_param = yaml .safe_load (f )["/**" ]["ros__parameters" ]
39
38
40
39
map_hash_generator = Node (
41
40
package = "map_loader" ,
@@ -56,11 +55,9 @@ def launch_setup(context, *args, **kwargs):
56
55
remappings = [("output/lanelet2_map" , "vector_map" )],
57
56
parameters = [
58
57
{
59
- "center_line_resolution" : 5.0 ,
60
58
"lanelet2_map_path" : LaunchConfiguration ("lanelet2_map_path" ),
61
- "lanelet2_map_projector_type" : "MGRS" , # Options: MGRS, UTM
62
59
},
63
- lanelet2_map_origin_param ,
60
+ lanelet2_map_loader_param ,
64
61
],
65
62
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
66
63
)
@@ -144,6 +141,14 @@ def add_launch_arg(name: str, default_value=None, description=None):
144
141
[LaunchConfiguration ("map_path" ), "/pointcloud_map.pcd" ],
145
142
"path to pointcloud map file" ,
146
143
),
144
+ add_launch_arg (
145
+ "lanelet2_map_loader_param_path" ,
146
+ [
147
+ FindPackageShare ("map_loader" ),
148
+ "/config/lanelet2_map_loader.param.yaml" ,
149
+ ],
150
+ "path to lanelet2_map_loader param file" ,
151
+ ),
147
152
add_launch_arg ("use_intra_process" , "false" , "use ROS2 component container communication" ),
148
153
add_launch_arg ("use_multithread" , "false" , "use multithread" ),
149
154
0 commit comments