Skip to content

Commit

Permalink
Merge pull request #1416 from tier4/sync-upstream
Browse files Browse the repository at this point in the history
chore: sync tier4/autoware.universe:awf-latest
  • Loading branch information
tier4-autoware-public-bot[bot] authored Jul 18, 2024
2 parents 0c4479f + 2ee831e commit 77ada35
Show file tree
Hide file tree
Showing 691 changed files with 10,887 additions and 4,305 deletions.
7 changes: 0 additions & 7 deletions .cppcheck_suppressions
Original file line number Diff line number Diff line change
Expand Up @@ -3,22 +3,15 @@
checkersReport
constParameterReference
constVariableReference
// cspell: ignore cstyle
cstyleCast
funcArgNamesDifferent
functionConst
functionStatic
invalidPointerCast
knownConditionTrueFalse
missingInclude
missingIncludeSystem
noConstructor
noExplicitConstructor
noValidConfiguration
passedByValue
preprocessorErrorDirective
redundantInitialization
shadowFunction
shadowVariable
// cspell: ignore uninit
uninitMemberVar
Expand Down
61 changes: 31 additions & 30 deletions .github/CODEOWNERS

Large diffs are not rendered by default.

8 changes: 8 additions & 0 deletions .github/workflows/build-and-test-differential.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,14 @@ jobs:
restore-keys: |
ccache-main-${{ runner.arch }}-${{ matrix.rosdistro }}-
# Limit ccache size only for CUDA builds to avoid running out of disk space
- name: Limit ccache size
if: ${{ matrix.container-suffix == '-cuda' }}
run: |
rm -f "${CCACHE_DIR}/ccache.conf"
echo -e "# Set maximum cache size\nmax_size = 1MB" >> "${CCACHE_DIR}/ccache.conf"
shell: bash

- name: Show ccache stats before build
run: du -sh ${CCACHE_DIR} && ccache -s
shell: bash
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 @@ -58,7 +58,7 @@ jobs:
run: |
filtered_paths=""
for dir in ${{ steps.get-full-paths.outputs.full-paths }}; do
if [ -d "$dir" ] && find "$dir" -name "*.cpp" -o -name "*.hpp" | grep -q .; then
if [ -d "$dir" ] && find "$dir" -name "*.cpp" | grep -q .; then
filtered_paths="$filtered_paths $dir"
fi
done
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ struct VehicleKinematics
using Message = autoware_adapi_v1_msgs::msg::VehicleKinematics;
static constexpr char name[] = "/api/vehicle/kinematics";
static constexpr size_t depth = 1;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -991,34 +991,51 @@ calcCurvature<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
* curvature calculation
*/
template <class T>
std::vector<std::pair<double, double>> calcCurvatureAndArcLength(const T & points)
std::vector<std::pair<double, std::pair<double, double>>> calcCurvatureAndSegmentLength(
const T & points)
{
// Note that arclength is for the segment, not the sum.
std::vector<std::pair<double, double>> curvature_arc_length_vec;
curvature_arc_length_vec.emplace_back(0.0, 0.0);
// segment length is pair of segment length between {p1, p2} and {p2, p3}
std::vector<std::pair<double, std::pair<double, double>>> curvature_and_segment_length_vec;
curvature_and_segment_length_vec.reserve(points.size());
curvature_and_segment_length_vec.emplace_back(0.0, std::make_pair(0.0, 0.0));
for (size_t i = 1; i < points.size() - 1; ++i) {
const auto p1 = autoware::universe_utils::getPoint(points.at(i - 1));
const auto p2 = autoware::universe_utils::getPoint(points.at(i));
const auto p3 = autoware::universe_utils::getPoint(points.at(i + 1));
const double curvature = autoware::universe_utils::calcCurvature(p1, p2, p3);
const double arc_length =
autoware::universe_utils::calcDistance2d(points.at(i - 1), points.at(i)) +
autoware::universe_utils::calcDistance2d(points.at(i), points.at(i + 1));
curvature_arc_length_vec.emplace_back(curvature, arc_length);

// The first point has only the next point, so put the distance to that point.
// In other words, assign the first segment length at the second point to the
// second_segment_length at the first point.
if (i == 1) {
curvature_and_segment_length_vec.at(0).second.second =
autoware::universe_utils::calcDistance2d(p1, p2);
}

// The second_segment_length of the previous point and the first segment length of the current
// point are equal.
const std::pair<double, double> arc_length{
curvature_and_segment_length_vec.back().second.second,
autoware::universe_utils::calcDistance2d(p2, p3)};

curvature_and_segment_length_vec.emplace_back(curvature, arc_length);
}
curvature_arc_length_vec.emplace_back(0.0, 0.0);

return curvature_arc_length_vec;
// set to the last point
curvature_and_segment_length_vec.emplace_back(
0.0, std::make_pair(curvature_and_segment_length_vec.back().second.second, 0.0));

return curvature_and_segment_length_vec;
}

extern template std::vector<std::pair<double, double>>
calcCurvatureAndArcLength<std::vector<autoware_planning_msgs::msg::PathPoint>>(
extern template std::vector<std::pair<double, std::pair<double, double>>>
calcCurvatureAndSegmentLength<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const std::vector<autoware_planning_msgs::msg::PathPoint> & points);
extern template std::vector<std::pair<double, double>>
calcCurvatureAndArcLength<std::vector<tier4_planning_msgs::msg::PathPointWithLaneId>>(
extern template std::vector<std::pair<double, std::pair<double, double>>>
calcCurvatureAndSegmentLength<std::vector<tier4_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<tier4_planning_msgs::msg::PathPointWithLaneId> & points);
extern template std::vector<std::pair<double, double>>
calcCurvatureAndArcLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
extern template std::vector<std::pair<double, std::pair<double, double>>>
calcCurvatureAndSegmentLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points);

/**
Expand Down
12 changes: 6 additions & 6 deletions common/autoware_motion_utils/src/trajectory/trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,14 +238,14 @@ calcCurvature<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points);

//
template std::vector<std::pair<double, double>>
calcCurvatureAndArcLength<std::vector<autoware_planning_msgs::msg::PathPoint>>(
template std::vector<std::pair<double, std::pair<double, double>>>
calcCurvatureAndSegmentLength<std::vector<autoware_planning_msgs::msg::PathPoint>>(
const std::vector<autoware_planning_msgs::msg::PathPoint> & points);
template std::vector<std::pair<double, double>>
calcCurvatureAndArcLength<std::vector<tier4_planning_msgs::msg::PathPointWithLaneId>>(
template std::vector<std::pair<double, std::pair<double, double>>>
calcCurvatureAndSegmentLength<std::vector<tier4_planning_msgs::msg::PathPointWithLaneId>>(
const std::vector<tier4_planning_msgs::msg::PathPointWithLaneId> & points);
template std::vector<std::pair<double, double>>
calcCurvatureAndArcLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
template std::vector<std::pair<double, std::pair<double, double>>>
calcCurvatureAndSegmentLength<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & points);

//
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,23 @@ enum ReturnType : uint8_t {
DUAL_ONLY,
};

struct PointXYZIRC
{
float x{0.0F};
float y{0.0F};
float z{0.0F};
std::uint8_t intensity{0U};
std::uint8_t return_type{0U};
std::uint16_t channel{0U};

friend bool operator==(const PointXYZIRC & p1, const PointXYZIRC & p2) noexcept
{
return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) &&
float_eq<float>(p1.z, p2.z) && p1.intensity == p2.intensity &&
p1.return_type == p2.return_type && p1.channel == p2.channel;
}
};

struct PointXYZIRADRT
{
float x{0.0F};
Expand All @@ -75,25 +92,97 @@ struct PointXYZIRADRT
}
};

enum class PointIndex { X, Y, Z, Intensity, Ring, Azimuth, Distance, ReturnType, TimeStamp };
struct PointXYZIRCAEDT
{
float x{0.0F};
float y{0.0F};
float z{0.0F};
std::uint8_t intensity{0U};
std::uint8_t return_type{0U};
std::uint16_t channel{0U};
float azimuth{0.0F};
float elevation{0.0F};
float distance{0.0F};
std::uint32_t time_stamp{0U};

friend bool operator==(const PointXYZIRCAEDT & p1, const PointXYZIRCAEDT & p2) noexcept
{
return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) &&
float_eq<float>(p1.z, p2.z) && p1.intensity == p2.intensity &&
p1.return_type == p2.return_type && p1.channel == p2.channel &&
float_eq<float>(p1.azimuth, p2.azimuth) && float_eq<float>(p1.distance, p2.distance) &&
p1.time_stamp == p2.time_stamp;
}
};

enum class PointXYZIIndex { X, Y, Z, Intensity };
enum class PointXYZIRCIndex { X, Y, Z, Intensity, ReturnType, Channel };
enum class PointXYZIRADRTIndex {
X,
Y,
Z,
Intensity,
Ring,
Azimuth,
Distance,
ReturnType,
TimeStamp
};
enum class PointXYZIRCAEDTIndex {
X,
Y,
Z,
Intensity,
ReturnType,
Channel,
Azimuth,
Elevation,
Distance,
TimeStamp
};

LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(azimuth);
LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(elevation);
LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(distance);
LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(return_type);
LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(time_stamp);

LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(channel);

using PointXYZIRCGenerator = std::tuple<
point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator,
point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator,
field_return_type_generator, field_channel_generator>;

using PointXYZIRADRTGenerator = std::tuple<
point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator,
point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator,
point_cloud_msg_wrapper::field_ring_generator, field_azimuth_generator, field_distance_generator,
field_return_type_generator, field_time_stamp_generator>;

using PointXYZIRCAEDTGenerator = std::tuple<
point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator,
point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator,
field_return_type_generator, field_channel_generator, field_azimuth_generator,
field_elevation_generator, field_distance_generator, field_time_stamp_generator>;

} // namespace autoware_point_types

POINT_CLOUD_REGISTER_POINT_STRUCT(
autoware_point_types::PointXYZIRC,
(float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)(
std::uint8_t, return_type, return_type)(std::uint16_t, channel, channel))

POINT_CLOUD_REGISTER_POINT_STRUCT(
autoware_point_types::PointXYZIRADRT,
(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)(
float, azimuth, azimuth)(float, distance, distance)(std::uint8_t, return_type, return_type)(
double, time_stamp, time_stamp))

POINT_CLOUD_REGISTER_POINT_STRUCT(
autoware_point_types::PointXYZIRCAEDT,
(float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)(
std::uint8_t, return_type,
return_type)(std::uint16_t, channel, channel)(float, azimuth, azimuth)(
float, elevation, elevation)(float, distance, distance)(std::uint32_t, time_stamp, time_stamp))
#endif // AUTOWARE_POINT_TYPES__TYPES_HPP_
9 changes: 9 additions & 0 deletions common/autoware_point_types/test/test_point_types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,15 @@ TEST(PointEquality, PointXYZIRADRT)
EXPECT_EQ(pt0, pt1);
}

TEST(PointEquality, PointXYZIRCAEDT)
{
using autoware_point_types::PointXYZIRCAEDT;

PointXYZIRCAEDT pt0{0, 1, 2, 3, 4, 5, 6, 7, 8, 9};
PointXYZIRCAEDT pt1{0, 1, 2, 3, 4, 5, 6, 7, 8, 9};
EXPECT_EQ(pt0, pt1);
}

TEST(PointEquality, FloatEq)
{
// test template
Expand Down
25 changes: 25 additions & 0 deletions common/autoware_universe_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,11 +1,15 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_universe_utils)

option(BUILD_EXAMPLES "Build examples" OFF)

find_package(autoware_cmake REQUIRED)
autoware_package()

find_package(Boost REQUIRED)

find_package(fmt REQUIRED)

ament_auto_add_library(autoware_universe_utils SHARED
src/geometry/geometry.cpp
src/geometry/pose_deviation.cpp
Expand All @@ -16,6 +20,11 @@ ament_auto_add_library(autoware_universe_utils SHARED
src/ros/marker_helper.cpp
src/ros/logger_level_configure.cpp
src/system/backtrace.cpp
src/system/time_keeper.cpp
)

target_link_libraries(autoware_universe_utils
fmt::fmt
)

if(BUILD_TESTING)
Expand All @@ -30,4 +39,20 @@ if(BUILD_TESTING)
)
endif()

if(BUILD_EXAMPLES)
message(STATUS "Building examples")
file(GLOB_RECURSE example_files examples/*.cpp)

foreach(example_file ${example_files})
get_filename_component(example_name ${example_file} NAME_WE)
add_executable(${example_name} ${example_file})
target_link_libraries(${example_name}
autoware_universe_utils
)
install(TARGETS ${example_name}
DESTINATION lib/${PROJECT_NAME}
)
endforeach()
endif()

ament_auto_package()
Loading

0 comments on commit 77ada35

Please sign in to comment.