From 3f11f12498b2f745d4ad92e007037f72cca6f8ed Mon Sep 17 00:00:00 2001 From: Sergi Hernandez Juan <shernand@iri.upc.edu> Date: Mon, 19 Apr 2021 08:38:08 +0200 Subject: [PATCH] Added a static transform between the map and opendrive frames. Added arguments to the navigation launch to specify the opendrive transform. --- config/adc_rosnav/global_planner/iri_opendrive_params.yaml | 1 + launch/adc_navigation.launch | 7 +++++++ 2 files changed, 8 insertions(+) diff --git a/config/adc_rosnav/global_planner/iri_opendrive_params.yaml b/config/adc_rosnav/global_planner/iri_opendrive_params.yaml index 6aaa42b..45e7c0e 100644 --- a/config/adc_rosnav/global_planner/iri_opendrive_params.yaml +++ b/config/adc_rosnav/global_planner/iri_opendrive_params.yaml @@ -1,5 +1,6 @@ base_global_planner: "iri_opendrive_global_planner/OpendriveGlobalPlanner" OpendriveGlobalPlanner: + opendrive_frame: "opendrive" angle_tol: 0.5 dist_tol: 0.3 multi_hyp: True diff --git a/launch/adc_navigation.launch b/launch/adc_navigation.launch index c5407d6..a285bd9 100644 --- a/launch/adc_navigation.launch +++ b/launch/adc_navigation.launch @@ -19,6 +19,10 @@ <arg name="car_y" default="0.0"/> <arg name="car_yaw" default="0.0"/> + <arg name="opendrive_x" default="0.0"/> + <arg name="opendrive_y" default="0.0"/> + <arg name="opendrive_yaw" default="0.0"/> + <include file="$(find iri_rosnav)/launch/nav.launch"> <arg name="ns" value="$(arg name)"/> <arg name="path" value="$(find iri_adc_launch)/config/adc_rosnav"/> @@ -59,4 +63,7 @@ <param name="/$(arg name)/move_base/OpendriveGlobalPlanner/opendrive_file" value="$(arg opendrive_path)/$(arg map_name).xodr" /> + <node name="static_tf_map_to_opendrive" pkg="tf" type="static_transform_publisher" + args="$(arg opendrive_x) $(arg opendrive_y) 0 $(arg opendrive_yaw) 0 0 map opendrive 100"> + </node> </launch> -- GitLab