Skip to content

Commit

Permalink
Merge branch 'main' into feature/redesign_concatenate_and_time_sync_node
Browse files Browse the repository at this point in the history
  • Loading branch information
vividf authored Oct 4, 2024
2 parents 55e0d24 + 9e32e92 commit 0611bb9
Show file tree
Hide file tree
Showing 478 changed files with 8,907 additions and 7,728 deletions.
1 change: 0 additions & 1 deletion .cppcheck_suppressions
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
checkersReport
missingInclude
missingIncludeSystem
unknownMacro
unmatchedSuppression
unusedFunction
useInitializationList
Expand Down
2 changes: 1 addition & 1 deletion .cspell.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,5 +4,5 @@
"planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/scripts/**"
],
"ignoreRegExpList": [],
"words": ["dltype", "tvmgen", "fromarray"]
"words": ["dltype", "tvmgen", "fromarray", "soblin"]
}
10 changes: 4 additions & 6 deletions .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/** khalil@leodr
common/autoware_path_distance_calculator/** [email protected]
common/autoware_perception_rviz_plugin/** [email protected] [email protected] [email protected] [email protected] [email protected]
common/autoware_point_types/** [email protected] [email protected]
common/autoware_signal_processing/** [email protected] [email protected] [email protected] [email protected] [email protected]
common/autoware_test_utils/** [email protected] [email protected] [email protected] [email protected]
common/autoware_testing/** [email protected] [email protected] [email protected] [email protected]
common/autoware_universe_utils/** [email protected] [email protected] [email protected]
Expand All @@ -27,7 +28,6 @@ common/object_recognition_utils/** [email protected] takayuki.murooka@tier
common/osqp_interface/** [email protected] [email protected] [email protected] [email protected]
common/polar_grid/** [email protected]
common/qp_interface/** [email protected] [email protected] [email protected] [email protected]
common/signal_processing/** [email protected] [email protected] [email protected] [email protected] [email protected]
common/tensorrt_common/** [email protected] [email protected]
common/tier4_adapi_rviz_plugin/** [email protected] [email protected] [email protected]
common/tier4_api_utils/** [email protected]
Expand Down Expand Up @@ -91,8 +91,8 @@ localization/autoware_pose_initializer/** [email protected] isamu.takagi@tie
localization/autoware_pose_instability_detector/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
localization/autoware_stop_filter/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
localization/autoware_twist2accel/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
localization/localization_util/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
localization/ndt_scan_matcher/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
localization/autoware_localization_util/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
localization/autoware_ndt_scan_matcher/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
localization/yabloc/yabloc_common/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
localization/yabloc/yabloc_image_processing/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
localization/yabloc/yabloc_monitor/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
Expand All @@ -106,7 +106,7 @@ perception/autoware_bytetrack/** [email protected] [email protected]
perception/autoware_cluster_merger/** [email protected] [email protected] [email protected]
perception/autoware_compare_map_segmentation/** [email protected] [email protected] [email protected]
perception/autoware_crosswalk_traffic_light_estimator/** [email protected] [email protected] [email protected]
perception/autoware_detected_object_feature_remover/** [email protected]
perception/autoware_detected_object_feature_remover/** [email protected] [email protected] [email protected]
perception/autoware_detected_object_validation/** [email protected] [email protected] [email protected] [email protected] [email protected]
perception/autoware_detection_by_tracker/** [email protected] [email protected] [email protected]
perception/autoware_elevation_map_loader/** [email protected] [email protected] [email protected]
Expand Down Expand Up @@ -231,13 +231,11 @@ system/diagnostic_graph_utils/** [email protected]
system/dummy_diag_publisher/** [email protected] [email protected]
system/dummy_infrastructure/** [email protected]
system/duplicated_node_checker/** [email protected] [email protected] [email protected]
system/emergency_handler/** [email protected] [email protected] [email protected]
system/hazard_status_converter/** [email protected]
system/mrm_comfortable_stop_operator/** [email protected] [email protected]
system/mrm_emergency_stop_operator/** [email protected] [email protected]
system/mrm_handler/** [email protected] [email protected] [email protected]
system/system_diagnostic_monitor/** [email protected]
system/system_error_monitor/** [email protected]
system/system_monitor/** [email protected] [email protected]
system/topic_state_monitor/** [email protected]
system/velodyne_monitor/** [email protected]
Expand Down
6 changes: 4 additions & 2 deletions .github/actions/build-and-test-differential/action.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,10 @@ runs:
restore-keys: |
ccache-main-${{ runner.arch }}-${{ inputs.rosdistro }}-
- name: Show ccache stats before build
run: du -sh ${CCACHE_DIR} && ccache -s
- name: Show ccache stats before build and reset stats
run: |
du -sh ${CCACHE_DIR} && ccache -s
ccache --zero-stats
shell: bash

- name: Export CUDA state as a variable for adding to cache key
Expand Down
6 changes: 4 additions & 2 deletions .github/workflows/build-and-test.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,10 @@ jobs:
echo -e "# Set maximum cache size\nmax_size = 600MB" >> "${CCACHE_DIR}/ccache.conf"
shell: bash

- name: Show ccache stats before build
run: du -sh ${CCACHE_DIR} && ccache -s
- name: Show ccache stats before build and reset stats
run: |
du -sh ${CCACHE_DIR} && ccache -s
ccache --zero-stats
shell: bash

- name: Export CUDA state as a variable for adding to cache key
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/cppcheck-differential.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ jobs:
id: cppcheck
run: |
echo "Running Cppcheck on modified packages: ${{ steps.filter-paths-no-cpp-files.outputs.filtered-full-paths }}"
cppcheck --enable=all --inconclusive --check-level=exhaustive --error-exitcode=1 --suppressions-list=.cppcheck_suppressions --inline-suppr ${{ steps.filter-paths-no-cpp-files.outputs.filtered-full-paths }} 2> cppcheck-report.txt
cppcheck --enable=all --inconclusive --check-level=exhaustive -D'PLUGINLIB_EXPORT_CLASS(class_type, base_class)=' -Dslots= -DQ_SLOTS= --error-exitcode=1 --suppressions-list=.cppcheck_suppressions --inline-suppr ${{ steps.filter-paths-no-cpp-files.outputs.filtered-full-paths }} 2> cppcheck-report.txt
shell: bash

- name: Setup Problem Matchers for cppcheck
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/cppcheck-weekly.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ jobs:
continue-on-error: true
id: cppcheck
run: |
cppcheck --enable=all --inconclusive --check-level=exhaustive --suppress=*:*/test/* --error-exitcode=1 --xml --inline-suppr . 2> cppcheck-report.xml
cppcheck --enable=all --inconclusive --check-level=exhaustive -D'PLUGINLIB_EXPORT_CLASS(class_type, base_class)=' -Dslots= -DQ_SLOTS= --suppress=*:*/test/* --error-exitcode=1 --xml --inline-suppr . 2> cppcheck-report.xml
shell: bash

- name: Count errors by error ID and severity
Expand Down
88 changes: 88 additions & 0 deletions codecov.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,3 +30,91 @@ flag_management:
ignore:
- "**/test/*"
- "**/test/**/*"
- "**/debug.*"

component_management:
individual_components:
- component_id: planning-tier-iv-maintained-packages
name: Planning TIER IV Maintained Packages
paths:
- planning/autoware_costmap_generator/**
- planning/autoware_external_velocity_limit_selector/**
- planning/autoware_freespace_planner/**
- planning/autoware_freespace_planning_algorithms/**
- planning/autoware_mission_planner/**
# - planning/autoware_objects_of_interest_marker_interface/**
- planning/autoware_obstacle_cruise_planner/**
# - planning/autoware_obstacle_stop_planner/**
- planning/autoware_path_optimizer/**
- planning/autoware_path_smoother/**
- planning/autoware_planning_test_manager/**
- planning/autoware_planning_topic_converter/**
- planning/autoware_planning_validator/**
- planning/autoware_remaining_distance_time_calculator/**
- planning/autoware_route_handler/**
- planning/autoware_rtc_interface/**
- planning/autoware_scenario_selector/**
- planning/autoware_static_centerline_generator/**
- planning/autoware_surround_obstacle_checker/**
- planning/autoware_velocity_smoother/**
##### behavior_path_planner #####
# - planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/**
- planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/**
- planning/behavior_path_planner/autoware_behavior_path_planner_common/**
- planning/behavior_path_planner/autoware_behavior_path_start_planner_module/**
- planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/**
- planning/behavior_path_planner/autoware_behavior_path_lane_change_module/**
# - planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/**
- planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/**
# - planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/**
- planning/behavior_path_planner/autoware_behavior_path_planner/**
- planning/behavior_path_planner/autoware_behavior_path_side_shift_module/**
##### behavior_velocity_planner #####
- planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/**
# - planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/**
# - planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_planner/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/**
# - planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/**
# - planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/**
- planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/**
##### motion_velocity_planner #####
- planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/**
- planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/**
- planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/**
- planning/motion_velocity_planner/autoware_motion_velocity_planner_common/**
- planning/motion_velocity_planner/autoware_motion_velocity_planner_node/**

- component_id: control-tier-iv-maintained-packages
name: Control TIER IV Maintained Packages
paths:
- control/autoware_autonomous_emergency_braking/**
- control/autoware_control_validator/**
- control/autoware_external_cmd_selector/**
# - control/autoware_joy_controller/**
- control/autoware_lane_departure_checker/**
- control/autoware_mpc_lateral_controller/**
- control/autoware_operation_mode_transition_manager/**
- control/autoware_pid_longitudinal_controller/**
# - control/autoware_pure_pursuit/**
- control/autoware_shift_decider/**
# - control/autoware_smart_mpc_trajectory_follower/**
- control/autoware_trajectory_follower_base/**
- control/autoware_trajectory_follower_node/**
- control/autoware_vehicle_cmd_gate/**
# - control/control_performance_analysis/**
- control/obstacle_collision_checker/**
# - control/predicted_path_checker/**

- component_id: perception-tier-iv-maintained-packages
name: Perception TIER IV Maintained Packages
paths:
- perception/[^lidar_apollo_instance_segmentation]/**
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
cmake_minimum_required(VERSION 3.14)
project(interpolation)
project(autoware_interpolation)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_library(interpolation SHARED
ament_auto_add_library(autoware_interpolation SHARED
src/linear_interpolation.cpp
src/spline_interpolation.cpp
src/spline_interpolation_points_2d.cpp
Expand All @@ -17,7 +17,7 @@ if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_interpolation ${test_files})

target_link_libraries(test_interpolation
interpolation
autoware_interpolation
)
endif()

Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__INTERPOLATION_UTILS_HPP_
#define INTERPOLATION__INTERPOLATION_UTILS_HPP_
#ifndef AUTOWARE__INTERPOLATION__INTERPOLATION_UTILS_HPP_
#define AUTOWARE__INTERPOLATION__INTERPOLATION_UTILS_HPP_

#include <algorithm>
#include <array>
#include <stdexcept>
#include <vector>

namespace interpolation_utils
namespace autoware::interpolation
{
inline bool isIncreasing(const std::vector<double> & x)
{
Expand Down Expand Up @@ -109,6 +109,6 @@ void validateKeysAndValues(
throw std::invalid_argument("The size of base_keys and base_values are not the same.");
}
}
} // namespace interpolation_utils
} // namespace autoware::interpolation

#endif // INTERPOLATION__INTERPOLATION_UTILS_HPP_
#endif // AUTOWARE__INTERPOLATION__INTERPOLATION_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__LINEAR_INTERPOLATION_HPP_
#define INTERPOLATION__LINEAR_INTERPOLATION_HPP_
#ifndef AUTOWARE__INTERPOLATION__LINEAR_INTERPOLATION_HPP_
#define AUTOWARE__INTERPOLATION__LINEAR_INTERPOLATION_HPP_

#include "interpolation/interpolation_utils.hpp"
#include "autoware/interpolation/interpolation_utils.hpp"

#include <vector>

namespace interpolation
namespace autoware::interpolation
{
double lerp(const double src_val, const double dst_val, const double ratio);

Expand All @@ -30,7 +30,6 @@ std::vector<double> lerp(
double lerp(
const std::vector<double> & base_keys, const std::vector<double> & base_values,
const double query_key);
} // namespace autoware::interpolation

} // namespace interpolation

#endif // INTERPOLATION__LINEAR_INTERPOLATION_HPP_
#endif // AUTOWARE__INTERPOLATION__LINEAR_INTERPOLATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
#define INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
#ifndef AUTOWARE__INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
#define AUTOWARE__INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_

#include "interpolation/interpolation_utils.hpp"
#include "autoware/interpolation/interpolation_utils.hpp"

#include <geometry_msgs/msg/quaternion.hpp>

Expand All @@ -29,7 +29,7 @@

#include <vector>

namespace interpolation
namespace autoware::interpolation
{
geometry_msgs::msg::Quaternion slerp(
const geometry_msgs::msg::Quaternion & src_quat, const geometry_msgs::msg::Quaternion & dst_quat,
Expand All @@ -43,6 +43,6 @@ std::vector<geometry_msgs::msg::Quaternion> slerp(
geometry_msgs::msg::Quaternion lerpOrientation(
const geometry_msgs::msg::Quaternion & o_from, const geometry_msgs::msg::Quaternion & o_to,
const double ratio);
} // namespace interpolation
} // namespace autoware::interpolation

#endif // INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
#endif // AUTOWARE__INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,47 +12,29 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__SPLINE_INTERPOLATION_HPP_
#define INTERPOLATION__SPLINE_INTERPOLATION_HPP_
#ifndef AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_HPP_
#define AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_HPP_

#include "autoware/interpolation/interpolation_utils.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "interpolation/interpolation_utils.hpp"

#include <Eigen/Core>

#include <algorithm>
#include <cmath>
#include <iostream>
#include <numeric>
#include <vector>

namespace interpolation
{
// NOTE: X(s) = a_i (s - s_i)^3 + b_i (s - s_i)^2 + c_i (s - s_i) + d_i : (i = 0, 1, ... N-1)
struct MultiSplineCoef
namespace autoware::interpolation
{
MultiSplineCoef() = default;

explicit MultiSplineCoef(const size_t num_spline)
{
a.resize(num_spline);
b.resize(num_spline);
c.resize(num_spline);
d.resize(num_spline);
}

std::vector<double> a;
std::vector<double> b;
std::vector<double> c;
std::vector<double> d;
};

// static spline interpolation functions
std::vector<double> spline(
const std::vector<double> & base_keys, const std::vector<double> & base_values,
const std::vector<double> & query_keys);
std::vector<double> splineByAkima(
const std::vector<double> & base_keys, const std::vector<double> & base_values,
const std::vector<double> & query_keys);
} // namespace interpolation

// non-static 1-dimensional spline interpolation
//
Expand Down Expand Up @@ -98,11 +80,18 @@ class SplineInterpolation
size_t getSize() const { return base_keys_.size(); }

private:
Eigen::VectorXd a_;
Eigen::VectorXd b_;
Eigen::VectorXd c_;
Eigen::VectorXd d_;

std::vector<double> base_keys_;
interpolation::MultiSplineCoef multi_spline_coef_;

void calcSplineCoefficients(
const std::vector<double> & base_keys, const std::vector<double> & base_values);

Eigen::Index get_index(const double & key) const;
};
} // namespace autoware::interpolation

#endif // INTERPOLATION__SPLINE_INTERPOLATION_HPP_
#endif // AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_HPP_
Loading

0 comments on commit 0611bb9

Please sign in to comment.