Skip to content

Commit

Permalink
refactor(motion_utils)!: add autoware prefix and include dir
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

style(pre-commit): autofix
  • Loading branch information
kosuke55 committed Jun 18, 2024
1 parent 84be455 commit 32fffc4
Show file tree
Hide file tree
Showing 9 changed files with 20 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <Eigen/Core>
#include <Eigen/Geometry>
#include <motion_utils/trajectory/trajectory.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_planning_msgs/msg/trajectory.hpp>
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_debug_tools/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,10 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_motion_utils</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2_ros</depend>
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_debug_tools/src/lateral_error_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ void LateralErrorPublisher::onGroundTruthPose(
}

// Search closest trajectory point with vehicle pose
const auto closest_index = motion_utils::findNearestIndex(
const auto closest_index = autoware_motion_utils::findNearestIndex(
current_trajectory_ptr_->points, current_vehicle_pose_ptr_->pose.pose,
std::numeric_limits<double>::max(), yaw_threshold_to_search_closest_);
if (!closest_index) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ Planning:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: behavior_path_planner.path_shifter
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: motion_utils
logger_name: autoware_motion_utils

behavior_path_planner_avoidance:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
Expand Down Expand Up @@ -74,7 +74,7 @@ Planning:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner
logger_name: motion_utils
logger_name: autoware_motion_utils

behavior_velocity_planner_intersection:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner
Expand All @@ -86,15 +86,15 @@ Planning:
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
logger_name: motion_utils
logger_name: autoware_motion_utils

motion_velocity_smoother:
- node_name: /planning/scenario_planning/motion_velocity_smoother
logger_name: planning.scenario_planning.motion_velocity_smoother
- node_name: /planning/scenario_planning/motion_velocity_smoother
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/motion_velocity_smoother
logger_name: motion_utils
logger_name: autoware_motion_utils

route_handler:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
Expand All @@ -110,15 +110,15 @@ Control:
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: autoware_universe_utils
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: motion_utils
logger_name: autoware_motion_utils

longitudinal_controller:
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: control.trajectory_follower.controller_node_exe.longitudinal_controller
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: autoware_universe_utils
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: motion_utils
logger_name: autoware_motion_utils

vehicle_cmd_gate:
- node_name: /control/vehicle_cmd_gate
Expand Down
2 changes: 1 addition & 1 deletion driving_environment_analyzer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_behavior_path_planner_common</depend>
<depend>autoware_lane_departure_checker</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_route_handler</depend>
Expand All @@ -29,7 +30,6 @@
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
<depend>libqt5-widgets</depend>
<depend>motion_utils</depend>
<depend>qtbase5-dev</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
10 changes: 5 additions & 5 deletions driving_environment_analyzer/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "driving_environment_analyzer/utils.hpp"

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

#include <lanelet2_extension/regulatory_elements/Forward.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
Expand Down Expand Up @@ -79,7 +79,7 @@ double calcElevationAngle(const lanelet::ConstLanelet & lane, const Pose & pose)
return 0.0;
}

const size_t idx = motion_utils::findNearestSegmentIndex(points, pose.position);
const size_t idx = autoware_motion_utils::findNearestSegmentIndex(points, pose.position);

const auto p1 = autoware_universe_utils::getPoint(points.at(idx));
const auto p2 = autoware_universe_utils::getPoint(points.at(idx + 1));
Expand All @@ -96,7 +96,7 @@ double getLaneWidth(const lanelet::ConstLanelet & lane)
return points;
};

const auto lon_length = motion_utils::calcArcLength(to_ros_msg(lane.centerline()));
const auto lon_length = autoware_motion_utils::calcArcLength(to_ros_msg(lane.centerline()));
return boost::geometry::area(lane.polygon2d().basicPolygon()) / lon_length;
}

Expand All @@ -118,7 +118,7 @@ double getMaxCurvature(const lanelet::ConstLanelets & lanes)
double max_value = 0.0;

for (const auto & lane : lanes) {
const auto values = motion_utils::calcCurvature(to_ros_msg(lane.centerline()));
const auto values = autoware_motion_utils::calcCurvature(to_ros_msg(lane.centerline()));
const auto max_value_itr = std::max_element(values.begin(), values.end());
if (max_value_itr == values.end()) {
continue;
Expand Down Expand Up @@ -146,7 +146,7 @@ std::pair<double, double> getLaneWidth(const lanelet::ConstLanelets & lanes)
double max_value = 0.0;

for (const auto & lane : lanes) {
const auto lon_length = motion_utils::calcArcLength(to_ros_msg(lane.centerline()));
const auto lon_length = autoware_motion_utils::calcArcLength(to_ros_msg(lane.centerline()));
const auto width = boost::geometry::area(lane.polygon2d().basicPolygon()) / lon_length;

if (min_value > width) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef PLANNING_DEBUG_TOOLS__TRAJECTORY_ANALYZER_HPP_
#define PLANNING_DEBUG_TOOLS__TRAJECTORY_ANALYZER_HPP_

#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "planning_debug_tools/msg/trajectory_debug_info.hpp"
#include "planning_debug_tools/util.hpp"
#include "rclcpp/rclcpp.hpp"
Expand Down Expand Up @@ -86,8 +86,8 @@ class TrajectoryAnalyzer
TrajectoryDebugInfo data;
data.stamp = node_->now();
data.size = points.size();
data.curvature = motion_utils::calcCurvature(points);
const auto arclength_offset = motion_utils::calcSignedArcLength(points, 0, ego_p);
data.curvature = autoware_motion_utils::calcCurvature(points);
const auto arclength_offset = autoware_motion_utils::calcSignedArcLength(points, 0, ego_p);
data.arclength = calcPathArcLengthArray(points, -arclength_offset);
data.velocity = getVelocityArray(points);
data.acceleration = getAccelerationArray(points);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef PLANNING_DEBUG_TOOLS__UTIL_HPP_
#define PLANNING_DEBUG_TOOLS__UTIL_HPP_

#include "autoware/motion_utils/trajectory/trajectory.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "rclcpp/rclcpp.hpp"

#include "autoware_planning_msgs/msg/path.hpp"
Expand Down
2 changes: 1 addition & 1 deletion planning/planning_debug_tools/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@

<build_depend>rosidl_default_generators</build_depend>

<depend>autoware_motion_utils</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
<depend>nav_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down

0 comments on commit 32fffc4

Please sign in to comment.