Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: add parameter argument for lanelet2_map_loader #954

Merged
merged 2 commits into from
May 24, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 14 additions & 9 deletions launch/tier4_map_launch/launch/map.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,7 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import os

from ament_index_python.packages import get_package_share_directory
import launch
from launch.actions import DeclareLaunchArgument
from launch.actions import GroupAction
Expand All @@ -26,16 +24,17 @@
from launch_ros.actions import Node
from launch_ros.actions import PushRosNamespace
from launch_ros.descriptions import ComposableNode
from launch_ros.substitutions import FindPackageShare
import yaml


def launch_setup(context, *args, **kwargs):
lanelet2_map_origin_path = os.path.join(
get_package_share_directory("map_loader"), "config/lanelet2_map_loader.param.yaml"
lanelet2_map_loader_param_path = LaunchConfiguration("lanelet2_map_loader_param_path").perform(
context
)

with open(lanelet2_map_origin_path, "r") as f:
lanelet2_map_origin_param = yaml.safe_load(f)["/**"]["ros__parameters"]
with open(lanelet2_map_loader_param_path, "r") as f:
lanelet2_map_loader_param = yaml.safe_load(f)["/**"]["ros__parameters"]

map_hash_generator = Node(
package="map_loader",
Expand All @@ -56,11 +55,9 @@ def launch_setup(context, *args, **kwargs):
remappings=[("output/lanelet2_map", "vector_map")],
parameters=[
{
"center_line_resolution": 5.0,
"lanelet2_map_path": LaunchConfiguration("lanelet2_map_path"),
"lanelet2_map_projector_type": "MGRS", # Options: MGRS, UTM
},
lanelet2_map_origin_param,
lanelet2_map_loader_param,
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
Expand Down Expand Up @@ -144,6 +141,14 @@ def add_launch_arg(name: str, default_value=None, description=None):
[LaunchConfiguration("map_path"), "/pointcloud_map.pcd"],
"path to pointcloud map file",
),
add_launch_arg(
"lanelet2_map_loader_param_path",
[
FindPackageShare("map_loader"),
"/config/lanelet2_map_loader.param.yaml",
],
"path to lanelet2_map_loader param file",
),
add_launch_arg("use_intra_process", "false", "use ROS2 component container communication"),
add_launch_arg("use_multithread", "false", "use multithread"),

Expand Down
9 changes: 4 additions & 5 deletions map/map_loader/config/lanelet2_map_loader.param.yaml
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
/**:
ros__parameters:
lanelet2_map_projector_type: MGRS # Options: MGRS, UTM
latitude: 40.816617984672746 # Latitude of map_origin, using in UTM
longitude: 29.360491808334285 # Longitude of map_origin, using in UTM

# Latitude of map_origin
latitude: 40.816617984672746

# Longitude of map_origin
longitude: 29.360491808334285
center_line_resolution: 5.0 # [m]