Skip to content

Commit

Permalink
Merge branch 'main' into feat/autoware_test_utils/add_jump_clock
Browse files Browse the repository at this point in the history
  • Loading branch information
kminoda authored Jun 24, 2024
2 parents 75478ec + 9a456e6 commit 006e193
Show file tree
Hide file tree
Showing 27 changed files with 92 additions and 58 deletions.
2 changes: 2 additions & 0 deletions .cppcheck_suppressions
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ constParameterReference
constVariable
constVariableReference
containerOutOfBounds
// cspell: ignore cstyle
cstyleCast
duplicateBranch
duplicateBreak
Expand All @@ -27,6 +28,7 @@ shadowArgument
shadowFunction
shadowVariable
syntaxError
// cspell: ignore uninit
uninitMemberVar
unknownMacro
unmatchedSuppression
Expand Down
18 changes: 6 additions & 12 deletions .github/workflows/clang-tidy-differential.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,10 @@ jobs:
runs-on: ubuntu-latest
container: ghcr.io/autowarefoundation/autoware:latest-prebuilt-cuda
steps:
- name: Set PR fetch depth
run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}"

- name: Checkout PR branch and all PR commits
uses: actions/checkout@v4
with:
ref: ${{ github.event.pull_request.head.sha }}
fetch-depth: ${{ env.PR_FETCH_DEPTH }}
fetch-depth: 0

- name: Show disk space before the tasks
run: df -h
Expand All @@ -41,19 +37,17 @@ jobs:

- name: Get modified files
id: get-modified-files
uses: tj-actions/changed-files@v42
with:
files: |
**/*.cpp
**/*.hpp
run: |
echo "changed_files=$(git diff --name-only "origin/${{ github.base_ref }}"...HEAD | grep -E '\.(cpp|hpp)$' || true)" >> $GITHUB_OUTPUT
shell: bash

- name: Run clang-tidy
if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }}
if: ${{ steps.get-modified-files.outputs.changed_files != '' }}
uses: autowarefoundation/autoware-github-actions/clang-tidy@v1
with:
rosdistro: humble
target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
target-files: ${{ steps.get-modified-files.outputs.all_changed_files }}
target-files: ${{ steps.get-modified-files.outputs.changed_files }}
clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy
build-depends-repos: build_depends.repos

Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/cppcheck-daily.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ jobs:
continue-on-error: true
id: cppcheck
run: |
cppcheck --enable=all --inconclusive --check-level=exhaustive --error-exitcode=1 --xml . 2> cppcheck-report.xml
cppcheck --enable=all --inconclusive --check-level=exhaustive --suppress=*:*/test/* --error-exitcode=1 --xml . 2> cppcheck-report.xml
shell: bash

- name: Count errors by error ID and severity
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@
#include <OgreQuaternion.h>
#include <OgreSceneManager.h>
#include <OgreSceneNode.h>
#include <OgreVector3.h>
#include <OgreVector.h>
#include <OgreViewport.h>

namespace tier4_camera_view_rviz_plugin
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
#include "rviz_common/frame_position_tracking_view_controller.hpp"

#include <OgreQuaternion.h>
#include <OgreVector3.h>
#include <OgreVector.h>

namespace rviz_common
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@
#include <OgreQuaternion.h>
#include <OgreRay.h>
#include <OgreSceneNode.h>
#include <OgreVector3.h>
#include <OgreVector.h>
#include <OgreViewport.h>
#include <stdint.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@

#include "rviz_default_plugins/view_controllers/orbit/orbit_view_controller.hpp"

#include <OgreVector3.h>
#include <OgreVector.h>

#include <utility>

Expand Down
2 changes: 1 addition & 1 deletion common/tier4_perception_rviz_plugin/src/tools/util.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include <rviz_common/viewport_mouse_event.hpp>

#include <OgreVector3.h>
#include <OgreVector.h>

#include <optional>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@

#include <OgreColourValue.h>
#include <OgreManualObject.h>
#include <OgreVector3.h>
#include <OgreVector.h>

#include <deque>
#include <memory>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,11 @@
#include <opencv4/opencv2/calib3d.hpp>
#include <opencv4/opencv2/core/quaternion.hpp>

#include <cv_bridge/cv_bridge.h>
#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp> // for ROS 2 Jazzy or newer
#else
#include <cv_bridge/cv_bridge.h> // for ROS 2 Humble or older
#endif
#include <tf2/LinearMath/Transform.h>

#include <algorithm>
Expand Down
6 changes: 5 additions & 1 deletion localization/yabloc/yabloc_common/src/cv_decompress.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,11 @@
#include <opencv4/opencv2/imgcodecs.hpp>
#include <opencv4/opencv2/imgproc.hpp>

#include <cv_bridge/cv_bridge.h>
#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp> // for ROS 2 Jazzy or newer
#else
#include <cv_bridge/cv_bridge.h> // for ROS 2 Humble or older
#endif

#include <iostream>

Expand Down
6 changes: 5 additions & 1 deletion localization/yabloc/yabloc_common/src/pub_sub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,11 @@

#include "yabloc_common/pub_sub.hpp"

#include <cv_bridge/cv_bridge.h>
#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp> // for ROS 2 Jazzy or newer
#else
#include <cv_bridge/cv_bridge.h> // for ROS 2 Humble or older
#endif
#include <pcl_conversions/pcl_conversions.h>

namespace yabloc::common
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,11 @@
#include <yabloc_common/cv_decompress.hpp>
#include <yabloc_common/pub_sub.hpp>

#include <cv_bridge/cv_bridge.h>
#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp> // for ROS 2 Jazzy or newer
#else
#include <cv_bridge/cv_bridge.h> // for ROS 2 Humble or older
#endif
#include <pcl_conversions/pcl_conversions.h>

namespace yabloc::line_segments_overlay
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,11 @@
#include <sensor_msgs/msg/compressed_image.hpp>
#include <sensor_msgs/msg/image.hpp>

#include <cv_bridge/cv_bridge.h>
#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp> // for ROS 2 Jazzy or newer
#else
#include <cv_bridge/cv_bridge.h> // for ROS 2 Humble or older
#endif

#include <optional>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,11 @@
#include <opencv2/highgui.hpp>
#include <opencv2/imgproc.hpp>

#include <cv_bridge/cv_bridge.h>
#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp> // for ROS 2 Jazzy or newer
#else
#include <cv_bridge/cv_bridge.h> // for ROS 2 Humble or older
#endif

#include <filesystem>

Expand Down
5 changes: 3 additions & 2 deletions perception/bytetrack/lib/src/lapjv.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,8 @@ int_t _carr_dense(

/** Find columns with minimum d[j] and put them on the SCAN list.
*/
uint_t _find_dense(const uint_t n, uint_t lo, cost_t * d, int_t * cols, [[maybe_unused]] int_t * y)
uint_t _find_dense(
const uint_t n, uint_t lo, const cost_t * d, int_t * cols, [[maybe_unused]] int_t * y)
{
uint_t hi = lo + 1;
cost_t mind = d[cols[lo]];
Expand All @@ -203,7 +204,7 @@ uint_t _find_dense(const uint_t n, uint_t lo, cost_t * d, int_t * cols, [[maybe_
// and try to decrease d of the TODO columns using the SCAN column.
int_t _scan_dense(
const uint_t n, cost_t * cost[], uint_t * plo, uint_t * phi, cost_t * d, int_t * cols,
int_t * pred, int_t * y, cost_t * v)
int_t * pred, const int_t * y, const cost_t * v)
{
uint_t lo = *plo;
uint_t hi = *phi;
Expand Down
9 changes: 0 additions & 9 deletions perception/bytetrack/lib/src/strack.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,12 +112,6 @@ void STrack::activate(int frame_id)
this->track_id = this->next_id();
this->unique_id = boost::uuids::random_generator()();

std::vector<float> _tlwh_tmp(4);
_tlwh_tmp[0] = this->original_tlwh[0];
_tlwh_tmp[1] = this->original_tlwh[1];
_tlwh_tmp[2] = this->original_tlwh[2];
_tlwh_tmp[3] = this->original_tlwh[3];
std::vector<float> xyah = tlwh_to_xyah(_tlwh_tmp);
// init kf
init_kalman_filter();
// reflect state
Expand All @@ -132,7 +126,6 @@ void STrack::activate(int frame_id)

void STrack::re_activate(STrack & new_track, int frame_id, bool new_id)
{
std::vector<float> xyah = tlwh_to_xyah(new_track.tlwh);
// TODO(me): write kf update
Eigen::MatrixXd measurement = Eigen::MatrixXd::Zero(_kf_parameters.dim_z, 1);
measurement << new_track.tlwh[0], new_track.tlwh[1], new_track.tlwh[2], new_track.tlwh[3];
Expand All @@ -156,8 +149,6 @@ void STrack::update(STrack & new_track, int frame_id)
this->frame_id = frame_id;
this->tracklet_len++;

std::vector<float> xyah = tlwh_to_xyah(new_track.tlwh);

// update
// TODO(me): write update
Eigen::MatrixXd measurement = Eigen::MatrixXd::Zero(_kf_parameters.dim_z, 1);
Expand Down
5 changes: 2 additions & 3 deletions perception/bytetrack/lib/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,6 @@ std::vector<std::vector<float>> ByteTracker::ious(

// bbox_ious
for (size_t k = 0; k < btlbrs.size(); k++) {
std::vector<float> ious_tmp;
float box_area = (btlbrs[k][2] - btlbrs[k][0] + 1) * (btlbrs[k][3] - btlbrs[k][1] + 1);
for (size_t n = 0; n < atlbrs.size(); n++) {
float iw = std::min(atlbrs[n][2], btlbrs[k][2]) - std::max(atlbrs[n][0], btlbrs[k][0]) + 1;
Expand Down Expand Up @@ -277,8 +276,6 @@ double ByteTracker::lapjv(
std::vector<std::vector<float>> cost_c;
cost_c.assign(cost.begin(), cost.end());

std::vector<std::vector<float>> cost_c_extended;

int n_rows = cost.size();
int n_cols = cost[0].size();
rowsol.resize(n_rows);
Expand All @@ -296,6 +293,8 @@ double ByteTracker::lapjv(
}

if (extend_cost || cost_limit < LONG_MAX) {
std::vector<std::vector<float>> cost_c_extended;

n = n_rows + n_cols;
cost_c_extended.resize(n);
for (size_t i = 0; i < cost_c_extended.size(); i++) cost_c_extended[i].resize(n);
Expand Down
4 changes: 2 additions & 2 deletions perception/bytetrack/src/bytetrack_visualizer_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,14 +128,14 @@ void ByteTrackVisualizerNode::callback(
}

std::vector<cv::Rect> bboxes;
for (auto & feat_obj : rect_msg->feature_objects) {
for (const auto & feat_obj : rect_msg->feature_objects) {
auto roi_msg = feat_obj.feature.roi;
cv::Rect rect(roi_msg.x_offset, roi_msg.y_offset, roi_msg.width, roi_msg.height);
bboxes.push_back(rect);
}

std::vector<boost::uuids::uuid> uuids;
for (auto & dynamic_obj : uuid_msg->objects) {
for (const auto & dynamic_obj : uuid_msg->objects) {
auto uuid_msg = dynamic_obj.id.uuid;
boost::uuids::uuid uuid_raw;
std::copy(uuid_msg.begin(), uuid_msg.end(), uuid_raw.begin());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,12 @@
#include <tier4_perception_msgs/msg/traffic_light_roi_array.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <image_geometry/pinhole_camera_model.h>
#if __has_include(<image_geometry/pinhole_camera_model.hpp>)
#include <image_geometry/pinhole_camera_model.hpp> // for ROS 2 Jazzy or newer
#else
#include <image_geometry/pinhole_camera_model.h> // for ROS 2 Humble or older
#endif

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_routing/RoutingGraph.h>
#include <lanelet2_traffic_rules/TrafficRulesFactory.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,12 @@
#include <tier4_perception_msgs/msg/traffic_light_array.hpp>
#include <tier4_perception_msgs/msg/traffic_light_roi_array.hpp>

#include <image_geometry/pinhole_camera_model.h>
#if __has_include(<image_geometry/pinhole_camera_model.hpp>)
#include <image_geometry/pinhole_camera_model.hpp> // for ROS 2 Jazzy or newer
#else
#include <image_geometry/pinhole_camera_model.h> // for ROS 2 Humble or older
#endif

#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/time_synchronizer.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,12 @@
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <tier4_perception_msgs/msg/traffic_light_roi_array.hpp>

#include <image_geometry/pinhole_camera_model.h>
#if __has_include(<image_geometry/pinhole_camera_model.hpp>)
#include <image_geometry/pinhole_camera_model.hpp> // for ROS 2 Jazzy or newer
#else
#include <image_geometry/pinhole_camera_model.h> // for ROS 2 Humble or older
#endif

#include <lanelet2_core/Forward.h>
#include <pcl/common/transforms.h>
#include <pcl/point_cloud.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,11 @@
#include <tier4_perception_msgs/msg/traffic_light_array.hpp>
#include <tier4_perception_msgs/msg/traffic_light_roi_array.hpp>

#include <cv_bridge/cv_bridge.h>
#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp> // for ROS 2 Jazzy or newer
#else
#include <cv_bridge/cv_bridge.h> // for ROS 2 Humble or older
#endif
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/synchronizer.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -339,16 +339,21 @@ std::tuple<double, double> OptimizationBasedPlanner::calcInitialMotion(
const auto stop_dist = autoware::motion_utils::calcDistanceToForwardStopPoint(
input_traj_points, ego_pose, ego_nearest_param_.dist_threshold,
ego_nearest_param_.yaw_threshold);
if ((stop_dist && *stop_dist > stop_dist_to_prohibit_engage_) || !stop_dist) {
initial_vel = engage_velocity_;
initial_acc = engage_acceleration_;
if (!stop_dist.has_value()) {
RCLCPP_DEBUG(
rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"),
"calcInitialMotion : vehicle speed is low (%.3f), and desired speed is high (%.3f). Use "
"engage speed (%.3f) until vehicle speed reaches engage_vel_thr (%.3f)",
vehicle_speed, target_vel, engage_velocity_, engage_vel_thr);
return std::make_tuple(engage_velocity_, engage_acceleration_);
} else if (stop_dist.value() > stop_dist_to_prohibit_engage_) {
RCLCPP_DEBUG(
rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"),
"calcInitialMotion : vehicle speed is low (%.3f), and desired speed is high (%.3f). Use "
"engage speed (%.3f) until vehicle speed reaches engage_vel_thr (%.3f). stop_dist = %.3f",
vehicle_speed, target_vel, engage_velocity_, engage_vel_thr, stop_dist.value());
return std::make_tuple(initial_vel, initial_acc);
} else if (stop_dist) {
return std::make_tuple(engage_velocity_, engage_acceleration_);
} else {
RCLCPP_DEBUG(
rclcpp::get_logger("ObstacleCruisePlanner::OptimizationBasedPlanner"),
"calcInitialMotion : stop point is close (%.3f[m]). no engage.", stop_dist.value());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -509,7 +509,6 @@ std::vector<TrajectoryPoint> PIDBasedPlanner::getAccelerationLimitedTrajectory(
const double v0, const double a0, const double target_acc, const double target_jerk_ratio) const
{
// calculate vt function
const auto & i = longitudinal_info_;
const auto vt = [&](
const double v0, const double a0, const double jerk, const double t,
const double target_acc) {
Expand Down Expand Up @@ -541,8 +540,8 @@ std::vector<TrajectoryPoint> PIDBasedPlanner::getAccelerationLimitedTrajectory(
// Therefore, we calculate v1 (velocity at next step) and use it for initial velocity.
const double v1 = v0; // + 0.1; // a0 * 0.1; // + jerk * 0.1 * 0.1 / 2.0;
const double a1 = a0; // + jerk * 0.1;
const double jerk =
target_acc > a1 ? i.max_jerk * target_jerk_ratio : i.min_jerk * target_jerk_ratio;
const double jerk = target_acc > a1 ? longitudinal_info_.max_jerk * target_jerk_ratio
: longitudinal_info_.min_jerk * target_jerk_ratio;

double t_current = 0.0;
std::vector<double> s_vec{0.0};
Expand Down
Loading

0 comments on commit 006e193

Please sign in to comment.