Skip to content

Commit 60bff85

Browse files
Remove driveblocks dependencies
Signed-off-by: Simon Eisenmann <simon.eisenmann@driveblocks.ai>
1 parent b048568 commit 60bff85

File tree

7 files changed

+196
-280
lines changed

7 files changed

+196
-280
lines changed

planning/mapless_architecture/autoware_local_mission_planner/include/autoware/local_mission_planner/mission_planner_node.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,6 @@
1414
#include "autoware_planning_msgs/msg/mission.hpp"
1515
#include "autoware_planning_msgs/msg/mission_lanes_stamped.hpp"
1616
#include "autoware_planning_msgs/msg/visualization_distance.hpp"
17-
#include "db_msgs/msg/lanelets_stamped.hpp"
1817
#include "geometry_msgs/msg/point.hpp"
1918
#include "nav_msgs/msg/odometry.hpp"
2019
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

planning/mapless_architecture/autoware_local_mission_planner/src/mission_planner_node.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@
1111
#include "autoware_planning_msgs/msg/driving_corridor.hpp"
1212
#include "autoware_planning_msgs/msg/mission.hpp"
1313
#include "autoware_planning_msgs/msg/mission_lanes_stamped.hpp"
14-
#include "db_msgs/msg/lanelets_stamped.hpp"
1514
#include "geometry_msgs/msg/point.hpp"
1615
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
1716
#include "visualization_msgs/msg/marker.hpp"

planning/mapless_architecture/autoware_local_mission_planner/test/src/test_mission_planner_core.cpp

+137-219
Large diffs are not rendered by default.

planning/mapless_architecture/autoware_local_mission_planner_common/include/autoware/local_mission_planner_common/helper_functions.hpp

-10
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,6 @@
1010
#include "tf2_ros/transform_listener.h"
1111

1212
#include "autoware_planning_msgs/msg/road_segments.hpp"
13-
#include "db_msgs/msg/lanelets_stamped.hpp"
1413
#include "geometry_msgs/msg/point.hpp"
1514
#include "geometry_msgs/msg/pose.hpp"
1615

@@ -92,15 +91,6 @@ double NormalizePsi(const double psi);
9291
*/
9392
std::vector<double> GetPsiForPoints(const std::vector<geometry_msgs::msg::Point> & points);
9493

95-
/**
96-
* @brief Convert the LaneletsStamped message into a RoadSegments message.
97-
*
98-
* @param msg The message (db_msgs::msg::LaneletsStamped).
99-
* @return autoware_planning_msgs::msg::RoadSegments.
100-
*/
101-
autoware_planning_msgs::msg::RoadSegments ConvertLaneletsStamped2RoadSegments(
102-
const db_msgs::msg::LaneletsStamped & msg);
103-
10494
/**
10595
* @brief Holds
10696
* the origin lanelet Id,

planning/mapless_architecture/autoware_local_mission_planner_common/src/helper_functions.cpp

-49
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@
66
#include "rclcpp/rclcpp.hpp"
77

88
#include "autoware_planning_msgs/msg/road_segments.hpp"
9-
#include "db_msgs/msg/lanelets_stamped.hpp"
109

1110
namespace autoware::mapless_architecture
1211
{
@@ -140,54 +139,6 @@ double GetYawFromQuaternion(const double x, const double y, const double z, cons
140139
return yaw;
141140
}
142141

143-
// Declare a static logger
144-
static rclcpp::Logger static_logger = rclcpp::get_logger("static_logger");
145-
146-
autoware_planning_msgs::msg::RoadSegments ConvertLaneletsStamped2RoadSegments(
147-
const db_msgs::msg::LaneletsStamped & msg)
148-
{
149-
// Initialize road segments message
150-
autoware_planning_msgs::msg::RoadSegments road_segments;
151-
152-
// Fill message header and pose
153-
road_segments.header = msg.header;
154-
road_segments.pose = msg.pose;
155-
156-
// Convert lanelets to segments if lanelets are not empty
157-
if (!msg.lanelets.empty()) {
158-
for (const db_msgs::msg::Lanelet & lanelet : msg.lanelets) {
159-
// Initialize a segment
160-
autoware_planning_msgs::msg::Segment segment;
161-
162-
// Fill the segment with basic information
163-
segment.id = lanelet.id;
164-
segment.successor_lanelet_id = lanelet.successor_lanelet_id;
165-
segment.neighboring_lanelet_id = lanelet.neighboring_lanelet_id;
166-
167-
// Copy linestrings data
168-
for (int i = 0; i < 2; ++i) {
169-
// Copy points from the original linestring to the new one if points are not empty
170-
if (!lanelet.linestrings[i].points.empty()) {
171-
segment.linestrings[i].poses.reserve(lanelet.linestrings[i].points.size());
172-
173-
for (const db_msgs::msg::DBPoint & point : lanelet.linestrings[i].points) {
174-
segment.linestrings[i].poses.push_back(point.pose);
175-
}
176-
} else {
177-
RCLCPP_WARN(
178-
static_logger,
179-
"Linestring does not contain points (ConvertLaneletsStamped2RoadSegments)!");
180-
}
181-
}
182-
183-
// Add the filled segment to the road_segments message
184-
road_segments.segments.push_back(segment);
185-
}
186-
}
187-
188-
return road_segments;
189-
}
190-
191142
std::vector<std::vector<int>> GetAllSuccessorSequences(
192143
const std::vector<LaneletConnection> & lanelet_connections, const int id_initial_lanelet)
193144
{

planning/mapless_architecture/autoware_local_road_provider/include/autoware/local_road_provider/local_road_provider_node.hpp

+9
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,15 @@ class LocalRoadProviderNode : public rclcpp::Node
3333
*/
3434
void CallbackLaneletsMessages_(const db_msgs::msg::LaneletsStamped & msg);
3535

36+
/**
37+
* @brief Convert the LaneletsStamped message into a RoadSegments message.
38+
*
39+
* @param msg The message (db_msgs::msg::LaneletsStamped).
40+
* @return autoware_planning_msgs::msg::RoadSegments.
41+
*/
42+
autoware_planning_msgs::msg::RoadSegments ConvertLaneletsStamped2RoadSegments(
43+
const db_msgs::msg::LaneletsStamped & msg);
44+
3645
// Declare ROS2 publisher and subscriber
3746

3847
rclcpp::Publisher<autoware_planning_msgs::msg::RoadSegments>::SharedPtr road_publisher_;

planning/mapless_architecture/autoware_local_road_provider/src/local_road_provider_node.cpp

+50
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,55 @@ LocalRoadProviderNode::LocalRoadProviderNode() : Node("local_road_provider_node"
2828
std::bind(&LocalRoadProviderNode::CallbackLaneletsMessages_, this, _1));
2929
}
3030

31+
autoware_planning_msgs::msg::RoadSegments
32+
LocalRoadProviderNode::ConvertLaneletsStamped2RoadSegments(
33+
const db_msgs::msg::LaneletsStamped & msg)
34+
{
35+
// Declare a static logger
36+
static rclcpp::Logger static_logger = rclcpp::get_logger("static_logger");
37+
38+
// Initialize road segments message
39+
autoware_planning_msgs::msg::RoadSegments road_segments;
40+
41+
// Fill message header and pose
42+
road_segments.header = msg.header;
43+
road_segments.pose = msg.pose;
44+
45+
// Convert lanelets to segments if lanelets are not empty
46+
if (!msg.lanelets.empty()) {
47+
for (const db_msgs::msg::Lanelet & lanelet : msg.lanelets) {
48+
// Initialize a segment
49+
autoware_planning_msgs::msg::Segment segment;
50+
51+
// Fill the segment with basic information
52+
segment.id = lanelet.id;
53+
segment.successor_lanelet_id = lanelet.successor_lanelet_id;
54+
segment.neighboring_lanelet_id = lanelet.neighboring_lanelet_id;
55+
56+
// Copy linestrings data
57+
for (int i = 0; i < 2; ++i) {
58+
// Copy points from the original linestring to the new one if points are not empty
59+
if (!lanelet.linestrings[i].points.empty()) {
60+
segment.linestrings[i].poses.reserve(lanelet.linestrings[i].points.size());
61+
62+
for (const db_msgs::msg::DBPoint & point : lanelet.linestrings[i].points) {
63+
segment.linestrings[i].poses.push_back(point.pose);
64+
}
65+
} else {
66+
RCLCPP_WARN(
67+
static_logger,
68+
"Linestring does not contain points (ConvertLaneletsStamped2RoadSegments)!");
69+
}
70+
}
71+
72+
// Add the filled segment to the road_segments message
73+
road_segments.segments.push_back(segment);
74+
}
75+
}
76+
77+
return road_segments;
78+
}
79+
3180
void LocalRoadProviderNode::CallbackLaneletsMessages_(const db_msgs::msg::LaneletsStamped & msg)
3281
{
3382
autoware_planning_msgs::msg::RoadSegments road_segments =
@@ -36,4 +85,5 @@ void LocalRoadProviderNode::CallbackLaneletsMessages_(const db_msgs::msg::Lanele
3685
// Publish the RoadSegments message
3786
road_publisher_->publish(road_segments);
3887
}
88+
3989
} // namespace autoware::mapless_architecture

0 commit comments

Comments
 (0)