Skip to content

Commit b589b53

Browse files
Add namespace
Signed-off-by: Simon Eisenmann <simon.eisenmann@driveblocks.ai>
1 parent a12fcd7 commit b589b53

File tree

23 files changed

+71
-5
lines changed

23 files changed

+71
-5
lines changed

planning/mapless_architecture/autoware_hmi/include/autoware/hmi/hmi_node.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,9 @@
99
#include <string>
1010
#include <vector>
1111

12+
namespace autoware::mapless_architecture
13+
{
14+
1215
/**
1316
* Node for HMI.
1417
*/
@@ -51,5 +54,6 @@ class HMINode : public rclcpp::Node
5154

5255
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_callback_handle_;
5356
};
57+
}
5458

5559
#endif // HMI_NODE_HPP_

planning/mapless_architecture/autoware_hmi/src/hmi_main.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ int main(int argc, char * argv[])
1212
RCLCPP_INFO(rclcpp::get_logger("hmi"), "Launching HMI node...");
1313

1414
rclcpp::init(argc, argv);
15-
rclcpp::spin(std::make_shared<HMINode>());
15+
rclcpp::spin(std::make_shared<autoware::mapless_architecture::HMINode>());
1616
rclcpp::shutdown();
1717
return 0;
1818
}

planning/mapless_architecture/autoware_hmi/src/hmi_node.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,8 @@
66
#include "autoware_planning_msgs/msg/mission.hpp"
77
#include "rclcpp/rclcpp.hpp"
88

9+
namespace autoware::mapless_architecture
10+
{
911
using std::placeholders::_1;
1012

1113
/**
@@ -82,3 +84,4 @@ void HMINode::PublishMission_(std::string mission)
8284

8385
mission_publisher_->publish(missionMessage);
8486
}
87+
}

planning/mapless_architecture/autoware_local_map_provider/include/autoware/local_map_provider/local_map_provider_node.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,8 @@
77
#include "autoware_planning_msgs/msg/road_segments.hpp"
88
#include "rclcpp/rclcpp.hpp"
99

10+
namespace autoware::mapless_architecture{
11+
1012
/**
1113
* Node for the Local Map Provider.
1214
*/
@@ -42,5 +44,6 @@ class LocalMapProviderNode : public rclcpp::Node
4244

4345
rclcpp::Subscription<autoware_planning_msgs::msg::RoadSegments>::SharedPtr road_subscriber_;
4446
};
47+
}
4548

4649
#endif // LOCAL_MAP_PROVIDER_NODE_HPP_

planning/mapless_architecture/autoware_local_map_provider/src/local_map_provider_main.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ int main(int argc, char * argv[])
1212
RCLCPP_INFO(rclcpp::get_logger("local_map_provider"), "Launching Local Map Provider node...");
1313

1414
rclcpp::init(argc, argv);
15-
rclcpp::spin(std::make_shared<LocalMapProviderNode>());
15+
rclcpp::spin(std::make_shared<autoware::mapless_architecture::LocalMapProviderNode>());
1616
rclcpp::shutdown();
1717
return 0;
1818
}

planning/mapless_architecture/autoware_local_map_provider/src/local_map_provider_node.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55

66
#include "rclcpp/rclcpp.hpp"
77

8+
namespace autoware::mapless_architecture{
89
using std::placeholders::_1;
910

1011
LocalMapProviderNode::LocalMapProviderNode() : Node("local_map_provider_node")
@@ -37,3 +38,4 @@ void LocalMapProviderNode::CallbackRoadSegmentsMessages_(
3738
map_publisher_->publish(
3839
local_map); // Outlook: Add global map, sign detection etc. to the message
3940
}
41+
}

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

+3
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@
2727
#include <tuple>
2828
#include <vector>
2929

30+
namespace autoware::mapless_architecture
31+
{
3032
using namespace lib_mission_planner;
3133

3234
// Create Direction data type
@@ -336,5 +338,6 @@ class MissionPlannerNode : public rclcpp::Node
336338
// Unique ID for each marker
337339
int centerline_marker_id_ = 0;
338340
};
341+
}
339342

340343
#endif // MISSION_PLANNER_NODE_HPP_

planning/mapless_architecture/autoware_local_mission_planner/src/mission_planner_main.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ int main(int argc, char * argv[])
1010
RCLCPP_INFO(rclcpp::get_logger("mission_planner"), "Launching mission planner node...");
1111

1212
rclcpp::init(argc, argv);
13-
rclcpp::spin(std::make_shared<MissionPlannerNode>());
13+
rclcpp::spin(std::make_shared<autoware::mapless_architecture::MissionPlannerNode>());
1414
rclcpp::shutdown();
1515
return 0;
1616
}

planning/mapless_architecture/autoware_local_mission_planner/src/mission_planner_node.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@
2727
#include <unordered_map>
2828
#include <vector>
2929

30+
namespace autoware::mapless_architecture
31+
{
3032
using std::placeholders::_1;
3133
using namespace lib_mission_planner;
3234

@@ -1116,3 +1118,4 @@ void MissionPlannerNode::CalculatePredecessors(std::vector<LaneletConnection> &
11161118
}
11171119
}
11181120
}
1121+
}

planning/mapless_architecture/autoware_local_mission_planner/test/gtest_main.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@
55
#include "include/test_mission_planner_core.hpp"
66
#include "rclcpp/rclcpp.hpp"
77

8+
namespace autoware::mapless_architecture
9+
{
10+
811
TEST(MissionPlannerCore, CalculateDistanceBetweenPointAndLineString)
912
{
1013
EXPECT_EQ(TestCalculateDistanceBetweenPointAndLineString(), 0);
@@ -52,3 +55,4 @@ int main(int argc, char ** argv)
5255
return RUN_ALL_TESTS();
5356
rclcpp::shutdown();
5457
}
58+
}

planning/mapless_architecture/autoware_local_mission_planner/test/include/test_mission_planner_core.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@
55

66
#include "db_msgs/msg/lanelets_stamped.hpp"
77

8+
namespace autoware::mapless_architecture
9+
{
10+
811
/**
912
* @brief Test distance between point and LineString calculation.
1013
*
@@ -72,4 +75,6 @@ int TestCreateMarkerArray();
7275
*/
7376
int TestCreateDrivingCorridor();
7477

78+
}
79+
7580
#endif // TEST_MISSION_PLANNER_CORE_HPP_

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

+4
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,9 @@
1111
#include <iostream>
1212
#include <tuple>
1313

14+
namespace autoware::mapless_architecture
15+
{
16+
1417
db_msgs::msg::LaneletsStamped CreateLanelets()
1518
{
1619
// Local variables
@@ -662,3 +665,4 @@ int TestCreateDrivingCorridor()
662665

663666
return 0;
664667
}
668+
}

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

+3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@
1616

1717
#include <vector>
1818

19+
namespace autoware::mapless_architecture
20+
{
1921
namespace lib_mission_planner
2022
{
2123

@@ -276,5 +278,6 @@ int FindOccupiedLaneletID(
276278
int FindEgoOccupiedLaneletID(const std::vector<lanelet::Lanelet> & lanelets);
277279

278280
} // namespace lib_mission_planner
281+
}
279282

280283
#endif // LIB_MISSION_PLANNER__HELPER_FUNCTIONS_HPP_

planning/mapless_architecture/autoware_local_mission_planner_common/src/helper_functions.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,8 @@
88

99
#include "db_msgs/msg/lanelets_stamped.hpp"
1010

11+
namespace autoware::mapless_architecture
12+
{
1113
namespace lib_mission_planner
1214
{
1315

@@ -441,3 +443,5 @@ int FindEgoOccupiedLaneletID(const std::vector<lanelet::Lanelet> & lanelets)
441443
}
442444

443445
} // namespace lib_mission_planner
446+
447+
}

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

+4
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,9 @@
88

99
#include "db_msgs/msg/lanelets_stamped.hpp"
1010

11+
namespace autoware::mapless_architecture
12+
{
13+
1114
/**
1215
* Node for the Local Road Provider.
1316
*/
@@ -43,5 +46,6 @@ class LocalRoadProviderNode : public rclcpp::Node
4346

4447
rclcpp::Subscription<db_msgs::msg::LaneletsStamped>::SharedPtr lanelets_subscriber_;
4548
};
49+
}
4650

4751
#endif // LOCAL_ROAD_PROVIDER_NODE_HPP_

planning/mapless_architecture/autoware_local_road_provider/src/local_road_provider_main.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ int main(int argc, char * argv[])
1212
RCLCPP_INFO(rclcpp::get_logger("local_road_provider"), "Launching Local Road Provider node...");
1313

1414
rclcpp::init(argc, argv);
15-
rclcpp::spin(std::make_shared<LocalRoadProviderNode>());
15+
rclcpp::spin(std::make_shared<autoware::mapless_architecture::LocalRoadProviderNode>());
1616
rclcpp::shutdown();
1717
return 0;
1818
}

planning/mapless_architecture/autoware_local_road_provider/src/local_road_provider_node.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,8 @@
66
#include "autoware/local_mission_planner_common/helper_functions.hpp"
77
#include "rclcpp/rclcpp.hpp"
88

9+
namespace autoware::mapless_architecture
10+
{
911
using std::placeholders::_1;
1012

1113
LocalRoadProviderNode::LocalRoadProviderNode() : Node("local_road_provider_node")
@@ -34,3 +36,4 @@ void LocalRoadProviderNode::CallbackLaneletsMessages_(const db_msgs::msg::Lanele
3436
// Publish the RoadSegments message
3537
road_publisher_->publish(road_segments);
3638
}
39+
}

planning/mapless_architecture/autoware_mission_lane_converter/include/autoware/mission_lane_converter/mission_lane_converter_node.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,9 @@
1616
#include <tuple>
1717
#include <vector>
1818

19+
namespace autoware::mapless_architecture
20+
{
21+
1922
/**
2023
* Node to convert the mission lane to an autoware trajectory type.
2124
*/
@@ -175,5 +178,6 @@ class MissionLaneConverterNode : public rclcpp::Node
175178
// ros parameters
176179
float target_speed_;
177180
};
181+
}
178182

179183
#endif // MISSION_LANE_CONVERTER_NODE_HPP_

planning/mapless_architecture/autoware_mission_lane_converter/src/main_mission_lane_converter.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ int main(int argc, char * argv[])
1212
"Launching mission lane converter node...");
1313

1414
rclcpp::init(argc, argv);
15-
rclcpp::spin(std::make_shared<MissionLaneConverterNode>());
15+
rclcpp::spin(std::make_shared<autoware::mapless_architecture::MissionLaneConverterNode>());
1616
rclcpp::shutdown();
1717
return 0;
1818
}

planning/mapless_architecture/autoware_mission_lane_converter/src/mission_lane_converter_node.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@
1616
#include <chrono>
1717
#include <functional>
1818

19+
namespace autoware::mapless_architecture
20+
{
1921
using std::placeholders::_1;
2022
using namespace lib_mission_planner;
2123

@@ -609,3 +611,4 @@ visualization_msgs::msg::Marker MissionLaneConverterNode::GetGlobalTrjVisualizat
609611

610612
return trj_vis_global;
611613
}
614+
}

planning/mapless_architecture/autoware_mission_lane_converter/test/gtest_main.cpp

+5
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,9 @@
44
#include "include/test_mission_planner_converter.hpp"
55
#include "rclcpp/rclcpp.hpp"
66

7+
namespace autoware::mapless_architecture
8+
{
9+
710
TEST(MissionConverter, MissionToTrajectory)
811
{
912
EXPECT_EQ(TestMissionToTrajectory(), 0);
@@ -16,3 +19,5 @@ int main(int argc, char ** argv)
1619
return RUN_ALL_TESTS();
1720
rclcpp::shutdown();
1821
}
22+
23+
}

planning/mapless_architecture/autoware_mission_lane_converter/test/include/test_mission_planner_converter.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,11 @@
44
#ifndef TEST_MISSION_PLANNER_CONVERTER_HPP_
55
#define TEST_MISSION_PLANNER_CONVERTER_HPP_
66

7+
namespace autoware::mapless_architecture
8+
{
9+
710
int TestMissionToTrajectory();
811

12+
}
13+
914
#endif // TEST_MISSION_PLANNER_CONVERTER_HPP_

planning/mapless_architecture/autoware_mission_lane_converter/test/src/test_mission_planner_converter.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,9 @@
66

77
#include "geometry_msgs/msg/point.hpp"
88

9+
namespace autoware::mapless_architecture
10+
{
11+
912
int TestMissionToTrajectory()
1013
{
1114
MissionLaneConverterNode mission_converter = MissionLaneConverterNode();
@@ -109,3 +112,4 @@ int TestMissionToTrajectory()
109112

110113
return 0;
111114
}
115+
}

0 commit comments

Comments
 (0)