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

refactor(universe_utils/motion_utils): add autoware namespace #1344

Merged
merged 2 commits into from
Jun 20, 2024
Merged
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
The table of contents is too big for display.
Diff view
Diff view
  •  
  •  
  •  
2 changes: 1 addition & 1 deletion common/autoware_grid_map_utils/test/benchmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ int main(int argc, char * argv[])
result_file
<< "#Size PolygonVertices PolygonIndexes grid_map_utils_constructor grid_map_utils_iteration "
"grid_map_constructor grid_map_iteration\n";
autoware_universe_utils::StopWatch<std::chrono::milliseconds> stopwatch;
autoware::universe_utils::StopWatch<std::chrono::milliseconds> stopwatch;

constexpr auto nb_iterations = 10;
constexpr auto polygon_side_vertices =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
#ifndef AUTOWARE__MOTION_UTILS__CONSTANTS_HPP_
#define AUTOWARE__MOTION_UTILS__CONSTANTS_HPP_

namespace autoware_motion_utils
namespace autoware::motion_utils
{
constexpr double overlap_threshold = 0.1;
} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__CONSTANTS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -22,12 +22,12 @@
#include <tuple>
#include <vector>

namespace autoware_motion_utils
namespace autoware::motion_utils
{
std::optional<double> calcDecelDistWithJerkAndAccConstraints(
const double current_vel, const double target_vel, const double current_acc, const double acc_min,
const double jerk_acc, const double jerk_dec);

} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__DISTANCE__DISTANCE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <string>
#include <vector>

namespace autoware_motion_utils
namespace autoware::motion_utils
{
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
using autoware_adapi_v1_msgs::msg::VelocityFactor;
Expand All @@ -49,6 +49,6 @@ class VelocityFactorInterface
VelocityFactor velocity_factor_{};
};

} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <string>

namespace autoware_motion_utils
namespace autoware::motion_utils
{
using geometry_msgs::msg::Pose;

Expand All @@ -48,6 +48,6 @@ visualization_msgs::msg::MarkerArray createDeletedSlowDownVirtualWallMarker(

visualization_msgs::msg::MarkerArray createDeletedDeadLineVirtualWallMarker(
const rclcpp::Time & now, const int32_t id);
} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__MARKER__MARKER_HELPER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <unordered_map>
#include <vector>

namespace autoware_motion_utils
namespace autoware::motion_utils
{

/// @brief type of virtual wall associated with different marker styles and namespace
Expand Down Expand Up @@ -76,6 +76,6 @@ class VirtualWallMarkerCreator
/// @param now current time to be used for displaying the markers
visualization_msgs::msg::MarkerArray create_markers(const rclcpp::Time & now = rclcpp::Time());
};
} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__MARKER__VIRTUAL_WALL_MARKER_CREATOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <vector>

namespace autoware_motion_utils
namespace autoware::motion_utils
{
/**
* @brief A resampling function for a path(points). Note that in a default setting, position xy are
Expand Down Expand Up @@ -234,6 +234,6 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory(
const bool use_akima_spline_for_xy = false, const bool use_lerp_for_z = true,
const bool use_zero_order_hold_for_twist = true,
const bool resample_input_trajectory_stop_point = true);
} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -42,17 +42,17 @@ bool validate_size(const T & points)
template <class T>
bool validate_resampling_range(const T & points, const std::vector<double> & resampling_intervals)
{
const double points_length = autoware_motion_utils::calcArcLength(points);
const double points_length = autoware::motion_utils::calcArcLength(points);
return points_length >= resampling_intervals.back();
}

template <class T>
bool validate_points_duplication(const T & points)
{
for (size_t i = 0; i < points.size() - 1; ++i) {
const auto & curr_pt = autoware_universe_utils::getPoint(points.at(i));
const auto & next_pt = autoware_universe_utils::getPoint(points.at(i + 1));
const double ds = autoware_universe_utils::calcDistance2d(curr_pt, next_pt);
const auto & curr_pt = autoware::universe_utils::getPoint(points.at(i));
const auto & next_pt = autoware::universe_utils::getPoint(points.at(i + 1));
const double ds = autoware::universe_utils::calcDistance2d(curr_pt, next_pt);
if (ds < close_s_threshold) {
return false;
}
Expand All @@ -67,27 +67,27 @@ bool validate_arguments(const T & input_points, const std::vector<double> & resa
// Check size of the arguments
if (!validate_size(input_points)) {
RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2");
autoware_universe_utils::print_backtrace();
autoware::universe_utils::print_backtrace();
return false;
}
if (!validate_size(resampling_intervals)) {
RCLCPP_DEBUG(
get_logger(), "invalid argument: The number of resampling intervals is less than 2");
autoware_universe_utils::print_backtrace();
autoware::universe_utils::print_backtrace();
return false;
}

// Check resampling range
if (!validate_resampling_range(input_points, resampling_intervals)) {
RCLCPP_DEBUG(get_logger(), "invalid argument: resampling interval is longer than input points");
autoware_universe_utils::print_backtrace();
autoware::universe_utils::print_backtrace();
return false;
}

// Check duplication
if (!validate_points_duplication(input_points)) {
RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points");
autoware_universe_utils::print_backtrace();
autoware::universe_utils::print_backtrace();
return false;
}

Expand All @@ -100,23 +100,23 @@ bool validate_arguments(const T & input_points, const double resampling_interval
// Check size of the arguments
if (!validate_size(input_points)) {
RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2");
autoware_universe_utils::print_backtrace();
autoware::universe_utils::print_backtrace();
return false;
}

// check resampling interval
if (resampling_interval < autoware_motion_utils::overlap_threshold) {
if (resampling_interval < autoware::motion_utils::overlap_threshold) {
RCLCPP_DEBUG(
get_logger(), "invalid argument: resampling interval is less than %f",
autoware_motion_utils::overlap_threshold);
autoware_universe_utils::print_backtrace();
autoware::motion_utils::overlap_threshold);
autoware::universe_utils::print_backtrace();
return false;
}

// Check duplication
if (!validate_points_duplication(input_points)) {
RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points");
autoware_universe_utils::print_backtrace();
autoware::universe_utils::print_backtrace();
return false;
}

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

#include <vector>

namespace autoware_motion_utils
namespace autoware::motion_utils
{
using TrajectoryPoints = std::vector<autoware_planning_msgs::msg::TrajectoryPoint>;

Expand Down Expand Up @@ -115,6 +115,6 @@ inline tier4_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId(
return output;
}

} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <algorithm>
#include <limits>

namespace autoware_motion_utils
namespace autoware::motion_utils
{
/**
* @brief An interpolation function that finds the closest interpolated point on the trajectory from
Expand Down Expand Up @@ -73,24 +73,24 @@ geometry_msgs::msg::Pose calcInterpolatedPose(const T & points, const double tar
}

if (points.size() < 2 || target_length < 0.0) {
return autoware_universe_utils::getPose(points.front());
return autoware::universe_utils::getPose(points.front());
}

double accumulated_length = 0;
for (size_t i = 0; i < points.size() - 1; ++i) {
const auto & curr_pose = autoware_universe_utils::getPose(points.at(i));
const auto & next_pose = autoware_universe_utils::getPose(points.at(i + 1));
const double length = autoware_universe_utils::calcDistance3d(curr_pose, next_pose);
const auto & curr_pose = autoware::universe_utils::getPose(points.at(i));
const auto & next_pose = autoware::universe_utils::getPose(points.at(i + 1));
const double length = autoware::universe_utils::calcDistance3d(curr_pose, next_pose);
if (accumulated_length + length > target_length) {
const double ratio = (target_length - accumulated_length) / std::max(length, 1e-6);
return autoware_universe_utils::calcInterpolatedPose(curr_pose, next_pose, ratio);
return autoware::universe_utils::calcInterpolatedPose(curr_pose, next_pose, ratio);
}
accumulated_length += length;
}

return autoware_universe_utils::getPose(points.back());
return autoware::universe_utils::getPose(points.back());
}

} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__INTERPOLATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include <optional>
#include <utility>
namespace autoware_motion_utils
namespace autoware::motion_utils
{
std::optional<std::pair<size_t, size_t>> getPathIndexRangeWithLaneId(
const tier4_planning_msgs::msg::PathWithLaneId & path, const int64_t target_lane_id);
Expand All @@ -41,6 +41,6 @@ size_t findNearestSegmentIndexFromLaneId(
tier4_planning_msgs::msg::PathWithLaneId convertToRearWheelCenter(
const tier4_planning_msgs::msg::PathWithLaneId & path, const double rear_to_cog,
const bool enable_last_point_compensation = true);
} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__PATH_WITH_LANE_ID_HPP_
Loading
Loading