Skip to content

Commit

Permalink
fix(autoware_static_centerline_generator): add autoware_ prefix
Browse files Browse the repository at this point in the history
Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Apr 18, 2024
1 parent 8ff92b7 commit 36e7c06
Show file tree
Hide file tree
Showing 23 changed files with 73 additions and 73 deletions.
8 changes: 4 additions & 4 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)

Expand All @@ -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"
Expand All @@ -29,10 +29,10 @@ ament_auto_add_executable(main

if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0)
rosidl_target_interfaces(main
static_centerline_generator "rosidl_typesupport_cpp")
autoware_static_centerline_generator "rosidl_typesupport_cpp")
else()
rosidl_get_typesupport_target(
cpp_typesupport_target static_centerline_generator "rosidl_typesupport_cpp")
cpp_typesupport_target autoware_static_centerline_generator "rosidl_typesupport_cpp")
target_link_libraries(main "${cpp_typesupport_target}")
endif()

Expand Down
4 changes: 2 additions & 2 deletions planning/static_centerline_generator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ We can run
with the following command by designating `<vehicle_model>`

```sh
ros2 launch static_centerline_generator run_planning_server.launch.xml vehicle_model:=<vehicle-model>
ros2 launch autoware_static_centerline_generator run_planning_server.launch.xml vehicle_model:=<vehicle-model>
```

FYI, port ID of the http server is 4010 by default.
Expand All @@ -50,7 +50,7 @@ The optimized centerline can be generated from the command line interface by des
- `<vehicle-model>`

```sh
ros2 launch static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:=<input-osm-path> lanelet2_output_file_path:=<output-osm-path> start_lanelet_id:=<start-lane-id> end_lanelet_id:=<end-lane-id> vehicle_model:=<vehicle-model>
ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml run_backgrond:=false lanelet2_input_file_path:=<input-osm-path> lanelet2_output_file_path:=<output-osm-path> start_lanelet_id:=<start-lane-id> end_lanelet_id:=<end-lane-id> vehicle_model:=<vehicle-model>
```

The default output map path containing the optimized centerline locates `/tmp/lanelet2_map.osm`.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@

#include <vector>

namespace static_centerline_generator
namespace autoware::static_centerline_generator
{
std::vector<TrajectoryPoint> generate_centerline_with_bag(rclcpp::Node & node);
} // namespace static_centerline_generator
} // namespace autoware::static_centerline_generator
#endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__BAG_EGO_TRAJECTORY_BASED_CENTERLINE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include <vector>

namespace static_centerline_generator
namespace autoware::static_centerline_generator
{
class OptimizationTrajectoryBasedCenterline
{
Expand All @@ -37,7 +37,7 @@ class OptimizationTrajectoryBasedCenterline
rclcpp::Publisher<PathWithLaneId>::SharedPtr pub_raw_path_with_lane_id_{nullptr};
rclcpp::Publisher<Path>::SharedPtr pub_raw_path_{nullptr};
};
} // namespace static_centerline_generator
} // namespace autoware::static_centerline_generator
// clang-format off
#endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
// clang-format on
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@

#include "rclcpp/rclcpp.hpp"
#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp"
#include "static_centerline_generator/srv/load_map.hpp"
#include "static_centerline_generator/srv/plan_path.hpp"
#include "static_centerline_generator/srv/plan_route.hpp"
#include "autoware_static_centerline_generator/srv/load_map.hpp"
#include "autoware_static_centerline_generator/srv/plan_path.hpp"
#include "autoware_static_centerline_generator/srv/plan_route.hpp"
#include "static_centerline_generator/type_alias.hpp"
#include "vehicle_info_util/vehicle_info_util.hpp"

Expand All @@ -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
{
Expand Down Expand Up @@ -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
Expand Up @@ -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;
Expand All @@ -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
Expand Up @@ -24,7 +24,7 @@
#include <string>
#include <vector>

namespace static_centerline_generator
namespace autoware::static_centerline_generator
{
namespace utils
{
Expand Down Expand Up @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,11 @@
<!-- mandatory arguments for planning-->
<arg name="vehicle_model"/>

<include file="$(find-pkg-share static_centerline_generator)/launch/static_centerline_generator.launch.xml">
<include file="$(find-pkg-share autoware_static_centerline_generator)/launch/static_centerline_generator.launch.xml">
<arg name="vehicle_model" value="$(var vehicle_model)"/>
<arg name="run_background" value="true"/>
</include>

<!-- local server to connect path optimizer and cloud software -->
<node pkg="static_centerline_generator" exec="app.py" name="static_centerline_generator_http_server" output="screen"/>
<node pkg="autoware_static_centerline_generator" exec="app.py" name="static_centerline_generator_http_server" output="screen"/>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@
</node>

<!-- optimize path -->
<node pkg="static_centerline_generator" exec="main" name="static_centerline_generator">
<node pkg="autoware_static_centerline_generator" exec="main" name="autoware_static_centerline_generator">
<remap from="lanelet2_map_topic" to="$(var lanelet2_map_topic)"/>
<remap from="input_centerline" to="~/input_centerline"/>
<remap from="output_whole_centerline" to="~/output_whole_centerline"/>
Expand All @@ -79,11 +79,11 @@
<param from="$(var obstacle_avoidance_planner_param)"/>
<param from="$(var mission_planner_param)"/>
<!-- node param -->
<param from="$(find-pkg-share static_centerline_generator)/config/static_centerline_generator.param.yaml"/>
<param from="$(find-pkg-share autoware_static_centerline_generator)/config/autoware_static_centerline_generator.param.yaml"/>
<param name="centerline_source" value="$(var centerline_source)"/>
<param name="bag_filename" value="$(var bag_filename)"/>
</node>

<!-- rviz -->
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(find-pkg-share static_centerline_generator)/rviz/static_centerline_generator.rviz" if="$(var rviz)"/>
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(find-pkg-share autoware_static_centerline_generator)/rviz/autoware_static_centerline_generator.rviz" if="$(var rviz)"/>
</launch>
4 changes: 2 additions & 2 deletions planning/static_centerline_generator/package.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?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>
<description>The autoware_static_centerline_generator package</description>
<maintainer email="[email protected]">Takayuki Murooka</maintainer>
<maintainer email="[email protected]">Kosuke Takeuchi</maintainer>
<license>Apache License 2.0</license>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ Visualization Manager:
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /static_centerline_generator/input_centerline
Value: /autoware_static_centerline_generator/input_centerline
Value: true
View Drivable Area:
Alpha: 0.9990000128746033
Expand Down Expand Up @@ -179,7 +179,7 @@ Visualization Manager:
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /static_centerline_generator/output_centerline
Value: /autoware_static_centerline_generator/output_centerline
Value: true
View Footprint:
Alpha: 1
Expand Down Expand Up @@ -222,7 +222,7 @@ Visualization Manager:
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Value: /static_centerline_generator/debug/raw_centerline
Value: /autoware_static_centerline_generator/debug/raw_centerline
Value: false
View Drivable Area:
Alpha: 0.9990000128746033
Expand Down Expand Up @@ -268,7 +268,7 @@ Visualization Manager:
Durability Policy: Transient Local
History Policy: Keep Last
Reliability Policy: Reliable
Value: /static_centerline_generator/debug/unsafe_footprints
Value: /autoware_static_centerline_generator/debug/unsafe_footprints
Value: true
Enabled: false
Name: debug
Expand Down
12 changes: 6 additions & 6 deletions planning/static_centerline_generator/scripts/app.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@
from flask_cors import CORS
import rclpy
from rclpy.node import Node
from static_centerline_generator.srv import LoadMap
from static_centerline_generator.srv import PlanPath
from static_centerline_generator.srv import PlanRoute
from autoware_static_centerline_generator.srv import LoadMap
from autoware_static_centerline_generator.srv import PlanPath
from autoware_static_centerline_generator.srv import PlanRoute

rclpy.init()
node = Node("static_centerline_generator_http_server")
Expand All @@ -51,7 +51,7 @@ def get_map():
map_id = map_uuid

# create client
cli = create_client(LoadMap, "/planning/static_centerline_generator/load_map")
cli = create_client(LoadMap, "/planning/autoware_static_centerline_generator/load_map")

# request map loading
req = LoadMap.Request(map=data["map"])
Expand Down Expand Up @@ -85,7 +85,7 @@ def post_planned_route():
print("map_id is not correct.")

# create client
cli = create_client(PlanRoute, "/planning/static_centerline_generator/plan_route")
cli = create_client(PlanRoute, "/planning/autoware_static_centerline_generator/plan_route")

# request route planning
req = PlanRoute.Request(
Expand Down Expand Up @@ -123,7 +123,7 @@ def post_planned_path():
print("map_id is not correct.")

# create client
cli = create_client(PlanPath, "/planning/static_centerline_generator/plan_path")
cli = create_client(PlanPath, "/planning/autoware_static_centerline_generator/plan_path")

# request path planning
route_lane_ids = [eval(i) for i in request.args.getlist("route[]")]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@ def __init__(self):
transient_local_qos = QoSProfile(depth=1, durability=QoSDurabilityPolicy.TRANSIENT_LOCAL)
self.sub_whole_centerline = self.create_subscription(
Trajectory,
"/static_centerline_generator/output_whole_centerline",
"/autoware_static_centerline_generator/output_whole_centerline",
self.onWholeCenterline,
transient_local_qos,
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,8 +98,8 @@ def remove_diff_to_ignore(osm_root):
)
args = parser.parse_args()

original_osm_file_name = "/tmp/static_centerline_generator/input/lanelet2_map.osm"
modified_osm_file_name = "/tmp/static_centerline_generator/output/lanelet2_map.osm"
original_osm_file_name = "/tmp/autoware_static_centerline_generator/input/lanelet2_map.osm"
modified_osm_file_name = "/tmp/autoware_static_centerline_generator/output/lanelet2_map.osm"

# load LL2 maps
original_osm_tree = ET.parse(original_osm_file_name)
Expand All @@ -118,7 +118,7 @@ def remove_diff_to_ignore(osm_root):
remove_diff_to_ignore(modified_osm_root)

# write LL2 maps
output_dir_path = "/tmp/static_centerline_generator/show_lanelet2_map_diff/"
output_dir_path = "/tmp/autoware_static_centerline_generator/show_lanelet2_map_diff/"
os.makedirs(output_dir_path + "original/", exist_ok=True)
os.makedirs(output_dir_path + "modified/", exist_ok=True)

Expand Down
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
#!/bin/bash

ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix static_centerline_generator --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus
ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="bag_ego_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" bag_filename:="$(ros2 pkg prefix autoware_static_centerline_generator --share)/test/data/bag_ego_trajectory.db3" vehicle_model:=lexus
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
#!/bin/bash

ros2 launch static_centerline_generator static_centerline_generator.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus
ros2 launch autoware_static_centerline_generator static_centerline_generator.launch.xml centerline_source:="optimization_trajectory_base" run_background:=false lanelet2_input_file_path:="$HOME/autoware_map/sample_map/lanelet2_map.osm" start_lanelet_id:=125 end_lanelet_id:=132 vehicle_model:=lexus
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include <nav_msgs/msg/odometry.hpp>

namespace static_centerline_generator
namespace autoware::static_centerline_generator
{
std::vector<TrajectoryPoint> generate_centerline_with_bag(rclcpp::Node & node)
{
Expand Down Expand Up @@ -79,4 +79,4 @@ std::vector<TrajectoryPoint> generate_centerline_with_bag(rclcpp::Node & node)

return centerline_traj_points;
}
} // namespace static_centerline_generator
} // namespace autoware::static_centerline_generator
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "static_centerline_generator/utils.hpp"
#include "tier4_autoware_utils/ros/parameter.hpp"

namespace static_centerline_generator
namespace autoware::static_centerline_generator
{
namespace
{
Expand Down Expand Up @@ -180,4 +180,4 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra

return whole_optimized_traj_points;
}
} // namespace static_centerline_generator
} // namespace autoware::static_centerline_generator
2 changes: 1 addition & 1 deletion planning/static_centerline_generator/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
Expand Down
Loading

0 comments on commit 36e7c06

Please sign in to comment.