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

fix(autoware_static_centerline_generator): remove prefix from topics and node names #7028

Merged
merged 1 commit into from
May 15, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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: /autoware_static_centerline_generator/input_centerline
Value: /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: /autoware_static_centerline_generator/output_centerline
Value: /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: /autoware_static_centerline_generator/debug/raw_centerline
Value: /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: /autoware_static_centerline_generator/debug/unsafe_footprints
Value: /static_centerline_generator/debug/unsafe_footprints
Value: true
Enabled: false
Name: debug
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ def get_map():
map_id = map_uuid

# create client
cli = create_client(LoadMap, "/planning/autoware_static_centerline_generator/load_map")
cli = create_client(LoadMap, "/planning/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/autoware_static_centerline_generator/plan_route")
cli = create_client(PlanRoute, "/planning/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/autoware_static_centerline_generator/plan_path")
cli = create_client(PlanPath, "/planning/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,
"/autoware_static_centerline_generator/output_whole_centerline",
"/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 @@ -169,7 +169,7 @@ std::vector<TrajectoryPoint> resample_trajectory_points(

StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode(
const rclcpp::NodeOptions & node_options)
: Node("autoware_static_centerline_generator", node_options)
: Node("static_centerline_generator", node_options)
{
// publishers
pub_map_bin_ =
Expand Down Expand Up @@ -217,19 +217,19 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode(
// services
callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
srv_load_map_ = create_service<LoadMap>(
"/planning/autoware_static_centerline_generator/load_map",
"/planning/static_centerline_generator/load_map",
std::bind(
&StaticCenterlineGeneratorNode::on_load_map, this, std::placeholders::_1,
std::placeholders::_2),
rmw_qos_profile_services_default, callback_group_);
srv_plan_route_ = create_service<PlanRoute>(
"/planning/autoware_static_centerline_generator/plan_route",
"/planning/static_centerline_generator/plan_route",
std::bind(
&StaticCenterlineGeneratorNode::on_plan_route, this, std::placeholders::_1,
std::placeholders::_2),
rmw_qos_profile_services_default, callback_group_);
srv_plan_path_ = create_service<PlanPath>(
"/planning/autoware_static_centerline_generator/plan_path",
"/planning/static_centerline_generator/plan_path",
std::bind(
&StaticCenterlineGeneratorNode::on_plan_path, this, std::placeholders::_1,
std::placeholders::_2),
Expand Down
Loading