Skip to content

Commit

Permalink
feat(obstacle_cruise_planner): remove include directory
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <[email protected]>
  • Loading branch information
takayuki5168 committed Jun 17, 2024
1 parent 89b3233 commit bd4be72
Show file tree
Hide file tree
Showing 21 changed files with 81 additions and 71 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
#ifndef COMMON_STRUCTS_HPP_
#define COMMON_STRUCTS_HPP_

#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "motion_utils/trajectory/conversion.hpp"
#include "motion_utils/trajectory/interpolation.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
#include "tier4_autoware_utils/ros/update_param.hpp"
#include "tier4_autoware_utils/ros/uuid_helper.hpp"
#include "type_alias.hpp"

#include <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -302,4 +302,4 @@ struct EgoNearestParam
double yaw_threshold;
};

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
#endif // COMMON_STRUCTS_HPP_
8 changes: 5 additions & 3 deletions planning/autoware_obstacle_cruise_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,21 +12,23 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware_obstacle_cruise_planner/node.hpp"
#include "node.hpp"

#include "autoware_obstacle_cruise_planner/polygon_utils.hpp"
#include "autoware_obstacle_cruise_planner/utils.hpp"
#include "motion_utils/resample/resample.hpp"
#include "motion_utils/trajectory/conversion.hpp"
#include "object_recognition_utils/predicted_path_utils.hpp"
#include "polygon_utils.hpp"
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
#include "tier4_autoware_utils/ros/update_param.hpp"
#include "utils.hpp"

#include <boost/format.hpp>

#include <algorithm>
#include <chrono>
#include <limits>
#include <utility>

namespace
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,17 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__NODE_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__NODE_HPP_
#ifndef NODE_HPP_
#define NODE_HPP_

#include "autoware_obstacle_cruise_planner/common_structs.hpp"
#include "autoware_obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
#include "autoware_obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "common_structs.hpp"
#include "optimization_based_planner/optimization_based_planner.hpp"
#include "pid_based_planner/pid_based_planner.hpp"
#include "signal_processing/lowpass_filter_1d.hpp"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
#include "tier4_autoware_utils/system/stop_watch.hpp"
#include "type_alias.hpp"

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
Expand Down Expand Up @@ -280,4 +280,4 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
};
} // namespace autoware::motion_planning

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__NODE_HPP_
#endif // NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware_obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
#include "optimization_based_planner/optimization_based_planner.hpp"

#include "autoware_obstacle_cruise_planner/utils.hpp"
#include "interpolation/linear_interpolation.hpp"
#include "interpolation/spline_interpolation.hpp"
#include "interpolation/zero_order_hold.hpp"
Expand All @@ -24,6 +23,7 @@
#include "motion_utils/trajectory/trajectory.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
#include "utils.hpp"

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
Expand All @@ -33,6 +33,9 @@

#include <tf2/utils.h>

#include <algorithm>
#include <limits>

constexpr double ZERO_VEL_THRESHOLD = 0.01;
constexpr double CLOSE_S_DIST_THRESHOLD = 1e-3;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
#ifndef OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
#define OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT

#include "autoware_obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
#include "autoware_obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp"
#include "autoware_obstacle_cruise_planner/planner_interface.hpp"
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "optimization_based_planner/s_boundary.hpp"
#include "optimization_based_planner/velocity_optimizer.hpp"
#include "planner_interface.hpp"
#include "type_alias.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
Expand Down Expand Up @@ -118,5 +118,5 @@ class OptimizationBasedPlanner : public PlannerInterface
double stop_dist_to_prohibit_engage_;
};
// clang-format off
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
#endif // OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
// clang-format on
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
#ifndef OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
#define OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_

#include <limits>
#include <vector>
Expand All @@ -30,4 +30,4 @@ class SBoundary

using SBoundaries = std::vector<SBoundary>;

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
#endif // OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware_obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp"
#include "optimization_based_planner/velocity_optimizer.hpp"

#include <Eigen/Core>

#include <algorithm>
#include <iostream>

VelocityOptimizer::VelocityOptimizer(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,10 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
#ifndef OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
#define OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_

#include "autoware_obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
#include "optimization_based_planner/s_boundary.hpp"
#include "osqp_interface/osqp_interface.hpp"

#include <vector>
Expand Down Expand Up @@ -72,4 +72,4 @@ class VelocityOptimizer
autoware::common::osqp::OSQPInterface qp_solver_;
};

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
#endif // OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
#ifndef PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
#define PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_

#include <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -94,4 +94,4 @@ class CruisePlanningDebugInfo
std::array<double, static_cast<int>(TYPE::SIZE)> info_;
};

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
#endif // PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,19 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware_obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
#include "pid_based_planner/pid_based_planner.hpp"

#include "autoware_obstacle_cruise_planner/utils.hpp"
#include "interpolation/spline_interpolation.hpp"
#include "motion_utils/marker/marker_helper.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
#include "tier4_autoware_utils/ros/update_param.hpp"
#include "utils.hpp"

#include "tier4_planning_msgs/msg/velocity_limit.hpp"

#include <algorithm>
#include <string>
namespace
{
VelocityLimit createVelocityLimitMsg(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
#ifndef PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
#define PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_

#include "autoware_obstacle_cruise_planner/pid_based_planner/cruise_planning_debug_info.hpp"
#include "autoware_obstacle_cruise_planner/pid_based_planner/pid_controller.hpp"
#include "autoware_obstacle_cruise_planner/planner_interface.hpp"
#include "pid_based_planner/cruise_planning_debug_info.hpp"
#include "pid_based_planner/pid_controller.hpp"
#include "planner_interface.hpp"
#include "signal_processing/lowpass_filter_1d.hpp"

#include "visualization_msgs/msg/marker_array.hpp"
Expand Down Expand Up @@ -137,4 +137,4 @@ class PIDBasedPlanner : public PlannerInterface
std::function<double(double)> error_func_;
};

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
#endif // PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
#ifndef PID_BASED_PLANNER__PID_CONTROLLER_HPP_
#define PID_BASED_PLANNER__PID_CONTROLLER_HPP_

#include <optional>

Expand Down Expand Up @@ -59,4 +59,4 @@ class PIDController
std::optional<double> prev_error_;
};

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
#endif // PID_BASED_PLANNER__PID_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware_obstacle_cruise_planner/planner_interface.hpp"
#include "planner_interface.hpp"

#include "motion_utils/distance/distance.hpp"
#include "motion_utils/marker/marker_helper.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
#ifndef PLANNER_INTERFACE_HPP_
#define PLANNER_INTERFACE_HPP_

#include "autoware_obstacle_cruise_planner/common_structs.hpp"
#include "autoware_obstacle_cruise_planner/stop_planning_debug_info.hpp"
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "autoware_obstacle_cruise_planner/utils.hpp"
#include "common_structs.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "stop_planning_debug_info.hpp"
#include "tier4_autoware_utils/ros/update_param.hpp"
#include "tier4_autoware_utils/system/stop_watch.hpp"
#include "type_alias.hpp"
#include "utils.hpp"

#include <algorithm>
#include <limits>
Expand Down Expand Up @@ -425,4 +425,4 @@ class PlannerInterface
std::nullopt};
};

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
#endif // PLANNER_INTERFACE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware_obstacle_cruise_planner/polygon_utils.hpp"
#include "polygon_utils.hpp"

#include "motion_utils/trajectory/trajectory.hpp"
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"

#include <algorithm>

namespace
{
PointWithStamp calcNearestCollisionPoint(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
#ifndef POLYGON_UTILS_HPP_
#define POLYGON_UTILS_HPP_

#include "autoware_obstacle_cruise_planner/common_structs.hpp"
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "common_structs.hpp"
#include "tier4_autoware_utils/geometry/boost_geometry.hpp"
#include "type_alias.hpp"

#include <boost/geometry.hpp>

Expand Down Expand Up @@ -52,4 +52,4 @@ std::vector<PointWithStamp> getCollisionPoints(

} // namespace polygon_utils

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
#endif // POLYGON_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
#ifndef STOP_PLANNING_DEBUG_INFO_HPP_
#define STOP_PLANNING_DEBUG_INFO_HPP_

#include <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -85,4 +85,4 @@ class StopPlanningDebugInfo
std::array<double, static_cast<int>(TYPE::SIZE)> info_;
};

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
#endif // STOP_PLANNING_DEBUG_INFO_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
#ifndef TYPE_ALIAS_HPP_
#define TYPE_ALIAS_HPP_

#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"

Expand Down Expand Up @@ -63,4 +63,4 @@ namespace bg = boost::geometry;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;

#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
#endif // TYPE_ALIAS_HPP_
2 changes: 1 addition & 1 deletion planning/autoware_obstacle_cruise_planner/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware_obstacle_cruise_planner/utils.hpp"
#include "utils.hpp"

#include "object_recognition_utils/predicted_path_utils.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
Expand Down
Loading

0 comments on commit bd4be72

Please sign in to comment.