Skip to content

Commit f5eca32

Browse files
authored
Merge branch 'main' into feature/3d_distortion_corrector
2 parents 9a724c0 + ad46e3c commit f5eca32

File tree

96 files changed

+377
-673
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

96 files changed

+377
-673
lines changed

.github/CODEOWNERS

+1-1
Original file line numberDiff line numberDiff line change
@@ -156,6 +156,7 @@ perception/traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhon
156156
perception/traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp
157157
perception/traffic_light_visualization/** tao.zhong@tier4.jp yukihiro.saito@tier4.jp
158158
planning/autoware_remaining_distance_time_calculator/** ahmed.ebrahim@leodrive.ai
159+
planning/autoware_static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp
159160
planning/behavior_path_avoidance_by_lane_change_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp
160161
planning/behavior_path_avoidance_module/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp
161162
planning/behavior_path_dynamic_avoidance_module/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp
@@ -208,7 +209,6 @@ planning/sampling_based_planner/frenet_planner/** maxime.clement@tier4.jp
208209
planning/sampling_based_planner/path_sampler/** maxime.clement@tier4.jp
209210
planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp
210211
planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
211-
planning/static_centerline_generator/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp
212212
planning/surround_obstacle_checker/** satoshi.ota@tier4.jp
213213
sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
214214
sensing/image_diagnostics/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp

common/component_interface_tools/CMakeLists.txt

+10-1
Original file line numberDiff line numberDiff line change
@@ -3,5 +3,14 @@ project(component_interface_tools)
33

44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
6-
ament_auto_add_executable(service_log_checker src/service_log_checker.cpp)
6+
7+
ament_auto_add_library(${PROJECT_NAME} SHARED
8+
src/service_log_checker.cpp
9+
)
10+
11+
rclcpp_components_register_node(${PROJECT_NAME}
12+
PLUGIN "ServiceLogChecker"
13+
EXECUTABLE service_log_checker_node
14+
)
15+
716
ament_auto_package(INSTALL_TO_SHARE launch)
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
<launch>
2-
<node pkg="component_interface_tools" exec="service_log_checker" name="service_log_checker"/>
2+
<node pkg="component_interface_tools" exec="service_log_checker_node"/>
33
</launch>

common/component_interface_tools/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
<depend>diagnostic_updater</depend>
1414
<depend>fmt</depend>
1515
<depend>rclcpp</depend>
16+
<depend>rclcpp_components</depend>
1617
<depend>tier4_system_msgs</depend>
1718
<depend>yaml_cpp_vendor</depend>
1819

common/component_interface_tools/src/service_log_checker.cpp

+4-11
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,8 @@
2222
#define FMT_HEADER_ONLY
2323
#include <fmt/format.h>
2424

25-
ServiceLogChecker::ServiceLogChecker() : Node("service_log_checker"), diagnostics_(this)
25+
ServiceLogChecker::ServiceLogChecker(const rclcpp::NodeOptions & options)
26+
: Node("service_log_checker", options), diagnostics_(this)
2627
{
2728
sub_ = create_subscription<ServiceLog>(
2829
"/service_log", 50, std::bind(&ServiceLogChecker::on_service_log, this, std::placeholders::_1));
@@ -98,13 +99,5 @@ void ServiceLogChecker::update_diagnostics(diagnostic_updater::DiagnosticStatusW
9899
}
99100
}
100101

101-
int main(int argc, char ** argv)
102-
{
103-
rclcpp::init(argc, argv);
104-
rclcpp::executors::SingleThreadedExecutor executor;
105-
auto node = std::make_shared<ServiceLogChecker>();
106-
executor.add_node(node);
107-
executor.spin();
108-
executor.remove_node(node);
109-
rclcpp::shutdown();
110-
}
102+
#include <rclcpp_components/register_node_macro.hpp>
103+
RCLCPP_COMPONENTS_REGISTER_NODE(ServiceLogChecker)

common/component_interface_tools/src/service_log_checker.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
class ServiceLogChecker : public rclcpp::Node
2727
{
2828
public:
29-
ServiceLogChecker();
29+
explicit ServiceLogChecker(const rclcpp::NodeOptions & options);
3030

3131
private:
3232
using ServiceLog = tier4_system_msgs::msg::ServiceLog;

map/map_height_fitter/src/map_height_fitter.cpp

+3-11
Original file line numberDiff line numberDiff line change
@@ -200,20 +200,12 @@ double MapHeightFitter::Impl::get_ground_height(const Point & point) const
200200
}
201201
}
202202
} else if (fit_target_ == "vector_map") {
203-
lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(vector_map_);
204-
205-
geometry_msgs::msg::Pose pose;
206-
pose.position.x = x;
207-
pose.position.y = y;
208-
pose.position.z = 0.0;
209-
lanelet::ConstLanelet closest_lanelet;
210-
const bool result =
211-
lanelet::utils::query::getClosestLanelet(all_lanelets, pose, &closest_lanelet);
212-
if (!result) {
203+
const auto closest_points = vector_map_->pointLayer.nearest(lanelet::BasicPoint2d{x, y}, 1);
204+
if (closest_points.empty()) {
213205
RCLCPP_WARN_STREAM(logger, "failed to get closest lanelet");
214206
return point.z;
215207
}
216-
height = closest_lanelet.centerline().back().z();
208+
height = closest_points.front().z();
217209
}
218210

219211
return std::isfinite(height) ? height : point.z;

planning/.pages

+1-1
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ nav:
6767
- 'About Motion Velocity Smoother': planning/motion_velocity_smoother
6868
- 'About Motion Velocity Smoother (Japanese)': planning/motion_velocity_smoother/README.ja
6969
- 'Scenario Selector': planning/scenario_selector
70-
- 'Static Centerline Generator': planning/static_centerline_generator
70+
- 'Static Centerline Generator': planning/autoware_static_centerline_generator
7171
- 'API and Library':
7272
- 'Costmap Generator': planning/costmap_generator
7373
- 'External Velocity Limit Selector': planning/external_velocity_limit_selector
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
cmake_minimum_required(VERSION 3.14)
2+
project(autoware_planning_test_manager)
3+
4+
find_package(autoware_cmake REQUIRED)
5+
autoware_package()
6+
7+
ament_auto_add_library(autoware_planning_test_manager SHARED
8+
src/autoware_planning_test_manager.cpp
9+
)
10+
11+
ament_auto_package()
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
# Planning Interface Test Manager
2+
3+
## Background
4+
5+
In each node of the planning module, when exceptional input, such as unusual routes or significantly deviated ego-position, is given, the node may not be prepared for such input and could crash. As a result, debugging node crashes can be time-consuming. For example, if an empty trajectory is given as input and it was not anticipated during implementation, the node might crash due to the unaddressed exceptional input when changes are merged, during scenario testing or while the system is running on an actual vehicle.
6+
7+
## Purpose
8+
9+
The purpose is to provide a utility for implementing tests to ensure that node operates correctly when receiving exceptional input. By utilizing this utility and implementing tests for exceptional input, the purpose is to reduce bugs that are only discovered when actually running the system, by requiring measures for exceptional input before merging PRs.
10+
11+
## Features
12+
13+
### Confirmation of normal operation
14+
15+
For the test target node, confirm that the node operates correctly and publishes the required messages for subsequent nodes. To do this, test_node publish the necessary messages and confirm that the node's output is being published.
16+
17+
### Robustness confirmation for special inputs
18+
19+
After confirming normal operation, ensure that the test target node does not crash when given exceptional input. To do this, provide exceptional input from the test_node and confirm that the node does not crash.
20+
21+
(WIP)
22+
23+
## Usage
24+
25+
```cpp
26+
27+
TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory)
28+
{
29+
rclcpp::init(0, nullptr);
30+
31+
// instantiate test_manager with PlanningInterfaceTestManager type
32+
auto test_manager = std::make_shared<planning_test_utils::PlanningInterfaceTestManager>();
33+
34+
// get package directories for necessary configuration files
35+
const auto planning_test_utils_dir =
36+
ament_index_cpp::get_package_share_directory("planning_test_utils");
37+
const auto target_node_dir =
38+
ament_index_cpp::get_package_share_directory("target_node");
39+
40+
// set arguments to get the config file
41+
node_options.arguments(
42+
{"--ros-args", "--params-file",
43+
planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", "--params-file",
44+
planning_validator_dir + "/config/planning_validator.param.yaml"});
45+
46+
// instantiate the TargetNode with node_options
47+
auto test_target_node = std::make_shared<TargetNode>(node_options);
48+
49+
// publish the necessary topics from test_manager second argument is topic name
50+
test_manager->publishOdometry(test_target_node, "/localization/kinematic_state");
51+
test_manager->publishMaxVelocity(
52+
test_target_node, "motion_velocity_smoother/input/external_velocity_limit_mps");
53+
54+
// set scenario_selector's input topic name(this topic is changed to test node)
55+
test_manager->setTrajectoryInputTopicName("input/parking/trajectory");
56+
57+
// test with normal trajectory
58+
ASSERT_NO_THROW(test_manager->testWithNominalTrajectory(test_target_node));
59+
60+
// make sure target_node is running
61+
EXPECT_GE(test_manager->getReceivedTopicNum(), 1);
62+
63+
// test with trajectory input with empty/one point/overlapping point
64+
ASSERT_NO_THROW(test_manager->testWithAbnormalTrajectory(test_target_node));
65+
66+
// shutdown ROS context
67+
rclcpp::shutdown();
68+
}
69+
```
70+
71+
## Implemented tests
72+
73+
| Node | Test name | exceptional input | output | Exceptional input pattern |
74+
| -------------------------- | ----------------------------------------------------------------------------------------- | ----------------- | -------------- | ------------------------------------------------------------------------------------- |
75+
| planning_validator | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
76+
| motion_velocity_smoother | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
77+
| obstacle_cruise_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
78+
| obstacle_stop_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
79+
| obstacle_velocity_limiter | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
80+
| obstacle_avoidance_planner | NodeTestWithExceptionTrajectory | trajectory | trajectory | Empty, single point, path with duplicate points |
81+
| scenario_selector | NodeTestWithExceptionTrajectoryLaneDrivingMode NodeTestWithExceptionTrajectoryParkingMode | trajectory | scenario | Empty, single point, path with duplicate points for scenarios:LANEDRIVING and PARKING |
82+
| freespace_planner | NodeTestWithExceptionRoute | route | trajectory | Empty route |
83+
| behavior_path_planner | NodeTestWithExceptionRoute NodeTestWithOffTrackEgoPose | route | route odometry | Empty route Off-lane ego-position |
84+
| behavior_velocity_planner | NodeTestWithExceptionPathWithLaneID | path_with_lane_id | path | Empty path |
85+
86+
## Important Notes
87+
88+
During test execution, when launching a node, parameters are loaded from the parameter file within each package. Therefore, when adding parameters, it is necessary to add the required parameters to the parameter file in the target node package. This is to prevent the node from being unable to launch if there are missing parameters when retrieving them from the parameter file during node launch.
89+
90+
## Future extensions / Unimplemented parts
91+
92+
(WIP)

planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager.hpp planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_HPP_
16-
#define PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_HPP_
15+
#ifndef AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_
16+
#define AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_
1717

1818
// since ASSERT_NO_THROW in gtest masks the exception message, redefine it.
1919
#define ASSERT_NO_THROW_WITH_ERROR_MSG(statement) \
@@ -266,4 +266,4 @@ class PlanningInterfaceTestManager
266266

267267
} // namespace planning_test_utils
268268

269-
#endif // PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_HPP_
269+
#endif // AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>autoware_planning_test_manager</name>
5+
<version>0.1.0</version>
6+
<description>ROS 2 node for testing interface of the nodes in planning module</description>
7+
<maintainer email="kyoichi.sugahara@tier4.jp">Kyoichi Sugahara</maintainer>
8+
<maintainer email="takamasa.horibe@tier4.jp">Takamasa Horibe</maintainer>
9+
<license>Apache License 2.0</license>
10+
11+
<author email="kyoichi.sugahara@tier4.jp">Kyoichi Sugahara</author>
12+
13+
<buildtool_depend>ament_cmake_auto</buildtool_depend>
14+
<buildtool_depend>autoware_cmake</buildtool_depend>
15+
16+
<depend>autoware_auto_control_msgs</depend>
17+
<depend>autoware_auto_mapping_msgs</depend>
18+
<depend>autoware_auto_planning_msgs</depend>
19+
<depend>autoware_auto_vehicle_msgs</depend>
20+
<depend>autoware_perception_msgs</depend>
21+
<depend>autoware_planning_msgs</depend>
22+
<depend>component_interface_specs</depend>
23+
<depend>component_interface_utils</depend>
24+
<depend>lanelet2_extension</depend>
25+
<depend>lanelet2_io</depend>
26+
<depend>motion_utils</depend>
27+
<depend>nav_msgs</depend>
28+
<depend>planning_test_utils</depend>
29+
<depend>rclcpp</depend>
30+
<depend>route_handler</depend>
31+
<depend>tf2_msgs</depend>
32+
<depend>tf2_ros</depend>
33+
<depend>tier4_api_msgs</depend>
34+
<depend>tier4_autoware_utils</depend>
35+
<depend>tier4_planning_msgs</depend>
36+
<depend>tier4_v2x_msgs</depend>
37+
<depend>unique_identifier_msgs</depend>
38+
<depend>yaml_cpp_vendor</depend>
39+
40+
<test_depend>ament_cmake_ros</test_depend>
41+
<test_depend>ament_lint_auto</test_depend>
42+
<test_depend>autoware_lint_common</test_depend>
43+
44+
<export>
45+
<build_type>ament_cmake</build_type>
46+
</export>
47+
</package>

planning/planning_test_utils/src/planning_interface_test_manager.cpp planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,8 @@
1414

1515
#include "motion_utils/trajectory/conversion.hpp"
1616

17-
#include <planning_test_utils/planning_interface_test_manager.hpp>
18-
#include <planning_test_utils/planning_interface_test_manager_utils.hpp>
17+
#include <autoware_planning_test_manager/autoware_planning_test_manager.hpp>
18+
#include <planning_test_utils/planning_test_utils.hpp>
1919

2020
namespace planning_test_utils
2121
{

planning/static_centerline_generator/CMakeLists.txt planning/autoware_static_centerline_generator/CMakeLists.txt

+8-4
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
cmake_minimum_required(VERSION 3.14)
2-
project(static_centerline_generator)
2+
project(autoware_static_centerline_generator)
33

44
find_package(autoware_cmake REQUIRED)
55

@@ -9,7 +9,7 @@ find_package(rosidl_default_generators REQUIRED)
99
find_package(std_msgs REQUIRED)
1010

1111
rosidl_generate_interfaces(
12-
static_centerline_generator
12+
autoware_static_centerline_generator
1313
"srv/LoadMap.srv"
1414
"srv/PlanRoute.srv"
1515
"srv/PlanPath.srv"
@@ -29,10 +29,10 @@ ament_auto_add_executable(main
2929

3030
if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0)
3131
rosidl_target_interfaces(main
32-
static_centerline_generator "rosidl_typesupport_cpp")
32+
autoware_static_centerline_generator "rosidl_typesupport_cpp")
3333
else()
3434
rosidl_get_typesupport_target(
35-
cpp_typesupport_target static_centerline_generator "rosidl_typesupport_cpp")
35+
cpp_typesupport_target autoware_static_centerline_generator "rosidl_typesupport_cpp")
3636
target_link_libraries(main "${cpp_typesupport_target}")
3737
endif()
3838

@@ -43,6 +43,10 @@ ament_auto_package(
4343
rviz
4444
)
4545

46+
target_include_directories(main PRIVATE
47+
${CMAKE_CURRENT_SOURCE_DIR}/src
48+
)
49+
4650
if(BUILD_TESTING)
4751
add_launch_test(
4852
test/test_static_centerline_generator.test.py

planning/static_centerline_generator/README.md planning/autoware_static_centerline_generator/README.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ We can run
3434
with the following command by designating `<vehicle_model>`
3535

3636
```sh
37-
ros2 launch static_centerline_generator run_planning_server.launch.xml vehicle_model:=<vehicle-model>
37+
ros2 launch autoware_static_centerline_generator run_planning_server.launch.xml vehicle_model:=<vehicle-model>
3838
```
3939

4040
FYI, port ID of the http server is 4010 by default.
@@ -50,7 +50,7 @@ The optimized centerline can be generated from the command line interface by des
5050
- `<vehicle-model>`
5151

5252
```sh
53-
ros2 launch static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:=<input-osm-path> lanelet2_output_file_path:=<output-osm-path> start_lanelet_id:=<start-lane-id> end_lanelet_id:=<end-lane-id> vehicle_model:=<vehicle-model>
53+
ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:=<input-osm-path> lanelet2_output_file_path:=<output-osm-path> start_lanelet_id:=<start-lane-id> end_lanelet_id:=<end-lane-id> vehicle_model:=<vehicle-model>
5454
```
5555

5656
The default output map path containing the optimized centerline locates `/tmp/lanelet2_map.osm`.

planning/static_centerline_generator/launch/run_planning_server.launch.xml planning/autoware_static_centerline_generator/launch/run_planning_server.launch.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -2,11 +2,11 @@
22
<!-- mandatory arguments for planning-->
33
<arg name="vehicle_model"/>
44

5-
<include file="$(find-pkg-share static_centerline_generator)/launch/static_centerline_generator.launch.xml">
5+
<include file="$(find-pkg-share autoware_static_centerline_generator)/launch/static_centerline_generator.launch.xml">
66
<arg name="vehicle_model" value="$(var vehicle_model)"/>
77
<arg name="run_background" value="true"/>
88
</include>
99

1010
<!-- local server to connect path optimizer and cloud software -->
11-
<node pkg="static_centerline_generator" exec="app.py" name="static_centerline_generator_http_server" output="screen"/>
11+
<node pkg="autoware_static_centerline_generator" exec="app.py" name="static_centerline_generator_http_server" output="screen"/>
1212
</launch>

planning/static_centerline_generator/launch/static_centerline_generator.launch.xml planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml

+3-3
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@
5555
</node>
5656

5757
<!-- optimize path -->
58-
<node pkg="static_centerline_generator" exec="main" name="static_centerline_generator">
58+
<node pkg="autoware_static_centerline_generator" exec="main" name="static_centerline_generator">
5959
<remap from="lanelet2_map_topic" to="$(var lanelet2_map_topic)"/>
6060
<remap from="input_centerline" to="~/input_centerline"/>
6161
<remap from="output_whole_centerline" to="~/output_whole_centerline"/>
@@ -79,11 +79,11 @@
7979
<param from="$(var obstacle_avoidance_planner_param)"/>
8080
<param from="$(var mission_planner_param)"/>
8181
<!-- node param -->
82-
<param from="$(find-pkg-share static_centerline_generator)/config/static_centerline_generator.param.yaml"/>
82+
<param from="$(find-pkg-share autoware_static_centerline_generator)/config/static_centerline_generator.param.yaml"/>
8383
<param name="centerline_source" value="$(var centerline_source)"/>
8484
<param name="bag_filename" value="$(var bag_filename)"/>
8585
</node>
8686

8787
<!-- rviz -->
88-
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(find-pkg-share static_centerline_generator)/rviz/static_centerline_generator.rviz" if="$(var rviz)"/>
88+
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(find-pkg-share autoware_static_centerline_generator)/rviz/static_centerline_generator.param" if="$(var rviz)"/>
8989
</launch>

0 commit comments

Comments
 (0)