Skip to content

Commit e459f09

Browse files
authoredApr 11, 2024
feat(static_centerline_optimizer): generate centerline from ego's trajectory in bag (#6788)
* implement bag_ego_trajectory_based_centerline Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent a06122c commit e459f09

18 files changed

+491
-231
lines changed
 

‎planning/route_handler/include/route_handler/route_handler.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -354,6 +354,7 @@ class RouteHandler
354354
const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * right_lanelet) const;
355355
lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const;
356356
bool isPreferredLane(const lanelet::ConstLanelet & lanelet) const;
357+
lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const;
357358

358359
private:
359360
// MUST

‎planning/route_handler/src/route_handler.cpp

+7
Original file line numberDiff line numberDiff line change
@@ -2286,4 +2286,11 @@ bool RouteHandler::findDrivableLanePath(
22862286
return drivable_lane_path_found;
22872287
}
22882288

2289+
lanelet::ConstLanelets RouteHandler::getClosestLanelets(
2290+
const geometry_msgs::msg::Pose & target_pose) const
2291+
{
2292+
lanelet::ConstLanelets target_lanelets;
2293+
lanelet::utils::query::getCurrentLanelets(road_lanelets_, target_pose, &target_lanelets);
2294+
return target_lanelets;
2295+
}
22892296
} // namespace route_handler

‎planning/static_centerline_optimizer/CMakeLists.txt

+2
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,8 @@ autoware_package()
2222
ament_auto_add_executable(main
2323
src/main.cpp
2424
src/static_centerline_optimizer_node.cpp
25+
src/centerline_source/optimization_trajectory_based_centerline.cpp
26+
src/centerline_source/bag_ego_trajectory_based_centerline.cpp
2527
src/utils.cpp
2628
)
2729

Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/**:
22
ros__parameters:
3-
centerline_source: "optimization_trajectory_base" # select from "optimization_trajectory_base" and "bag_ego_trajectory_base"
43
marker_color: ["FF0000", "00FF00", "0000FF"]
54
marker_color_dist_thresh : [0.1, 0.2, 0.3]
5+
output_trajectory_interval: 1.0
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
16+
#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
17+
18+
#include "rclcpp/rclcpp.hpp"
19+
#include "static_centerline_optimizer/type_alias.hpp"
20+
21+
#include <memory>
22+
#include <string>
23+
#include <vector>
24+
25+
namespace static_centerline_optimizer
26+
{
27+
std::vector<TrajectoryPoint> generate_centerline_with_bag(rclcpp::Node & node);
28+
} // namespace static_centerline_optimizer
29+
#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,45 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
16+
#define STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
17+
18+
#include "rclcpp/rclcpp.hpp"
19+
#include "static_centerline_optimizer/type_alias.hpp"
20+
21+
#include <memory>
22+
#include <string>
23+
#include <vector>
24+
25+
namespace static_centerline_optimizer
26+
{
27+
class OptimizationTrajectoryBasedCenterline
28+
{
29+
public:
30+
OptimizationTrajectoryBasedCenterline() = default;
31+
explicit OptimizationTrajectoryBasedCenterline(rclcpp::Node & node);
32+
std::vector<TrajectoryPoint> generate_centerline_with_optimization(
33+
rclcpp::Node & node, const RouteHandler & route_handler,
34+
const std::vector<lanelet::Id> & route_lane_ids);
35+
36+
private:
37+
std::vector<TrajectoryPoint> optimize_trajectory(const Path & raw_path) const;
38+
39+
rclcpp::Publisher<PathWithLaneId>::SharedPtr pub_raw_path_with_lane_id_{nullptr};
40+
rclcpp::Publisher<Path>::SharedPtr pub_raw_path_{nullptr};
41+
};
42+
} // namespace static_centerline_optimizer
43+
// clang-format off
44+
#endif // STATIC_CENTERLINE_OPTIMIZER__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
45+
// clang-format on

‎planning/static_centerline_optimizer/include/static_centerline_optimizer/static_centerline_optimizer_node.hpp

+14-12
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_
1717

1818
#include "rclcpp/rclcpp.hpp"
19+
#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp"
1920
#include "static_centerline_optimizer/srv/load_map.hpp"
2021
#include "static_centerline_optimizer/srv/plan_path.hpp"
2122
#include "static_centerline_optimizer/srv/plan_route.hpp"
@@ -25,6 +26,7 @@
2526
#include <geography_utils/lanelet2_projector.hpp>
2627

2728
#include "std_msgs/msg/bool.hpp"
29+
#include "std_msgs/msg/float32.hpp"
2830
#include "std_msgs/msg/int32.hpp"
2931

3032
#include <memory>
@@ -37,18 +39,19 @@ using static_centerline_optimizer::srv::LoadMap;
3739
using static_centerline_optimizer::srv::PlanPath;
3840
using static_centerline_optimizer::srv::PlanRoute;
3941

42+
struct CenterlineWithRoute
43+
{
44+
std::vector<TrajectoryPoint> centerline{};
45+
std::vector<lanelet::Id> route_lane_ids{};
46+
};
47+
4048
class StaticCenterlineOptimizerNode : public rclcpp::Node
4149
{
4250
public:
4351
explicit StaticCenterlineOptimizerNode(const rclcpp::NodeOptions & node_options);
4452
void run();
4553

4654
private:
47-
struct CenterlineWithRoute
48-
{
49-
std::vector<TrajectoryPoint> centerline{};
50-
std::vector<lanelet::Id> route_lane_ids{};
51-
};
5255
// load map
5356
void load_map(const std::string & lanelet2_input_file_path);
5457
void on_load_map(
@@ -60,13 +63,12 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node
6063
void on_plan_route(
6164
const PlanRoute::Request::SharedPtr request, const PlanRoute::Response::SharedPtr response);
6265

63-
// plan path
66+
// plan centerline
6467
CenterlineWithRoute generate_centerline_with_route();
65-
std::vector<TrajectoryPoint> plan_path(const std::vector<lanelet::Id> & route_lane_ids);
66-
std::vector<TrajectoryPoint> optimize_trajectory(const Path & raw_path) const;
6768
void on_plan_path(
6869
const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response);
6970

71+
void update_centerline_range(const int traj_start_index, const int traj_end_index);
7072
void evaluate(
7173
const std::vector<lanelet::Id> & route_lane_ids,
7274
const std::vector<TrajectoryPoint> & optimized_traj_points);
@@ -88,19 +90,19 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node
8890
BagEgoTrajectoryBase,
8991
};
9092
CenterlineSource centerline_source_;
93+
OptimizationTrajectoryBasedCenterline optimization_trajectory_based_centerline_;
9194

9295
// publisher
9396
rclcpp::Publisher<HADMapBin>::SharedPtr pub_map_bin_{nullptr};
94-
rclcpp::Publisher<PathWithLaneId>::SharedPtr pub_raw_path_with_lane_id_{nullptr};
95-
rclcpp::Publisher<Path>::SharedPtr pub_raw_path_{nullptr};
9697
rclcpp::Publisher<MarkerArray>::SharedPtr pub_debug_unsafe_footprints_{nullptr};
97-
rclcpp::Publisher<Trajectory>::SharedPtr pub_whole_optimized_centerline_{nullptr};
98-
rclcpp::Publisher<Trajectory>::SharedPtr pub_optimized_centerline_{nullptr};
98+
rclcpp::Publisher<Trajectory>::SharedPtr pub_whole_centerline_{nullptr};
99+
rclcpp::Publisher<Trajectory>::SharedPtr pub_centerline_{nullptr};
99100

100101
// subscriber
101102
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr sub_traj_start_index_;
102103
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr sub_traj_end_index_;
103104
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr sub_save_map_;
105+
rclcpp::Subscription<std_msgs::msg::Float32>::SharedPtr sub_traj_resample_interval_;
104106

105107
// service
106108
rclcpp::Service<LoadMap>::SharedPtr srv_load_map_;

‎planning/static_centerline_optimizer/include/static_centerline_optimizer/utils.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,9 @@ namespace static_centerline_optimizer
2828
{
2929
namespace utils
3030
{
31+
lanelet::ConstLanelets get_lanelets_from_ids(
32+
const RouteHandler & route_handler, const std::vector<lanelet::Id> & lane_ids);
33+
3134
geometry_msgs::msg::Pose get_center_pose(
3235
const RouteHandler & route_handler, const size_t lanelet_id);
3336

‎planning/static_centerline_optimizer/launch/static_centerline_optimizer.launch.xml

+5
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@
55
<!-- flag -->
66
<arg name="run_background" default="false"/>
77
<arg name="rviz" default="true"/>
8+
<!-- <arg name="centerline_source" default="optimization_trajectory_base" description="select from optimization_trajectory_base and bag_ego_trajectory_base"/> -->
9+
<arg name="centerline_source" default="bag_ego_trajectory_base" description="select from optimization_trajectory_base and bag_ego_trajectory_base"/>
10+
<arg name="bag_filename" default="bag.db3"/>
811

912
<!-- mandatory arguments when run_background is true -->
1013
<arg name="lanelet2_input_file_path" default=""/>
@@ -78,6 +81,8 @@
7881
<param from="$(var mission_planner_param)"/>
7982
<!-- node param -->
8083
<param from="$(find-pkg-share static_centerline_optimizer)/config/static_centerline_optimizer.param.yaml"/>
84+
<param name="centerline_source" value="$(var centerline_source)"/>
85+
<param name="bag_filename" value="$(var bag_filename)"/>
8186
</node>
8287

8388
<!-- rviz -->
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
#!/bin/bash
2+
3+
ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_optimizer --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
#!/bin/bash
2+
3+
ros2 launch static_centerline_optimizer static_centerline_optimizer.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus

‎planning/static_centerline_optimizer/scripts/tmp/run.sh

-3
This file was deleted.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "static_centerline_optimizer/centerline_source/bag_ego_trajectory_based_centerline.hpp"
16+
17+
#include "rclcpp/serialization.hpp"
18+
#include "rosbag2_cpp/reader.hpp"
19+
#include "static_centerline_optimizer/static_centerline_optimizer_node.hpp"
20+
21+
#include <nav_msgs/msg/odometry.hpp>
22+
23+
namespace static_centerline_optimizer
24+
{
25+
std::vector<TrajectoryPoint> generate_centerline_with_bag(rclcpp::Node & node)
26+
{
27+
const auto bag_filename = node.declare_parameter<std::string>("bag_filename");
28+
29+
rosbag2_cpp::Reader bag_reader;
30+
bag_reader.open(bag_filename);
31+
32+
rclcpp::Serialization<nav_msgs::msg::Odometry> bag_serialization;
33+
std::vector<TrajectoryPoint> centerline_traj_points;
34+
while (bag_reader.has_next()) {
35+
const rosbag2_storage::SerializedBagMessageSharedPtr msg = bag_reader.read_next();
36+
37+
if (msg->topic_name != "/localization/kinematic_state") {
38+
continue;
39+
}
40+
41+
rclcpp::SerializedMessage serialized_msg(*msg->serialized_data);
42+
const auto ros_msg = std::make_shared<nav_msgs::msg::Odometry>();
43+
44+
bag_serialization.deserialize_message(&serialized_msg, ros_msg.get());
45+
46+
if (!centerline_traj_points.empty()) {
47+
constexpr double epsilon = 1e-1;
48+
if (
49+
std::abs(centerline_traj_points.back().pose.position.x - ros_msg->pose.pose.position.x) <
50+
epsilon &&
51+
std::abs(centerline_traj_points.back().pose.position.y - ros_msg->pose.pose.position.y) <
52+
epsilon) {
53+
continue;
54+
}
55+
}
56+
TrajectoryPoint centerline_traj_point;
57+
centerline_traj_point.pose.position = ros_msg->pose.pose.position;
58+
// std::cerr << centerline_traj_point.pose.position.x << " "
59+
// << centerline_traj_point.pose.position.y << std::endl;
60+
centerline_traj_points.push_back(centerline_traj_point);
61+
}
62+
63+
RCLCPP_INFO(node.get_logger(), "Extracted centerline from the bag.");
64+
65+
// calculate rough orientation of centerline trajectory points
66+
for (size_t i = 0; i < centerline_traj_points.size(); ++i) {
67+
if (i == centerline_traj_points.size() - 1) {
68+
if (i != 0) {
69+
centerline_traj_points.at(i).pose.orientation =
70+
centerline_traj_points.at(i - 1).pose.orientation;
71+
}
72+
} else {
73+
const double yaw_angle = tier4_autoware_utils::calcAzimuthAngle(
74+
centerline_traj_points.at(i).pose.position, centerline_traj_points.at(i + 1).pose.position);
75+
centerline_traj_points.at(i).pose.orientation =
76+
tier4_autoware_utils::createQuaternionFromYaw(yaw_angle);
77+
}
78+
}
79+
80+
return centerline_traj_points;
81+
}
82+
} // namespace static_centerline_optimizer

0 commit comments

Comments
 (0)
Please sign in to comment.