Skip to content

Commit

Permalink
refactor(motion_utils): add autoware namespace
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 committed Jun 20, 2024
1 parent e580454 commit 4a11c10
Show file tree
Hide file tree
Showing 227 changed files with 1,217 additions and 1,199 deletions.
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,7 +42,7 @@ 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();
}

Expand Down Expand Up @@ -105,10 +105,10 @@ bool validate_arguments(const T & input_points, const double resampling_interval
}

// 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::motion_utils::overlap_threshold);
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 @@ -91,6 +91,6 @@ geometry_msgs::msg::Pose calcInterpolatedPose(const T & points, const double tar
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_
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
#include <utility>
#include <vector>

namespace autoware_motion_utils
namespace autoware::motion_utils
{
static inline rclcpp::Logger get_logger()
{
Expand Down Expand Up @@ -1788,7 +1788,7 @@ std::optional<size_t> insertStopPoint(
const size_t stop_seg_idx, const geometry_msgs::msg::Point & stop_point, T & points_with_twist,
const double overlap_threshold = 1e-3)
{
const auto insert_idx = autoware_motion_utils::insertTargetPoint(
const auto insert_idx = autoware::motion_utils::insertTargetPoint(
stop_seg_idx, stop_point, points_with_twist, overlap_threshold);

if (!insert_idx) {
Expand Down Expand Up @@ -2231,13 +2231,13 @@ std::optional<double> calcDistanceToForwardStopPoint(
}

const auto nearest_segment_idx =
autoware_motion_utils::findNearestSegmentIndex(points_with_twist, pose, max_dist, max_yaw);
autoware::motion_utils::findNearestSegmentIndex(points_with_twist, pose, max_dist, max_yaw);

if (!nearest_segment_idx) {
return std::nullopt;
}

const auto stop_idx = autoware_motion_utils::searchZeroVelocityIndex(
const auto stop_idx = autoware::motion_utils::searchZeroVelocityIndex(
points_with_twist, *nearest_segment_idx + 1, points_with_twist.size());

if (!stop_idx) {
Expand Down Expand Up @@ -2278,7 +2278,7 @@ T cropForwardPoints(
}

double sum_length =
-autoware_motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos);
-autoware::motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos);
for (size_t i = target_seg_idx + 1; i < points.size(); ++i) {
sum_length += autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1));
if (forward_length < sum_length) {
Expand Down Expand Up @@ -2318,7 +2318,7 @@ T cropBackwardPoints(
}

double sum_length =
-autoware_motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos);
-autoware::motion_utils::calcLongitudinalOffsetToSegment(points, target_seg_idx, target_pos);
for (int i = target_seg_idx; 0 < i; --i) {
sum_length -= autoware::universe_utils::calcDistance2d(points.at(i), points.at(i - 1));
if (sum_length < -backward_length) {
Expand Down Expand Up @@ -2487,6 +2487,6 @@ extern template bool isTargetPointFront<std::vector<autoware_planning_msgs::msg:
const geometry_msgs::msg::Point & base_point, const geometry_msgs::msg::Point & target_point,
const double threshold = 0.0);

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

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

#include <deque>

namespace autoware_motion_utils
namespace autoware::motion_utils
{

using autoware_planning_msgs::msg::Trajectory;
Expand Down Expand Up @@ -77,6 +77,6 @@ class VehicleArrivalChecker : public VehicleStopChecker

void onTrajectory(const Trajectory::ConstSharedPtr msg);
};
} // namespace autoware_motion_utils
} // namespace autoware::motion_utils

#endif // AUTOWARE__MOTION_UTILS__VEHICLE__VEHICLE_STATE_CHECKER_HPP_
4 changes: 2 additions & 2 deletions common/autoware_motion_utils/src/distance/distance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "autoware/motion_utils/distance/distance.hpp"

namespace autoware_motion_utils
namespace autoware::motion_utils
{
namespace
{
Expand Down Expand Up @@ -269,4 +269,4 @@ std::optional<double> calcDecelDistWithJerkAndAccConstraints(

return calcDecelDistPlanType3(current_vel, target_vel, current_acc, jerk_acc);
}
} // namespace autoware_motion_utils
} // namespace autoware::motion_utils
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
#include <tier4_planning_msgs/msg/path_point_with_lane_id.hpp>

namespace autoware_motion_utils
namespace autoware::motion_utils
{
template <class PointType>
void VelocityFactorInterface::set(
Expand All @@ -31,7 +31,7 @@ void VelocityFactorInterface::set(
velocity_factor_.behavior = behavior_;
velocity_factor_.pose = stop_pose;
velocity_factor_.distance =
static_cast<float>(autoware_motion_utils::calcSignedArcLength(points, curr_point, stop_point));
static_cast<float>(autoware::motion_utils::calcSignedArcLength(points, curr_point, stop_point));
velocity_factor_.status = status;
velocity_factor_.detail = detail;
}
Expand All @@ -46,4 +46,4 @@ template void VelocityFactorInterface::set<autoware_planning_msgs::msg::Trajecto
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> &, const Pose &, const Pose &,
const VelocityFactorStatus, const std::string &);

} // namespace autoware_motion_utils
} // namespace autoware::motion_utils
4 changes: 2 additions & 2 deletions common/autoware_motion_utils/src/marker/marker_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ inline visualization_msgs::msg::MarkerArray createDeletedVirtualWallMarkerArray(
}
} // namespace

namespace autoware_motion_utils
namespace autoware::motion_utils
{
visualization_msgs::msg::MarkerArray createStopVirtualWallMarker(
const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now,
Expand Down Expand Up @@ -140,4 +140,4 @@ visualization_msgs::msg::MarkerArray createDeletedDeadLineVirtualWallMarker(
{
return createDeletedVirtualWallMarkerArray("dead_line_", now, id);
}
} // namespace autoware_motion_utils
} // namespace autoware::motion_utils
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "autoware/motion_utils/marker/marker_helper.hpp"

namespace autoware_motion_utils
namespace autoware::motion_utils
{

void VirtualWallMarkerCreator::cleanup()
Expand Down Expand Up @@ -55,13 +55,13 @@ visualization_msgs::msg::MarkerArray VirtualWallMarkerCreator::create_markers(
for (const auto & virtual_wall : virtual_walls_) {
switch (virtual_wall.style) {
case stop:
create_fn = autoware_motion_utils::createStopVirtualWallMarker;
create_fn = autoware::motion_utils::createStopVirtualWallMarker;
break;
case slowdown:
create_fn = autoware_motion_utils::createSlowDownVirtualWallMarker;
create_fn = autoware::motion_utils::createSlowDownVirtualWallMarker;
break;
case deadline:
create_fn = autoware_motion_utils::createDeadLineVirtualWallMarker;
create_fn = autoware::motion_utils::createDeadLineVirtualWallMarker;
break;
}
auto markers = create_fn(
Expand All @@ -85,4 +85,4 @@ visualization_msgs::msg::MarkerArray VirtualWallMarkerCreator::create_markers(
cleanup();
return marker_array;
}
} // namespace autoware_motion_utils
} // namespace autoware::motion_utils
Loading

0 comments on commit 4a11c10

Please sign in to comment.