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

[Don't merge] for Robobus from v0.20.1 #1061

Closed
wants to merge 7 commits into from
Closed
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
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<push-ros-namespace namespace="util"/>
<include file="$(find-pkg-share pose_initializer)/launch/pose_initializer.launch.xml">
<arg name="ndt_enabled" value="true"/>
<arg name="gnss_enabled" value="true"/>
<arg name="gnss_enabled" value="false"/>
<arg name="ekf_enabled" value="true"/>
<arg name="yabloc_enabled" value="false"/>
<arg name="stop_check_enabled" value="$(var stop_check_enabled)"/>
Expand All @@ -30,7 +30,7 @@
</group>

<!-- YabLoc Launch (as pose estimator) -->
<group if="$(eval &quot;'$(var pose_source)'=='yabloc'&quot;)">
<!-- <group if="$(eval &quot;'$(var pose_source)'=='yabloc'&quot;)">
<group>
<push-ros-namespace namespace="pose_estimator"/>
<include file="$(find-pkg-share tier4_localization_launch)/launch/pose_twist_estimator/yabloc.launch.xml"/>
Expand All @@ -50,7 +50,7 @@
<include file="$(find-pkg-share automatic_pose_initializer)/launch/automatic_pose_initializer.launch.xml"/>
</group>
</group>
</group>
</group> -->

<!-- Gyro Odometer Launch (as pose estimator) -->
<group if="$(eval &quot;'$(var twist_source)'=='gyro_odom'&quot;)">
Expand All @@ -59,7 +59,7 @@
</group>

<!-- Eagleye Launch (as pose & twist estimator) -->
<group if="$(eval &quot;'$(var pose_source)'=='eagleye' and '$(var twist_source)'=='eagleye'&quot;)">
<!-- <group if="$(eval &quot;'$(var pose_source)'=='eagleye' and '$(var twist_source)'=='eagleye'&quot;)">
<group>
<push-ros-namespace namespace="pose_twist_estimator"/>
<include file="$(find-pkg-share tier4_localization_launch)/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml">
Expand All @@ -84,10 +84,10 @@
<include file="$(find-pkg-share automatic_pose_initializer)/launch/automatic_pose_initializer.launch.xml"/>
</group>
</group>
</group>
</group> -->

<!-- Eagleye Launch (as pose estimator) -->
<group if="$(eval &quot;'$(var pose_source)'=='eagleye' and '$(var twist_source)'!='eagleye'&quot;)">
<!-- <group if="$(eval &quot;'$(var pose_source)'=='eagleye' and '$(var twist_source)'!='eagleye'&quot;)">
<group>
<push-ros-namespace namespace="pose_estimator"/>
<include file="$(find-pkg-share tier4_localization_launch)/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml">
Expand All @@ -111,20 +111,20 @@
<include file="$(find-pkg-share automatic_pose_initializer)/launch/automatic_pose_initializer.launch.xml"/>
</group>
</group>
</group>
</group> -->

<!-- Eagleye Launch (as twist estimator) -->
<group if="$(eval &quot;'$(var pose_source)'!='eagleye' and '$(var twist_source)'=='eagleye'&quot;)">
<!-- <group if="$(eval &quot;'$(var pose_source)'!='eagleye' and '$(var twist_source)'=='eagleye'&quot;)">
<push-ros-namespace namespace="twist_estimator"/>
<include file="$(find-pkg-share tier4_localization_launch)/launch/pose_twist_estimator/eagleye/eagleye_rt.launch.xml">
<arg name="output_twist_with_cov_name" value="/localization/twist_estimator/twist_with_covariance"/>
<arg name="use_eagleye_pose" value="false"/>
<arg name="use_eagleye_twist" value="true"/>
</include>
</group>
</group> -->

<!-- AR Tag Based Localizer (as pose estimator) -->
<group if="$(eval &quot;'$(var pose_source)'=='artag'&quot;)">
<!-- <group if="$(eval &quot;'$(var pose_source)'=='artag'&quot;)">
<group>
<push-ros-namespace namespace="pose_estimator"/>
<include file="$(find-pkg-share tier4_localization_launch)/launch/pose_twist_estimator/ar_tag_based_localizer.launch.xml"/>
Expand All @@ -148,5 +148,5 @@
<arg name="lidar_container_name" value="$(var lidar_container_name)"/>
</include>
</group>
</group>
</group> -->
</launch>
18 changes: 9 additions & 9 deletions launch/tier4_localization_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,8 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>ar_tag_based_localizer</exec_depend>
<!-- <exec_depend>ar_tag_based_localizer</exec_depend> -->
<exec_depend>automatic_pose_initializer</exec_depend>
<exec_depend>eagleye_geo_pose_fusion</exec_depend>
<exec_depend>eagleye_gnss_converter</exec_depend>
<exec_depend>eagleye_rt</exec_depend>
<exec_depend>ekf_localizer</exec_depend>
<exec_depend>geo_pose_projector</exec_depend>
<exec_depend>gyro_odometer</exec_depend>
Expand All @@ -27,11 +24,14 @@
<exec_depend>pose_initializer</exec_depend>
<exec_depend>pose_instability_detector</exec_depend>
<exec_depend>topic_tools</exec_depend>
<exec_depend>yabloc_common</exec_depend>
<exec_depend>yabloc_image_processing</exec_depend>
<exec_depend>yabloc_monitor</exec_depend>
<exec_depend>yabloc_particle_filter</exec_depend>
<exec_depend>yabloc_pose_initializer</exec_depend>
<!-- <exec_depend>eagleye_geo_pose_fusion</exec_depend> -->
<!-- <exec_depend>eagleye_gnss_converter</exec_depend> -->
<!-- <exec_depend>eagleye_rt</exec_depend> -->
<!-- <exec_depend>yabloc_common</exec_depend> -->
<!-- <exec_depend>yabloc_image_processing</exec_depend> -->
<!-- <exec_depend>yabloc_monitor</exec_depend> -->
<!-- <exec_depend>yabloc_particle_filter</exec_depend> -->
<!-- <exec_depend>yabloc_pose_initializer</exec_depend> -->

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,9 @@
<arg name="radar_object_clustering_param_path" default="$(find-pkg-share radar_object_clustering)/config/radar_object_clustering.param.yaml"/>

<!-- Camera-Lidar-Radar fusion based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;camera_lidar_radar_fusion&quot;')">
<!-- Camera-Lidar detectors -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml">
<!-- <group if="$(eval '&quot;$(var mode)&quot;==&quot;camera_lidar_radar_fusion&quot;')"> -->
<!-- Camera-Lidar detectors -->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="image_raw0" value="$(var image_raw0)"/>
<arg name="camera_info0" value="$(var camera_info0)"/>
Expand All @@ -63,14 +63,14 @@
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
<arg name="use_roi_based_cluster" value="$(var use_roi_based_cluster)"/>
<arg name="detection_by_tracker_param_path" value="$(var detection_by_tracker_param_path)"/>
</include>
<!-- Lidar dnn-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
</include> -->
<!-- Lidar dnn-based detectors-->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
</include>
<!-- Radar detector-->
<group>
</include> -->
<!-- Radar detector-->
<!-- <group>
<push-ros-namespace namespace="radar"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/radar_detector.launch.xml">
<arg name="input/radar" value="$(var input/radar)"/>
Expand All @@ -82,9 +82,9 @@
<arg name="radar_lanelet_filtering_range_param" value="$(var radar_lanelet_filtering_range_param)"/>
<arg name="radar_object_clustering_param_path" value="$(var radar_object_clustering_param_path)"/>
</include>
</group>
<!-- Object merger -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/camera_lidar_radar_merger.launch.xml">
</group> -->
<!-- Object merger -->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/camera_lidar_radar_merger.launch.xml">
<arg name="image_raw0" value="$(var image_raw0)"/>
<arg name="camera_info0" value="$(var camera_info0)"/>
<arg name="image_raw1" value="$(var image_raw1)"/>
Expand All @@ -107,12 +107,12 @@
<arg name="use_object_filter" value="$(var use_object_filter)"/>
<arg name="roi_detected_object_fusion_param_path" value="$(var roi_detected_object_fusion_param_path)"/>
</include>
</group>
</group> -->

<!-- Camera-Lidar fusion based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;camera_lidar_fusion&quot;')">
<!-- Camera-Lidar detectors -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml">
<!-- <group if="$(eval '&quot;$(var mode)&quot;==&quot;camera_lidar_fusion&quot;')"> -->
<!-- Camera-Lidar detectors -->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="image_raw0" value="$(var image_raw0)"/>
<arg name="camera_info0" value="$(var camera_info0)"/>
Expand All @@ -138,14 +138,14 @@
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
<arg name="use_roi_based_cluster" value="$(var use_roi_based_cluster)"/>
<arg name="detection_by_tracker_param_path" value="$(var detection_by_tracker_param_path)"/>
</include>
<!-- Lidar dnn-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
</include> -->
<!-- Lidar dnn-based detectors-->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
</include>
<!-- Object merger -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/camera_lidar_merger.launch.xml">
</include> -->
<!-- Object merger -->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/camera_lidar_merger.launch.xml">
<arg name="image_raw0" value="$(var image_raw0)"/>
<arg name="camera_info0" value="$(var camera_info0)"/>
<arg name="image_raw1" value="$(var image_raw1)"/>
Expand All @@ -167,46 +167,46 @@
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
</include>
</group>
</group> -->

<!-- Lidar-Radar fusion based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;lidar_radar_fusion&quot;')">
<!-- Radar detector-->
<group>
<!-- <group if="$(eval '&quot;$(var mode)&quot;==&quot;lidar_radar_fusion&quot;')"> -->
<!-- Radar detector-->
<!-- <group>
<push-ros-namespace namespace="radar"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/radar_detector.launch.xml">
<arg name="input/radar" value="$(var input/radar)"/>
<arg name="output/objects" value="far_objects"/>
<arg name="radar_lanelet_filtering_range_param" value="$(var radar_lanelet_filtering_range_param)"/>
<arg name="radar_object_clustering_param_path" value="$(var radar_object_clustering_param_path)"/>
</include>
</group>
<!-- Lidar dnn-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
</group> -->
<!-- Lidar dnn-based detectors-->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
</include>
<!-- Lidar rule-based detectors-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml">
</include> -->
<!-- Lidar rule-based detectors-->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml">
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>
<!-- Lidar object merger -->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/lidar_merger.launch.xml">
</include> -->
<!-- Lidar object merger -->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/merger/lidar_merger.launch.xml">
<arg name="output/objects" value="lidar/objects"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
<arg name="use_object_filter" value="$(var use_object_filter)"/>
</include>
<!-- Lidar-Radar object merger-->
<include file="$(find-pkg-share radar_fusion_to_detected_object)/launch/radar_object_fusion_to_detected_object.launch.xml">
</include> -->
<!-- Lidar-Radar object merger-->
<!-- <include file="$(find-pkg-share radar_fusion_to_detected_object)/launch/radar_object_fusion_to_detected_object.launch.xml">
<arg name="input/objects" value="lidar/objects"/>
<arg name="input/radars" value="radar/noise_filtered_objects"/>
<arg name="output/objects" value="objects"/>
</include>
</group>
</group> -->

<!-- Lidar based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;lidar&quot;')">
Expand All @@ -231,13 +231,13 @@
</group>

<!-- Radar based detection -->
<group if="$(eval '&quot;$(var mode)&quot;==&quot;radar&quot;')">
<!-- Radar detector-->
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/radar_detector.launch.xml">
<!-- <group if="$(eval '&quot;$(var mode)&quot;==&quot;radar&quot;')"> -->
<!-- Radar detector-->
<!-- <include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/radar_detector.launch.xml">
<arg name="input/radar" value="$(var input/radar)"/>
<arg name="output/objects" value="objects"/>
<arg name="radar_lanelet_filtering_range_param" value="$(var radar_lanelet_filtering_range_param)"/>
<arg name="radar_object_clustering_param_path" value="$(var radar_object_clustering_param_path)"/>
</include>
</group>
</group> -->
</launch>
4 changes: 2 additions & 2 deletions launch/tier4_perception_launch/launch/perception.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -231,7 +231,7 @@
</group>

<!-- Traffic light module -->
<group if="$(var use_traffic_light_recognition)">
<!-- <group if="$(var use_traffic_light_recognition)">
<push-ros-namespace namespace="traffic_light_recognition"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/traffic_light_recognition/traffic_light.launch.xml">
<arg name="enable_fine_detection" value="$(var traffic_light_recognition/enable_fine_detection)"/>
Expand All @@ -244,6 +244,6 @@
<arg name="car_traffic_light_classifier_model_name" value="$(var car_traffic_light_classifier_model_name)"/>
<arg name="pedestrian_traffic_light_classifier_model_name" value="$(var pedestrian_traffic_light_classifier_model_name)"/>
</include>
</group>
</group> -->
</group>
</launch>
4 changes: 0 additions & 4 deletions perception/map_based_prediction/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,6 @@ autoware_package()

find_package(Eigen3 REQUIRED)

find_package(glog REQUIRED)

include_directories(
SYSTEM
${EIGEN3_INCLUDE_DIR}
Expand All @@ -19,8 +17,6 @@ ament_auto_add_library(map_based_prediction_node SHARED
src/debug.cpp
)

target_link_libraries(map_based_prediction_node glog::glog)

rclcpp_components_register_node(map_based_prediction_node
PLUGIN "map_based_prediction::MapBasedPredictionNode"
EXECUTABLE map_based_prediction
Expand Down
1 change: 0 additions & 1 deletion perception/map_based_prediction/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
<depend>autoware_auto_perception_msgs</depend>
<depend>interpolation</depend>
<depend>lanelet2_extension</depend>
<depend>libgoogle-glog-dev</depend>
<depend>motion_utils</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,6 @@
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#include <glog/logging.h>

#include <algorithm>
#include <chrono>
#include <cmath>
Expand Down Expand Up @@ -728,8 +726,6 @@ void replaceObjectYawWithLaneletsYaw(
MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options)
: Node("map_based_prediction", node_options), debug_accumulated_time_(0.0)
{
google::InitGoogleLogging("map_based_prediction_node");
google::InstallFailureSignalHandler();
enable_delay_compensation_ = declare_parameter<bool>("enable_delay_compensation");
prediction_time_horizon_ = declare_parameter<double>("prediction_time_horizon");
lateral_control_time_horizon_ =
Expand Down
Loading