diff --git a/config/adc_rosnav/global_planner/iri_opendrive_params.yaml b/config/adc_rosnav/global_planner/iri_opendrive_params.yaml index 6aaa42b8b930d49938fcd2b6ee5ecf953bd2c0fa..45e7c0e11bbb974e4e007f8c1aa95f133b3227e5 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 c5407d655d58ff287a516bab78aa6636c571c125..a285bd93773f3d9e1abc799c89d32f57191dd2b4 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>