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

feat: backwardcpp test #6796

Closed
wants to merge 3 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
5 changes: 1 addition & 4 deletions perception/map_based_prediction/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,7 @@ find_package(autoware_cmake REQUIRED)
autoware_package()

find_package(Eigen3 REQUIRED)

find_package(glog REQUIRED)
find_package(backward_ros REQUIRED)

include_directories(
SYSTEM
Expand All @@ -19,8 +18,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
2 changes: 1 addition & 1 deletion perception/map_based_prediction/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@

<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>backward_ros</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
21 changes: 17 additions & 4 deletions perception/map_based_prediction/src/map_based_prediction_node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1771 to 1783, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 6.52 to 6.54, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -42,8 +42,6 @@
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#include <glog/logging.h>

#include <algorithm>
#include <chrono>
#include <cmath>
Expand Down Expand Up @@ -714,110 +712,125 @@

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_ =
declare_parameter<double>("lateral_control_time_horizon"); // [s] for lateral control point
prediction_sampling_time_interval_ = declare_parameter<double>("prediction_sampling_delta_time");
min_velocity_for_map_based_prediction_ =
declare_parameter<double>("min_velocity_for_map_based_prediction");
min_crosswalk_user_velocity_ = declare_parameter<double>("min_crosswalk_user_velocity");
max_crosswalk_user_delta_yaw_threshold_for_lanelet_ =
declare_parameter<double>("max_crosswalk_user_delta_yaw_threshold_for_lanelet");
dist_threshold_for_searching_lanelet_ =
declare_parameter<double>("dist_threshold_for_searching_lanelet");
delta_yaw_threshold_for_searching_lanelet_ =
declare_parameter<double>("delta_yaw_threshold_for_searching_lanelet");
sigma_lateral_offset_ = declare_parameter<double>("sigma_lateral_offset");
sigma_yaw_angle_deg_ = declare_parameter<double>("sigma_yaw_angle_deg");
object_buffer_time_length_ = declare_parameter<double>("object_buffer_time_length");
history_time_length_ = declare_parameter<double>("history_time_length");

check_lateral_acceleration_constraints_ =
declare_parameter<bool>("check_lateral_acceleration_constraints");
max_lateral_accel_ = declare_parameter<double>("max_lateral_accel");
min_acceleration_before_curve_ = declare_parameter<double>("min_acceleration_before_curve");

{ // lane change detection
lane_change_detection_method_ = declare_parameter<std::string>("lane_change_detection.method");

// lane change detection by time_to_change_lane
dist_threshold_to_bound_ = declare_parameter<double>(
"lane_change_detection.time_to_change_lane.dist_threshold_for_lane_change_detection"); // 1m
time_threshold_to_bound_ = declare_parameter<double>(
"lane_change_detection.time_to_change_lane.time_threshold_for_lane_change_detection");
cutoff_freq_of_velocity_lpf_ = declare_parameter<double>(
"lane_change_detection.time_to_change_lane.cutoff_freq_of_velocity_for_lane_change_"
"detection");

// lane change detection by lat_diff_distance
dist_ratio_threshold_to_left_bound_ = declare_parameter<double>(
"lane_change_detection.lat_diff_distance.dist_ratio_threshold_to_left_bound");
dist_ratio_threshold_to_right_bound_ = declare_parameter<double>(
"lane_change_detection.lat_diff_distance.dist_ratio_threshold_to_right_bound");
diff_dist_threshold_to_left_bound_ = declare_parameter<double>(
"lane_change_detection.lat_diff_distance.diff_dist_threshold_to_left_bound");
diff_dist_threshold_to_right_bound_ = declare_parameter<double>(
"lane_change_detection.lat_diff_distance.diff_dist_threshold_to_right_bound");

num_continuous_state_transition_ =
declare_parameter<int>("lane_change_detection.num_continuous_state_transition");

consider_only_routable_neighbours_ =
declare_parameter<bool>("lane_change_detection.consider_only_routable_neighbours");
}
reference_path_resolution_ = declare_parameter<double>("reference_path_resolution");
/* prediction path will disabled when the estimated path length exceeds lanelet length. This
* parameter control the estimated path length = vx * th * (rate) */
prediction_time_horizon_rate_for_validate_lane_length_ =
declare_parameter<double>("prediction_time_horizon_rate_for_validate_shoulder_lane_length");

use_vehicle_acceleration_ = declare_parameter<bool>("use_vehicle_acceleration");
speed_limit_multiplier_ = declare_parameter<double>("speed_limit_multiplier");
acceleration_exponential_half_life_ =
declare_parameter<double>("acceleration_exponential_half_life");

use_crosswalk_signal_ = declare_parameter<bool>("crosswalk_with_signal.use_crosswalk_signal");
threshold_velocity_assumed_as_stopping_ =
declare_parameter<double>("crosswalk_with_signal.threshold_velocity_assumed_as_stopping");
distance_set_for_no_intention_to_walk_ = declare_parameter<std::vector<double>>(
"crosswalk_with_signal.distance_set_for_no_intention_to_walk");
timeout_set_for_no_intention_to_walk_ = declare_parameter<std::vector<double>>(
"crosswalk_with_signal.timeout_set_for_no_intention_to_walk");

path_generator_ = std::make_shared<PathGenerator>(
prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_,
min_crosswalk_user_velocity_);

path_generator_->setUseVehicleAcceleration(use_vehicle_acceleration_);
path_generator_->setAccelerationHalfLife(acceleration_exponential_half_life_);

sub_objects_ = this->create_subscription<TrackedObjects>(
"~/input/objects", 1,
std::bind(&MapBasedPredictionNode::objectsCallback, this, std::placeholders::_1));
sub_map_ = this->create_subscription<HADMapBin>(
"/vector_map", rclcpp::QoS{1}.transient_local(),
std::bind(&MapBasedPredictionNode::mapCallback, this, std::placeholders::_1));
sub_traffic_signals_ = this->create_subscription<TrafficSignalArray>(
"/traffic_signals", 1,
std::bind(&MapBasedPredictionNode::trafficSignalsCallback, this, std::placeholders::_1));

pub_objects_ = this->create_publisher<PredictedObjects>("~/output/objects", rclcpp::QoS{1});
pub_debug_markers_ =
this->create_publisher<visualization_msgs::msg::MarkerArray>("maneuver", rclcpp::QoS{1});
processing_time_publisher_ =
std::make_unique<tier4_autoware_utils::DebugPublisher>(this, "map_based_prediction");

published_time_publisher_ = std::make_unique<tier4_autoware_utils::PublishedTimePublisher>(this);
set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&MapBasedPredictionNode::onParam, this, std::placeholders::_1));

stop_watch_ptr_ = std::make_unique<tier4_autoware_utils::StopWatch<std::chrono::milliseconds>>();
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");

// crash in 10s
std::thread thread([]() {
const auto you_shall_not_pass = []() {
char * ptr = (char *)42;
int v = *ptr;
return v;
};
// print countdown
for (int i = 10; i > 0; i--) {
std::cout << "Countdown: " << i << std::endl;
std::this_thread::sleep_for(std::chrono::seconds(1));
}
int v = you_shall_not_pass();
std::cout << "v=" << v << std::endl;
});
thread.detach();

Check warning on line 833 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

MapBasedPredictionNode::MapBasedPredictionNode increases from 89 to 101 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
}

rcl_interfaces::msg::SetParametersResult MapBasedPredictionNode::onParam(
Expand Down
Loading