File tree 8 files changed +25
-29
lines changed
planning/static_centerline_generator/src
8 files changed +25
-29
lines changed Original file line number Diff line number Diff line change 13
13
// limitations under the License.
14
14
15
15
#include " centerline_source/bag_ego_trajectory_based_centerline.hpp"
16
- #include " static_centerline_generator_node.hpp"
17
16
18
17
#include " rclcpp/serialization.hpp"
19
18
#include " rosbag2_cpp/reader.hpp"
19
+ #include " static_centerline_generator_node.hpp"
20
20
21
21
#include < nav_msgs/msg/odometry.hpp>
22
22
Original file line number Diff line number Diff line change 12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
16
- #define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
17
-
18
- #include " type_alias.hpp"
15
+ #ifndef CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
16
+ #define CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
19
17
20
18
#include " rclcpp/rclcpp.hpp"
19
+ #include " type_alias.hpp"
21
20
22
21
#include < vector>
23
22
24
23
namespace static_centerline_generator
25
24
{
26
25
std::vector<TrajectoryPoint> generate_centerline_with_bag (rclcpp::Node & node);
27
26
} // namespace static_centerline_generator
28
- #endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
27
+ #endif // CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
Original file line number Diff line number Diff line change 13
13
// limitations under the License.
14
14
15
15
#include " centerline_source/optimization_trajectory_based_centerline.hpp"
16
- #include " static_centerline_generator_node.hpp"
17
- #include " utils.hpp"
18
16
19
17
#include " motion_utils/resample/resample.hpp"
20
18
#include " motion_utils/trajectory/conversion.hpp"
21
19
#include " obstacle_avoidance_planner/node.hpp"
22
20
#include " path_smoother/elastic_band_smoother.hpp"
21
+ #include " static_centerline_generator_node.hpp"
23
22
#include " tier4_autoware_utils/ros/parameter.hpp"
23
+ #include " utils.hpp"
24
24
25
25
namespace static_centerline_generator
26
26
{
Original file line number Diff line number Diff line change 12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
16
- #define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
17
-
18
- #include " type_alias.hpp"
15
+ #ifndef CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
16
+ #define CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
19
17
20
18
#include " rclcpp/rclcpp.hpp"
19
+ #include " type_alias.hpp"
21
20
22
21
#include < vector>
23
22
@@ -40,5 +39,5 @@ class OptimizationTrajectoryBasedCenterline
40
39
};
41
40
} // namespace static_centerline_generator
42
41
// clang-format off
43
- #endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
42
+ #endif // CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
44
43
// clang-format on
Original file line number Diff line number Diff line change 12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #include " centerline_source/bag_ego_trajectory_based_centerline.hpp"
16
15
#include " static_centerline_generator_node.hpp"
17
- #include " type_alias.hpp"
18
- #include " utils.hpp"
19
16
17
+ #include " centerline_source/bag_ego_trajectory_based_centerline.hpp"
20
18
#include " lanelet2_extension/utility/message_conversion.hpp"
21
19
#include " lanelet2_extension/utility/query.hpp"
22
20
#include " lanelet2_extension/utility/utilities.hpp"
27
25
#include " static_centerline_generator/msg/points_with_lane_id.hpp"
28
26
#include " tier4_autoware_utils/geometry/geometry.hpp"
29
27
#include " tier4_autoware_utils/ros/parameter.hpp"
28
+ #include " type_alias.hpp"
29
+ #include " utils.hpp"
30
30
31
31
#include < geography_utils/lanelet2_projector.hpp>
32
32
#include < mission_planner/mission_planner_plugin.hpp>
Original file line number Diff line number Diff line change 12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #ifndef STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_
16
- #define STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_
15
+ #ifndef STATIC_CENTERLINE_GENERATOR_NODE_HPP_
16
+ #define STATIC_CENTERLINE_GENERATOR_NODE_HPP_
17
17
18
18
#include " centerline_source/optimization_trajectory_based_centerline.hpp"
19
- #include " type_alias.hpp"
20
-
21
19
#include " rclcpp/rclcpp.hpp"
22
20
#include " static_centerline_generator/srv/load_map.hpp"
23
21
#include " static_centerline_generator/srv/plan_path.hpp"
24
22
#include " static_centerline_generator/srv/plan_route.hpp"
23
+ #include " type_alias.hpp"
25
24
#include " vehicle_info_util/vehicle_info_util.hpp"
26
25
27
26
#include < geography_utils/lanelet2_projector.hpp>
@@ -117,4 +116,4 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node
117
116
vehicle_info_util::VehicleInfo vehicle_info_;
118
117
};
119
118
} // namespace static_centerline_generator
120
- #endif // STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_
119
+ #endif // STATIC_CENTERLINE_GENERATOR_NODE_HPP_
Original file line number Diff line number Diff line change 11
11
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
- #ifndef STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_
15
- #define STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_
14
+ #ifndef TYPE_ALIAS_HPP_
15
+ #define TYPE_ALIAS_HPP_
16
16
17
17
#include " route_handler/route_handler.hpp"
18
18
#include " tier4_autoware_utils/geometry/geometry.hpp"
@@ -43,4 +43,4 @@ using tier4_autoware_utils::Point2d;
43
43
using visualization_msgs::msg::MarkerArray;
44
44
} // namespace static_centerline_generator
45
45
46
- #endif // STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_
46
+ #endif // TYPE_ALIAS_HPP_
Original file line number Diff line number Diff line change 12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #ifndef STATIC_CENTERLINE_GENERATOR__UTILS_HPP_
16
- #define STATIC_CENTERLINE_GENERATOR__UTILS_HPP_
17
-
18
- #include " type_alias.hpp"
15
+ #ifndef UTILS_HPP_
16
+ #define UTILS_HPP_
19
17
20
18
#include " route_handler/route_handler.hpp"
19
+ #include " type_alias.hpp"
21
20
22
21
#include < rclcpp/time.hpp>
23
22
@@ -56,4 +55,4 @@ MarkerArray create_distance_text_marker(
56
55
} // namespace utils
57
56
} // namespace static_centerline_generator
58
57
59
- #endif // STATIC_CENTERLINE_GENERATOR__UTILS_HPP_
58
+ #endif // UTILS_HPP_
You can’t perform that action at this time.
0 commit comments