Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Apr 16, 2024
1 parent 1ae1873 commit 99906b7
Show file tree
Hide file tree
Showing 6 changed files with 139 additions and 150 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef \
STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
#define \
STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_
STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_
STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT

#include "rclcpp/rclcpp.hpp"
#include "route_handler/route_handler.hpp"
Expand All @@ -27,27 +27,27 @@

#include <vector>

namespace autoware::static_centerline_generator
namespace autoware::static_centerline_generator
{
using ::autoware_auto_planning_msgs::msg::Path;
using ::autoware_auto_planning_msgs::msg::PathWithLaneId;
using ::autoware_auto_planning_msgs::msg::TrajectoryPoint;
using ::route_handler::RouteHandler;
class OptimizationTrajectoryBasedCenterline
{
public:
OptimizationTrajectoryBasedCenterline() = default;
explicit OptimizationTrajectoryBasedCenterline(rclcpp::Node & node);
std::vector<TrajectoryPoint> generate_centerline_with_optimization(
rclcpp::Node & node, const RouteHandler & route_handler,
const std::vector<lanelet::Id> & route_lane_ids);
using ::autoware_auto_planning_msgs::msg::Path;
using ::autoware_auto_planning_msgs::msg::PathWithLaneId;
using ::autoware_auto_planning_msgs::msg::TrajectoryPoint;
using ::route_handler::RouteHandler;
class OptimizationTrajectoryBasedCenterline
{
public:
OptimizationTrajectoryBasedCenterline() = default;
explicit OptimizationTrajectoryBasedCenterline(rclcpp::Node & node);
std::vector<TrajectoryPoint> generate_centerline_with_optimization(
rclcpp::Node & node, const RouteHandler & route_handler,
const std::vector<lanelet::Id> & route_lane_ids);

private:
[[nodiscard]] static std::vector<TrajectoryPoint> optimize_trajectory(const Path & raw_path);
private:
[[nodiscard]] static std::vector<TrajectoryPoint> optimize_trajectory(const Path & raw_path);

rclcpp::Publisher<PathWithLaneId>::SharedPtr pub_raw_path_with_lane_id_{nullptr};
rclcpp::Publisher<Path>::SharedPtr pub_raw_path_{nullptr};
};
rclcpp::Publisher<PathWithLaneId>::SharedPtr pub_raw_path_with_lane_id_{nullptr};
rclcpp::Publisher<Path>::SharedPtr pub_raw_path_{nullptr};
};
} // namespace autoware::static_centerline_generator
// clang-format off
#endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,7 @@
#include "autoware_static_centerline_generator/srv/plan_path.hpp"
#include "autoware_static_centerline_generator/srv/plan_route.hpp"
#include "rclcpp/rclcpp.hpp"
#include \
"static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp"
#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp"
#include "static_centerline_generator/type_alias.hpp"
#include "vehicle_info_util/vehicle_info_util.hpp"

Expand Down Expand Up @@ -90,8 +89,7 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node
std::pair<int, int> traj_range_indices_{0, 0};
std::optional<CenterlineWithRoute> centerline_with_route_{std::nullopt};

enum class CenterlineSource
{
enum class CenterlineSource {
OptimizationTrajectoryBase = 0,
BagEgoTrajectoryBase,
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,9 @@ std::vector<TrajectoryPoint> generate_centerline_with_bag(rclcpp::Node & node)
constexpr double epsilon = 1e-1;
if (
std::abs(centerline_traj_points.back().pose.position.x - ros_msg->pose.pose.position.x) <
epsilon &&
epsilon &&
std::abs(centerline_traj_points.back().pose.position.y - ros_msg->pose.pose.position.y) <
epsilon)
{
epsilon) {
continue;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include \
"static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp"
#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp"

#include "motion_utils/resample/resample.hpp"
#include "motion_utils/trajectory/conversion.hpp"
Expand Down Expand Up @@ -91,19 +90,19 @@ OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization(

// extract path with lane id from lanelets
const auto raw_path_with_lane_id = [&]() {
const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id(
route_handler, route_lanelets, start_center_pose, ego_nearest_dist_threshold,
ego_nearest_yaw_threshold);
return motion_utils::resamplePath(non_resampled_path_with_lane_id, behavior_path_interval);
}();
const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id(
route_handler, route_lanelets, start_center_pose, ego_nearest_dist_threshold,
ego_nearest_yaw_threshold);
return motion_utils::resamplePath(non_resampled_path_with_lane_id, behavior_path_interval);
}();
pub_raw_path_with_lane_id_->publish(raw_path_with_lane_id);
RCLCPP_INFO(node.get_logger(), "Calculated raw path with lane id and published.");

// convert path with lane id to path
const auto raw_path = [&]() {
const auto non_resampled_path = convert_to_path(raw_path_with_lane_id);
return motion_utils::resamplePath(non_resampled_path, behavior_vel_interval);
}();
const auto non_resampled_path = convert_to_path(raw_path_with_lane_id);
return motion_utils::resamplePath(non_resampled_path, behavior_vel_interval);
}();
pub_raw_path_->publish(raw_path);
RCLCPP_INFO(node.get_logger(), "Converted to path and published.");

Expand All @@ -121,9 +120,9 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
{
// convert to trajectory points
const auto raw_traj_points = [&]() {
const auto raw_traj = convert_to_trajectory(raw_path);
return motion_utils::convertToTrajectoryPointArray(raw_traj);
}();
const auto raw_traj = convert_to_trajectory(raw_path);
return motion_utils::convertToTrajectoryPointArray(raw_traj);
}();

// create an instance of elastic band and model predictive trajectory.
const auto eb_path_smoother_ptr =
Expand All @@ -133,25 +132,24 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra

// NOTE: The optimization is executed every valid_optimized_traj_points_num points.
constexpr int valid_optimized_traj_points_num = 10;
const int traj_segment_num = static_cast<int>(raw_traj_points.size()) /
valid_optimized_traj_points_num;
const int traj_segment_num =
static_cast<int>(raw_traj_points.size()) / valid_optimized_traj_points_num;

// NOTE: num_initial_optimization exists to make the both optimizations stable since they may use
// warm start.
constexpr int num_initial_optimization = 2;

std::vector<TrajectoryPoint> whole_optimized_traj_points;
for (int virtual_ego_pose_idx = -num_initial_optimization;
virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx)
{
virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx) {
// calculate virtual ego pose for the optimization
constexpr int virtual_ego_pose_offset_idx = 1;
const auto virtual_ego_pose =
raw_traj_points
.at(
valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) +
virtual_ego_pose_offset_idx)
.pose;
.at(
valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) +
virtual_ego_pose_offset_idx)
.pose;

// smooth trajectory by elastic band in the path_smoother package
const auto smoothed_traj_points =
Expand Down
Loading

0 comments on commit 99906b7

Please sign in to comment.