Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

build(static_centerline_optimizer): prefix package and namespace with autoware_ #6635

Closed
wants to merge 11 commits into from
Next Next commit
build(static_centerline_optimizer): prefix package and namespace with…
… autoware_

Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
  • Loading branch information
esteve committed Apr 15, 2024
commit 0d3c941dec69cb64b907aa2fe3d6e90167a43e63
4 changes: 2 additions & 2 deletions planning/static_centerline_generator/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(static_centerline_generator)
project(autoware_static_centerline_generator)

find_package(autoware_cmake REQUIRED)

@@ -9,7 +9,7 @@ find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)

rosidl_generate_interfaces(
static_centerline_generator
autoware_static_centerline_generator
"srv/LoadMap.srv"
"srv/PlanRoute.srv"
"srv/PlanPath.srv"
Original file line number Diff line number Diff line change
@@ -34,11 +34,11 @@
#include <utility>
#include <vector>

namespace static_centerline_generator
namespace autoware::static_centerline_generator
{
using static_centerline_generator::srv::LoadMap;
using static_centerline_generator::srv::PlanPath;
using static_centerline_generator::srv::PlanRoute;
using autoware::static_centerline_generator::srv::LoadMap;
using autoware::static_centerline_generator::srv::PlanPath;
using autoware::static_centerline_generator::srv::PlanRoute;

struct CenterlineWithRoute
{
@@ -115,5 +115,5 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node
// vehicle info
vehicle_info_util::VehicleInfo vehicle_info_;
};
} // namespace static_centerline_generator
} // namespace autoware::static_centerline_generator
#endif // STATIC_CENTERLINE_GENERATOR__STATIC_CENTERLINE_GENERATOR_NODE_HPP_
Original file line number Diff line number Diff line change
@@ -26,7 +26,7 @@
#include "autoware_planning_msgs/msg/lanelet_route.hpp"
#include "visualization_msgs/msg/marker_array.hpp"

namespace static_centerline_generator
namespace autoware::static_centerline_generator
{
using autoware_auto_mapping_msgs::msg::HADMapBin;
using autoware_auto_perception_msgs::msg::PredictedObjects;
@@ -41,6 +41,6 @@ using tier4_autoware_utils::LinearRing2d;
using tier4_autoware_utils::LineString2d;
using tier4_autoware_utils::Point2d;
using visualization_msgs::msg::MarkerArray;
} // namespace static_centerline_generator
} // namespace autoware::static_centerline_generator

#endif // STATIC_CENTERLINE_GENERATOR__TYPE_ALIAS_HPP_
Original file line number Diff line number Diff line change
@@ -24,7 +24,7 @@
#include <string>
#include <vector>

namespace static_centerline_generator
namespace autoware::static_centerline_generator
{
namespace utils
{
@@ -53,6 +53,6 @@ MarkerArray create_distance_text_marker(
const geometry_msgs::msg::Pose & pose, const double dist,
const std::array<double, 3> & marker_color, const rclcpp::Time & now, const size_t idx);
} // namespace utils
} // namespace static_centerline_generator
} // namespace autoware::static_centerline_generator

#endif // STATIC_CENTERLINE_GENERATOR__UTILS_HPP_
2 changes: 1 addition & 1 deletion planning/static_centerline_generator/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>static_centerline_generator</name>
<name>autoware_static_centerline_generator</name>
<version>0.1.0</version>
<description>The static_centerline_generator package</description>
<maintainer email="takayuki.murooka@tier4.jp">Takayuki Murooka</maintainer>
2 changes: 1 addition & 1 deletion planning/static_centerline_generator/src/main.cpp
Original file line number Diff line number Diff line change
@@ -21,7 +21,7 @@ int main(int argc, char * argv[])
// initialize node
rclcpp::NodeOptions node_options;
auto node =
std::make_shared<static_centerline_generator::StaticCenterlineGeneratorNode>(node_options);
std::make_shared<autoware::static_centerline_generator::StaticCenterlineGeneratorNode>(node_options);

// get ros parameter
const bool run_background = node->declare_parameter<bool>("run_background");
Original file line number Diff line number Diff line change
@@ -533,7 +533,7 @@ void StaticCenterlineGeneratorNode::on_plan_path(

if (!current_lanelet_points.empty()) {
// register points with lane_id
static_centerline_generator::msg::PointsWithLaneId points_with_lane_id;
autoware_static_centerline_generator::msg::PointsWithLaneId points_with_lane_id;
points_with_lane_id.lane_id = lanelet.id();
points_with_lane_id.points = current_lanelet_points;
response->points_with_lane_ids.push_back(points_with_lane_id);