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

refactor(path_optimizer): rename package name and fix trajectory visualizer #98

Merged
merged 3 commits into from
Sep 3, 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 @@ -81,11 +81,11 @@ Planning:
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection

motion_obstacle_avoidance:
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
logger_name: planning.scenario_planning.lane_driving.motion_planning.obstacle_avoidance_planner
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
- node_name: /planning/scenario_planning/lane_driving/motion_planning/path_optimizer
logger_name: planning.scenario_planning.lane_driving.motion_planning.path_optimizer
- node_name: /planning/scenario_planning/lane_driving/motion_planning/path_optimizer
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
- node_name: /planning/scenario_planning/lane_driving/motion_planning/path_optimizer
logger_name: autoware_motion_utils

motion_velocity_smoother:
Expand Down Expand Up @@ -136,7 +136,7 @@ Common:
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
- node_name: /planning/scenario_planning/lane_driving/motion_planning/path_optimizer
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/motion_planning/path_smoother
logger_name: autoware_universe_utils
Expand Down
2 changes: 1 addition & 1 deletion planning/planning_debug_tools/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ in Global code
```lua
behavior_path = '/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id/debug_info'
behavior_velocity = '/planning/scenario_planning/lane_driving/behavior_planning/path/debug_info'
motion_avoid = '/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/trajectory/debug_info'
motion_avoid = '/planning/scenario_planning/lane_driving/motion_planning/path_optimizer/trajectory/debug_info'
motion_smoother_latacc = '/planning/scenario_planning/motion_velocity_smoother/debug/trajectory_lateral_acc_filtered/debug_info'
motion_smoother = '/planning/scenario_planning/trajectory/debug_info'
```
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<param name="path_with_lane_id_topics" value="[/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id]"/>
<param
name="trajectory_topics"
value="[/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/trajectory,
value="[/planning/scenario_planning/lane_driving/motion_planning/path_optimizer/trajectory,
/planning/scenario_planning/motion_velocity_smoother/debug/backward_filtered_trajectory,
/planning/scenario_planning/motion_velocity_smoother/debug/forward_filtered_trajectory,
/planning/scenario_planning/motion_velocity_smoother/debug/merged_filtered_trajectory,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ def __init__(self):
)
self.sub2 = self.create_subscription(
Trajectory,
lane_drv + "/motion_planning/obstacle_avoidance_planner/trajectory",
lane_drv + "/motion_planning/path_optimizer/trajectory",
self.CallBackAvoidTrajectory,
1,
)
Expand Down
16 changes: 8 additions & 8 deletions planning/planning_debug_tools/scripts/trajectory_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ def __init__(self):

self.behavior_path_planner_path = PathWithLaneId()
self.behavior_velocity_planner_path = Path()
self.obstacle_avoid_traj = Trajectory()
self.path_optimizer_traj = Trajectory()
self.obstacle_stop_traj = Trajectory()

self.plotted = [False] * 9
Expand All @@ -136,7 +136,7 @@ def __init__(self):
)

# BUFFER_SIZE = 65536*100
optimizer_debug = "/planning/scenario_planning/motion_velocity_smoother/debug/"
optimizer_debug = "/planning/scenario_planning/velocity_smoother/debug/"
self.sub1 = message_filters.Subscriber(
self, Trajectory, optimizer_debug + "trajectory_external_velocity_limited"
)
Expand All @@ -162,7 +162,7 @@ def __init__(self):
self.sub8 = message_filters.Subscriber(
self,
Trajectory,
lane_driving + "/motion_planning/obstacle_avoidance_planner/trajectory",
lane_driving + "/motion_planning/path_optimizer/trajectory",
)
self.sub9 = message_filters.Subscriber(self, Trajectory, lane_driving + "/trajectory")

Expand Down Expand Up @@ -252,7 +252,7 @@ def CallBackBehaviorVelocityPlannerPath(self, cmd):
self.update_behavior_velocity_planner_path = True

def CallbackObstacleAvoidTraj(self, cmd):
self.obstacle_avoid_traj = cmd
self.path_optimizer_traj = cmd
self.update_traj_ob_avoid = True

def CallbackObstacleStopTraj(self, cmd):
Expand All @@ -265,7 +265,7 @@ def setPlotTrajectoryVelocity(self):
(self.im2,) = self.ax1.plot(
[], [], label="1: behavior_velocity_planner_path", marker="", ls="--"
)
(self.im3,) = self.ax1.plot([], [], label="2: obstacle_avoid_traj", marker="", ls="-.")
(self.im3,) = self.ax1.plot([], [], label="2: path_optimizer_traj", marker="", ls="-.")
(self.im4,) = self.ax1.plot([], [], label="3: obstacle_stop_traj", marker="", ls="--")
(self.im5,) = self.ax1.plot([], [], label="4-1: opt input", marker="", ls="--")
(self.im6,) = self.ax1.plot(
Expand Down Expand Up @@ -329,8 +329,8 @@ def plotTrajectoryVelocity(self, data):
self.get_logger().info("plot start")

if self.update_traj_final:
self.im10.set_data(0, self.localization_vx)
self.im11.set_data(0, self.vehicle_vx)
self.im10.set_data([0], [self.localization_vx])
self.im11.set_data([0], [self.vehicle_vx])

if self.velocity_limit is not None:
x = [PLOT_MIN_ARCLENGTH, PLOT_MAX_ARCLENGTH]
Expand All @@ -347,7 +347,7 @@ def plotTrajectoryVelocity(self, data):
self.update_behavior_velocity_planner_path,
self.im2,
),
(self.obstacle_avoid_traj, self.update_traj_ob_avoid, self.im3),
(self.path_optimizer_traj, self.update_traj_ob_avoid, self.im3),
(self.obstacle_stop_traj, self.update_traj_ob_stop, self.im4),
(self.trajectory_raw, self.update_traj_raw, self.im5),
(self.trajectory_external_velocity_limited, self.update_ex_vel_lim, self.im6),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@ for module in "${behavior_velocity_module_list[@]}"; do
done

# obstacle avoidance planner
node_name_dict["obstacle_avoidance_planner"]=/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
logger_name_dict["obstacle_avoidance_planner"]=/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
node_name_dict["path_optimizer"]=/planning/scenario_planning/lane_driving/motion_planning/path_optimizer
logger_name_dict["path_optimizer"]=/planning/scenario_planning/lane_driving/motion_planning/path_optimizer

# motion velocity smoother
node_name_dict["motion_velocity_smoother"]=/planning/scenario_planning/motion_velocity_smoother
Expand Down
Loading