|
12 | 12 | // See the License for the specific language governing permissions and
|
13 | 13 | // limitations under the License.
|
14 | 14 |
|
15 |
| -#ifndef STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ |
16 |
| -#define STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ |
| 15 | +#ifndef STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ |
| 16 | +#define STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ |
17 | 17 |
|
18 | 18 | #include "rclcpp/rclcpp.hpp"
|
19 |
| -#include "static_centerline_optimizer/centerline_source/optimization_trajectory_based_centerline.hpp" |
20 |
| -#include "static_centerline_optimizer/srv/load_map.hpp" |
21 |
| -#include "static_centerline_optimizer/srv/plan_path.hpp" |
22 |
| -#include "static_centerline_optimizer/srv/plan_route.hpp" |
23 |
| -#include "static_centerline_optimizer/type_alias.hpp" |
| 19 | +#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp" |
| 20 | +#include "static_centerline_generator/srv/load_map.hpp" |
| 21 | +#include "static_centerline_generator/srv/plan_path.hpp" |
| 22 | +#include "static_centerline_generator/srv/plan_route.hpp" |
| 23 | +#include "static_centerline_generator/type_alias.hpp" |
24 | 24 | #include "vehicle_info_util/vehicle_info_util.hpp"
|
25 | 25 |
|
26 | 26 | #include <geography_utils/lanelet2_projector.hpp>
|
|
34 | 34 | #include <utility>
|
35 | 35 | #include <vector>
|
36 | 36 |
|
37 |
| -namespace static_centerline_optimizer |
| 37 | +namespace static_centerline_generator |
38 | 38 | {
|
39 |
| -using static_centerline_optimizer::srv::LoadMap; |
40 |
| -using static_centerline_optimizer::srv::PlanPath; |
41 |
| -using static_centerline_optimizer::srv::PlanRoute; |
| 39 | +using static_centerline_generator::srv::LoadMap; |
| 40 | +using static_centerline_generator::srv::PlanPath; |
| 41 | +using static_centerline_generator::srv::PlanRoute; |
42 | 42 |
|
43 | 43 | struct CenterlineWithRoute
|
44 | 44 | {
|
45 | 45 | std::vector<TrajectoryPoint> centerline{};
|
46 | 46 | std::vector<lanelet::Id> route_lane_ids{};
|
47 | 47 | };
|
48 | 48 |
|
49 |
| -class StaticCenterlineOptimizerNode : public rclcpp::Node |
| 49 | +class StaticCenterlineGeneratorNode : public rclcpp::Node |
50 | 50 | {
|
51 | 51 | public:
|
52 |
| - explicit StaticCenterlineOptimizerNode(const rclcpp::NodeOptions & node_options); |
| 52 | + explicit StaticCenterlineGeneratorNode(const rclcpp::NodeOptions & node_options); |
53 | 53 | void run();
|
54 | 54 |
|
55 | 55 | private:
|
@@ -115,5 +115,5 @@ class StaticCenterlineOptimizerNode : public rclcpp::Node
|
115 | 115 | // vehicle info
|
116 | 116 | vehicle_info_util::VehicleInfo vehicle_info_;
|
117 | 117 | };
|
118 |
| -} // namespace static_centerline_optimizer |
119 |
| -#endif // STATIC_CENTERLINE_OPTIMIZER__STATIC_CENTERLINE_OPTIMIZER_NODE_HPP_ |
| 118 | +} // namespace static_centerline_generator |
| 119 | +#endif // STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_ |
0 commit comments