Skip to content

Commit 0fdafe6

Browse files
authoredMay 24, 2022
feat: add parameter argument for lanelet2_map_loader (#954)
* feat: add parameter argument for lanelet2_map_loader Signed-off-by: h-ohta <hiroki.ota@tier4.jp> * feat: add comment
1 parent c484d8f commit 0fdafe6

File tree

2 files changed

+18
-14
lines changed

2 files changed

+18
-14
lines changed
 

‎launch/tier4_map_launch/launch/map.launch.py

+14-9
Original file line numberDiff line numberDiff line change
@@ -11,9 +11,7 @@
1111
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
14-
import os
1514

16-
from ament_index_python.packages import get_package_share_directory
1715
import launch
1816
from launch.actions import DeclareLaunchArgument
1917
from launch.actions import GroupAction
@@ -26,16 +24,17 @@
2624
from launch_ros.actions import Node
2725
from launch_ros.actions import PushRosNamespace
2826
from launch_ros.descriptions import ComposableNode
27+
from launch_ros.substitutions import FindPackageShare
2928
import yaml
3029

3130

3231
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
3534
)
3635

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"]
3938

4039
map_hash_generator = Node(
4140
package="map_loader",
@@ -56,11 +55,9 @@ def launch_setup(context, *args, **kwargs):
5655
remappings=[("output/lanelet2_map", "vector_map")],
5756
parameters=[
5857
{
59-
"center_line_resolution": 5.0,
6058
"lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"),
61-
"lanelet2_map_projector_type": "MGRS", # Options: MGRS, UTM
6259
},
63-
lanelet2_map_origin_param,
60+
lanelet2_map_loader_param,
6461
],
6562
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
6663
)
@@ -144,6 +141,14 @@ def add_launch_arg(name: str, default_value=None, description=None):
144141
[LaunchConfiguration("map_path"), "/pointcloud_map.pcd"],
145142
"path to pointcloud map file",
146143
),
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+
),
147152
add_launch_arg("use_intra_process", "false", "use ROS2 component container communication"),
148153
add_launch_arg("use_multithread", "false", "use multithread"),
149154

Original file line numberDiff line numberDiff line change
@@ -1,8 +1,7 @@
11
/**:
22
ros__parameters:
3+
lanelet2_map_projector_type: MGRS # Options: MGRS, UTM
4+
latitude: 40.816617984672746 # Latitude of map_origin, using in UTM
5+
longitude: 29.360491808334285 # Longitude of map_origin, using in UTM
36

4-
# Latitude of map_origin
5-
latitude: 40.816617984672746
6-
7-
# Longitude of map_origin
8-
longitude: 29.360491808334285
7+
center_line_resolution: 5.0 # [m]

0 commit comments

Comments
 (0)