From 9560d573cec741b829281029dc327d05cfac2e2b Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 14 Aug 2023 14:47:47 +0900 Subject: [PATCH 1/6] feat(lane_departure_checker): add maintainer (#4611) add maintainer Signed-off-by: kyoichi-sugahara --- control/lane_departure_checker/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/control/lane_departure_checker/package.xml b/control/lane_departure_checker/package.xml index d4e845ec97d82..1059e86cadc6d 100644 --- a/control/lane_departure_checker/package.xml +++ b/control/lane_departure_checker/package.xml @@ -5,6 +5,7 @@ 0.1.0 The lane_departure_checker package Kyoichi Sugahara + Makoto Kurihara Apache License 2.0 ament_cmake_auto From e8dd2255f3a07aa4cd21d4596d22a7145ec1a9ef Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Mon, 14 Aug 2023 17:48:50 +0900 Subject: [PATCH 2/6] fix(behavior_path_planner): change skip updataData() process condition (#4573) change skip condition Signed-off-by: kyoichi-sugahara --- .../src/scene_module/side_shift/side_shift_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp index 8e169309dfb00..4e9680cee4d59 100644 --- a/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/side_shift/side_shift_module.cpp @@ -185,7 +185,7 @@ void SideShiftModule::updateData() } } - if (current_state_ != ModuleStatus::RUNNING) { + if (current_state_ != ModuleStatus::RUNNING && current_state_ != ModuleStatus::IDLE) { return; } From bd7e95f00d65ae1023dc06dc82455c121b1e879f Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Mon, 14 Aug 2023 19:18:33 +0900 Subject: [PATCH 3/6] feat(map_based_prediction): plan paths of objects outside the lanelets. (#4618) * add publisher of calculation time Signed-off-by: Takayuki Murooka * plan path of objects outside the lane Signed-off-by: Takayuki Murooka * minor change Signed-off-by: Takayuki Murooka * fix CI Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../map_based_prediction_node.hpp | 7 ++- perception/map_based_prediction/package.xml | 1 + .../src/map_based_prediction_node.cpp | 62 +++++++++++++------ 3 files changed, 49 insertions(+), 21 deletions(-) diff --git a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp index 6a0bb29e9fb2d..5903706123169 100644 --- a/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp +++ b/perception/map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -31,6 +32,7 @@ #include #include #include +#include #include #include @@ -106,6 +108,7 @@ using autoware_auto_perception_msgs::msg::TrackedObject; using autoware_auto_perception_msgs::msg::TrackedObjectKinematics; using autoware_auto_perception_msgs::msg::TrackedObjects; using tier4_autoware_utils::StopWatch; +using tier4_debug_msgs::msg::StringStamped; class MapBasedPredictionNode : public rclcpp::Node { @@ -116,6 +119,7 @@ class MapBasedPredictionNode : public rclcpp::Node // ROS Publisher and Subscriber rclcpp::Publisher::SharedPtr pub_objects_; rclcpp::Publisher::SharedPtr pub_debug_markers_; + rclcpp::Publisher::SharedPtr pub_calculation_time_; rclcpp::Subscription::SharedPtr sub_objects_; rclcpp::Subscription::SharedPtr sub_map_; @@ -179,8 +183,7 @@ class MapBasedPredictionNode : public rclcpp::Node LaneletsData getCurrentLanelets(const TrackedObject & object); bool checkCloseLaneletCondition( - const std::pair & lanelet, const TrackedObject & object, - const lanelet::BasicPoint2d & search_point); + const std::pair & lanelet, const TrackedObject & object); float calculateLocalLikelihood( const lanelet::Lanelet & current_lanelet, const TrackedObject & object) const; void updateObjectData(TrackedObject & object); diff --git a/perception/map_based_prediction/package.xml b/perception/map_based_prediction/package.xml index 33abfe814c498..0765490502ec4 100644 --- a/perception/map_based_prediction/package.xml +++ b/perception/map_based_prediction/package.xml @@ -23,6 +23,7 @@ tf2_geometry_msgs tf2_ros tier4_autoware_utils + tier4_debug_msgs unique_identifier_msgs visualization_msgs diff --git a/perception/map_based_prediction/src/map_based_prediction_node.cpp b/perception/map_based_prediction/src/map_based_prediction_node.cpp index 9292476e80c8e..66a15f28bdd1b 100644 --- a/perception/map_based_prediction/src/map_based_prediction_node.cpp +++ b/perception/map_based_prediction/src/map_based_prediction_node.cpp @@ -40,6 +40,8 @@ namespace map_based_prediction { +namespace +{ /** * @brief First order Low pass filtering * @@ -586,6 +588,15 @@ ObjectClassification::_label_type changeLabelForPrediction( } } +StringStamped createStringStamped(const rclcpp::Time & now, const double data) +{ + StringStamped msg; + msg.stamp = now; + msg.data = std::to_string(data); + return msg; +} +} // namespace + MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options) : Node("map_based_prediction", node_options), debug_accumulated_time_(0.0) { @@ -649,6 +660,7 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_ pub_objects_ = this->create_publisher("objects", rclcpp::QoS{1}); pub_debug_markers_ = this->create_publisher("maneuver", rclcpp::QoS{1}); + pub_calculation_time_ = create_publisher("~/debug/calculation_time", 1); } PredictedObjectKinematics MapBasedPredictionNode::convertToPredictedKinematics( @@ -691,6 +703,7 @@ void MapBasedPredictionNode::mapCallback(const HADMapBin::ConstSharedPtr msg) void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPtr in_objects) { + stop_watch_.tic(); // Guard for map pointer and frame transformation if (!lanelet_map_ptr_) { return; @@ -869,6 +882,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt // Publish Results pub_objects_->publish(output); pub_debug_markers_->publish(debug_markers); + const auto calculation_time_msg = createStringStamped(now(), stop_watch_.toc()); + pub_calculation_time_->publish(calculation_time_msg); } PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser( @@ -1076,39 +1091,48 @@ LaneletsData MapBasedPredictionNode::getCurrentLanelets(const TrackedObject & ob return {}; } - LaneletsData closest_lanelets; + LaneletsData object_lanelets; + std::optional> closest_lanelet{std::nullopt}; for (const auto & lanelet : surrounding_lanelets) { // Check if the close lanelets meet the necessary condition for start lanelets and - // Check if similar lanelet is inside the closest lanelet - if ( - !checkCloseLaneletCondition(lanelet, object, search_point) || - isDuplicated(lanelet, closest_lanelets)) { + // Check if similar lanelet is inside the object lanelet + if (!checkCloseLaneletCondition(lanelet, object) || isDuplicated(lanelet, object_lanelets)) { continue; } - LaneletData closest_lanelet; - closest_lanelet.lanelet = lanelet.second; - closest_lanelet.probability = calculateLocalLikelihood(lanelet.second, object); - closest_lanelets.push_back(closest_lanelet); + // Memorize closest lanelet + // NOTE: The object may be outside the lanelet. + if (!closest_lanelet || lanelet.first < closest_lanelet->first) { + closest_lanelet = lanelet; + } + + // Check if the obstacle is inside of this lanelet + constexpr double epsilon = 1e-3; + if (lanelet.first < epsilon) { + const auto object_lanelet = + LaneletData{lanelet.second, calculateLocalLikelihood(lanelet.second, object)}; + object_lanelets.push_back(object_lanelet); + } } - return closest_lanelets; + if (!object_lanelets.empty()) { + return object_lanelets; + } + if (closest_lanelet) { + return LaneletsData{LaneletData{ + closest_lanelet->second, calculateLocalLikelihood(closest_lanelet->second, object)}}; + } + return LaneletsData{}; } bool MapBasedPredictionNode::checkCloseLaneletCondition( - const std::pair & lanelet, const TrackedObject & object, - const lanelet::BasicPoint2d & search_point) + const std::pair & lanelet, const TrackedObject & object) { // Step1. If we only have one point in the centerline, we will ignore the lanelet if (lanelet.second.centerline().size() <= 1) { return false; } - // Step2. Check if the obstacle is inside of this lanelet - if (!lanelet::geometry::inside(lanelet.second, search_point)) { - return false; - } - // If the object is in the objects history, we check if the target lanelet is // inside the current lanelets id or following lanelets const std::string object_id = tier4_autoware_utils::toHexString(object.object_id); @@ -1124,7 +1148,7 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( } } - // Step3. Calculate the angle difference between the lane angle and obstacle angle + // Step2. Calculate the angle difference between the lane angle and obstacle angle const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); const double lane_yaw = lanelet::utils::getLaneletAngle( lanelet.second, object.kinematics.pose_with_covariance.pose.position); @@ -1132,7 +1156,7 @@ bool MapBasedPredictionNode::checkCloseLaneletCondition( const double normalized_delta_yaw = tier4_autoware_utils::normalizeRadian(delta_yaw); const double abs_norm_delta = std::fabs(normalized_delta_yaw); - // Step4. Check if the closest lanelet is valid, and add all + // Step3. Check if the closest lanelet is valid, and add all // of the lanelets that are below max_dist and max_delta_yaw const double object_vel = object.kinematics.twist_with_covariance.twist.linear.x; const bool is_yaw_reversed = From 0ae23d4474bc465dbb97f26b2d7cd73f6e8c6001 Mon Sep 17 00:00:00 2001 From: Yutaka Shimizu <43805014+purewater0901@users.noreply.github.com> Date: Mon, 14 Aug 2023 22:06:54 +0900 Subject: [PATCH 4/6] feat(lane_change): ignore front parked objects (#4591) Signed-off-by: yutaka Co-authored-by: Fumiya Watanabe --- .../scene_module/lane_change/normal.hpp | 4 + .../utils/lane_change/utils.hpp | 6 - .../src/scene_module/lane_change/normal.cpp | 115 +++++++++++++++++- .../src/utils/lane_change/utils.cpp | 82 ------------- 4 files changed, 116 insertions(+), 91 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp index a6a6d12a5642b..948a2cc4fbb2a 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/scene_module/lane_change/normal.hpp @@ -143,6 +143,10 @@ class NormalLaneChange : public LaneChangeBase const double front_decel, const double rear_decel, std::unordered_map & debug_data) const; + LaneChangeTargetObjectIndices filterObject( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, + const lanelet::ConstLanelets & target_backward_lanes) const; + rclcpp::Logger logger_ = rclcpp::get_logger("lane_change").get_child(getModuleTypeStr()); }; } // namespace behavior_path_planner diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp index dc8298720239c..266c52918c567 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/lane_change/utils.hpp @@ -186,12 +186,6 @@ boost::optional getLeadingStaticObjectIdx( std::optional createPolygon( const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist); -LaneChangeTargetObjectIndices filterObject( - const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelets & target_backward_lanes, - const Pose & current_pose, const RouteHandler & route_handler, - const LaneChangeParameters & lane_change_parameters); - ExtendedPredictedObject transform( const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, const LaneChangeParameters & lane_change_parameters); diff --git a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp index 2f7c39f94604e..29cefe110d9e4 100644 --- a/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp +++ b/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp @@ -604,9 +604,7 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects( route_handler, target_lanes, current_pose, backward_length); // filter objects to get target object index - const auto target_obj_index = utils::lane_change::filterObject( - objects, current_lanes, target_lanes, target_backward_lanes, current_pose, route_handler, - *lane_change_parameters_); + const auto target_obj_index = filterObject(current_lanes, target_lanes, target_backward_lanes); LaneChangeTargetObjects target_objects; target_objects.current_lane.reserve(target_obj_index.current_lane.size()); @@ -637,6 +635,117 @@ LaneChangeTargetObjects NormalLaneChange::getTargetObjects( return target_objects; } +LaneChangeTargetObjectIndices NormalLaneChange::filterObject( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, + const lanelet::ConstLanelets & target_backward_lanes) const +{ + const auto current_pose = getEgoPose(); + const auto current_vel = getEgoVelocity(); + const auto & route_handler = *getRouteHandler(); + const auto & common_parameters = planner_data_->parameters; + const auto & objects = *planner_data_->dynamic_object; + const auto & object_check_min_road_shoulder_width = + lane_change_parameters_->object_check_min_road_shoulder_width; + const auto & object_shiftable_ratio_threshold = + lane_change_parameters_->object_shiftable_ratio_threshold; + + // Guard + if (objects.objects.empty()) { + return {}; + } + + // Get path + const auto path = + route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + const auto target_path = + route_handler.getCenterLinePath(target_lanes, 0.0, std::numeric_limits::max()); + + const auto current_polygon = + utils::lane_change::createPolygon(current_lanes, 0.0, std::numeric_limits::max()); + const auto target_polygon = + utils::lane_change::createPolygon(target_lanes, 0.0, std::numeric_limits::max()); + const auto target_backward_polygon = utils::lane_change::createPolygon( + target_backward_lanes, 0.0, std::numeric_limits::max()); + + // minimum distance to lane changing start point + const double t_prepare = common_parameters.lane_change_prepare_duration; + const double a_min = lane_change_parameters_->min_longitudinal_acc; + const double min_dist_to_lane_changing_start = std::max( + current_vel * t_prepare, current_vel * t_prepare + 0.5 * a_min * t_prepare * t_prepare); + + LaneChangeTargetObjectIndices filtered_obj_indices; + for (size_t i = 0; i < objects.objects.size(); ++i) { + const auto & object = objects.objects.at(i); + const auto & obj_velocity = object.kinematics.initial_twist_with_covariance.twist.linear.x; + const auto extended_object = + utils::lane_change::transform(object, common_parameters, *lane_change_parameters_); + + // ignore specific object types + if (!utils::lane_change::isTargetObjectType(object, *lane_change_parameters_)) { + continue; + } + + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); + + // calc distance from the current ego position + double max_dist_ego_to_obj = std::numeric_limits::lowest(); + double min_dist_ego_to_obj = std::numeric_limits::max(); + for (const auto & polygon_p : obj_polygon.outer()) { + const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const double dist_ego_to_obj = + motion_utils::calcSignedArcLength(path.points, current_pose.position, obj_p); + max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); + min_dist_ego_to_obj = std::min(dist_ego_to_obj, min_dist_ego_to_obj); + } + + // ignore static object that are behind the ego vehicle + if (obj_velocity < 1.0 && max_dist_ego_to_obj < 0.0) { + continue; + } + + // check if the object intersects with target lanes + if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) { + // ignore static parked object that are in front of the ego vehicle in target lanes + bool is_parked_object = utils::lane_change::isParkedObject( + target_path, route_handler, extended_object, object_check_min_road_shoulder_width, + object_shiftable_ratio_threshold); + if (is_parked_object && min_dist_ego_to_obj > min_dist_to_lane_changing_start) { + continue; + } + + filtered_obj_indices.target_lane.push_back(i); + continue; + } + + // check if the object intersects with target backward lanes + if ( + target_backward_polygon && + boost::geometry::intersects(target_backward_polygon.value(), obj_polygon)) { + filtered_obj_indices.target_lane.push_back(i); + continue; + } + + // check if the object intersects with current lanes + if ( + current_polygon && boost::geometry::intersects(current_polygon.value(), obj_polygon) && + max_dist_ego_to_obj >= 0.0) { + // check only the objects that are in front of the ego vehicle + filtered_obj_indices.current_lane.push_back(i); + continue; + } + + // ignore all objects that are behind the ego vehicle and not on the current and target + // lanes + if (max_dist_ego_to_obj < 0.0) { + continue; + } + + filtered_obj_indices.other_lane.push_back(i); + } + + return filtered_obj_indices; +} + PathWithLaneId NormalLaneChange::getTargetSegment( const lanelet::ConstLanelets & target_lanes, const Pose & lane_changing_start_pose, const double target_lane_length, const double lane_changing_length, diff --git a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp index b3688fdb1310e..c22c07c0e80c5 100644 --- a/planning/behavior_path_planner/src/utils/lane_change/utils.cpp +++ b/planning/behavior_path_planner/src/utils/lane_change/utils.cpp @@ -1078,88 +1078,6 @@ std::optional createPolygon( return lanelet::utils::to2D(polygon_3d).basicPolygon(); } -LaneChangeTargetObjectIndices filterObject( - const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, const lanelet::ConstLanelets & target_backward_lanes, - const Pose & current_pose, const RouteHandler & route_handler, - const LaneChangeParameters & lane_change_parameter) -{ - // Guard - if (objects.objects.empty()) { - return {}; - } - - // Get path - const auto path = - route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); - - const auto current_polygon = - createPolygon(current_lanes, 0.0, std::numeric_limits::max()); - const auto target_polygon = createPolygon(target_lanes, 0.0, std::numeric_limits::max()); - const auto target_backward_polygon = - createPolygon(target_backward_lanes, 0.0, std::numeric_limits::max()); - - LaneChangeTargetObjectIndices filtered_obj_indices; - for (size_t i = 0; i < objects.objects.size(); ++i) { - const auto & object = objects.objects.at(i); - const auto & obj_velocity = object.kinematics.initial_twist_with_covariance.twist.linear.x; - - // ignore specific object types - if (!isTargetObjectType(object, lane_change_parameter)) { - continue; - } - - const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); - - // calc distance from the current ego position - double max_dist_ego_to_obj = std::numeric_limits::lowest(); - for (const auto & polygon_p : obj_polygon.outer()) { - const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); - const double dist_ego_to_obj = - motion_utils::calcSignedArcLength(path.points, current_pose.position, obj_p); - max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); - } - - // ignore static object that are behind the ego vehicle - if (obj_velocity < 1.0 && max_dist_ego_to_obj < 0.0) { - continue; - } - - // check if the object intersects with target lanes - if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) { - filtered_obj_indices.target_lane.push_back(i); - continue; - } - - // check if the object intersects with target backward lanes - if ( - target_backward_polygon && - boost::geometry::intersects(target_backward_polygon.value(), obj_polygon)) { - filtered_obj_indices.target_lane.push_back(i); - continue; - } - - // check if the object intersects with current lanes - if ( - current_polygon && boost::geometry::intersects(current_polygon.value(), obj_polygon) && - max_dist_ego_to_obj >= 0.0) { - // check only the objects that are in front of the ego vehicle - filtered_obj_indices.current_lane.push_back(i); - continue; - } - - // ignore all objects that are behind the ego vehicle and not on the current and target - // lanes - if (max_dist_ego_to_obj < 0.0) { - continue; - } - - filtered_obj_indices.other_lane.push_back(i); - } - - return filtered_obj_indices; -} - ExtendedPredictedObject transform( const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, const LaneChangeParameters & lane_change_parameters) From 48d5336778850ff48a37b299438087c50333a28b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Tue, 15 Aug 2023 02:07:41 +0900 Subject: [PATCH 5/6] fix(behavior_path_planner): add guard to combineDrivableLanes (#4626) Signed-off-by: kosuke55 --- planning/behavior_path_planner/src/utils/utils.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/planning/behavior_path_planner/src/utils/utils.cpp b/planning/behavior_path_planner/src/utils/utils.cpp index 47729bab4d11f..8cc94bd6b46fa 100644 --- a/planning/behavior_path_planner/src/utils/utils.cpp +++ b/planning/behavior_path_planner/src/utils/utils.cpp @@ -3247,9 +3247,11 @@ std::vector combineDrivableLanes( } // NOTE: If original_drivable_lanes_vec is shorter than new_drivable_lanes_vec, push back remained // new_drivable_lanes_vec. - updated_drivable_lanes_vec.insert( - updated_drivable_lanes_vec.end(), new_drivable_lanes_vec.begin() + new_drivable_lanes_idx + 1, - new_drivable_lanes_vec.end()); + if (new_drivable_lanes_idx + 1 < new_drivable_lanes_vec.size()) { + updated_drivable_lanes_vec.insert( + updated_drivable_lanes_vec.end(), new_drivable_lanes_vec.begin() + new_drivable_lanes_idx + 1, + new_drivable_lanes_vec.end()); + } return updated_drivable_lanes_vec; } From 90930e5ac033b7e312c10baa0cca29d740f9ebda Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Tue, 15 Aug 2023 09:39:36 +0900 Subject: [PATCH 6/6] docs(traffic_light_multi_camera_fusion): fix broken table display (#4621) * docs(traffic_light_multi_camera_fusion): fix broken table display Signed-off-by: Tomohito Ando * style(pre-commit): autofix --------- Signed-off-by: Tomohito Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../traffic_light_multi_camera_fusion/README.md | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/perception/traffic_light_multi_camera_fusion/README.md b/perception/traffic_light_multi_camera_fusion/README.md index 2f225f1540f63..f7ee294cda147 100644 --- a/perception/traffic_light_multi_camera_fusion/README.md +++ b/perception/traffic_light_multi_camera_fusion/README.md @@ -9,12 +9,13 @@ ## Input topics -For every camera, the following three topics are subscribed: -| Name | Type | | -| ---------------------------------------| -------------------------------------------------------|----------------------------------------------------| -| `~//camera_info` | sensor_msgs::CameraInfo |camera info from traffic_light_map_based_detector | -| `~//rois` | tier4_perception_msgs::TrafficLightRoiArray |detection roi from traffic_light_fine_detector | -| `~//traffic_signals` | tier4_perception_msgs::TrafficLightSignalArray |classification result from traffic_light_classifier | +For every camera, the following three topics are subscribed: + +| Name | Type | Description | +| -------------------------------------- | ---------------------------------------------- | --------------------------------------------------- | +| `~//camera_info` | sensor_msgs::CameraInfo | camera info from traffic_light_map_based_detector | +| `~//rois` | tier4_perception_msgs::TrafficLightRoiArray | detection roi from traffic_light_fine_detector | +| `~//traffic_signals` | tier4_perception_msgs::TrafficLightSignalArray | classification result from traffic_light_classifier | You don't need to configure these topics manually. Just provide the `camera_namespaces` parameter and the node will automatically extract the `` and create the subscribers.