Skip to content

Commit 24bcd0e

Browse files
authored
feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency (#9757)
* feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 7102a48 commit 24bcd0e

File tree

8 files changed

+0
-14
lines changed

8 files changed

+0
-14
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@
2424
<depend>pluginlib</depend>
2525
<depend>rclcpp</depend>
2626
<depend>tf2</depend>
27-
<depend>tier4_planning_msgs</depend>
2827
<depend>visualization_msgs</depend>
2928

3029
<test_depend>ament_cmake_ros</test_depend>

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,6 @@
3333
<depend>sensor_msgs</depend>
3434
<depend>tf2_eigen</depend>
3535
<depend>tf2_geometry_msgs</depend>
36-
<depend>tier4_planning_msgs</depend>
3736
<depend>visualization_msgs</depend>
3837

3938
<test_depend>ament_cmake_ros</test_depend>

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,6 @@
2929
<depend>pluginlib</depend>
3030
<depend>rclcpp</depend>
3131
<depend>tf2</depend>
32-
<depend>tier4_planning_msgs</depend>
3332
<depend>visualization_msgs</depend>
3433

3534
<test_depend>ament_cmake_ros</test_depend>

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,6 @@
2424

2525
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
2626
#include <geometry_msgs/msg/pose.hpp>
27-
#include <tier4_planning_msgs/msg/path_point_with_lane_id.hpp>
28-
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
2927

3028
#include <lanelet2_core/LaneletMap.h>
3129

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,6 @@
3131
#include <nav_msgs/msg/odometry.hpp>
3232
#include <sensor_msgs/msg/point_cloud2.hpp>
3333
#include <std_msgs/msg/header.hpp>
34-
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
3534

3635
#include <lanelet2_core/Forward.h>
3736
#include <pcl/point_cloud.h>
@@ -72,7 +71,6 @@ struct PlannerData
7271
// last observed infomation for UNKNOWN
7372
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_raw_;
7473
std::map<lanelet::Id, TrafficSignalStamped> traffic_light_id_map_last_observed_;
75-
std::optional<tier4_planning_msgs::msg::VelocityLimit> external_velocity_limit;
7674

7775
// velocity smoother
7876
std::shared_ptr<autoware::velocity_smoother::SmootherBase> velocity_smoother_;

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,6 @@
2828
<depend>geometry_msgs</depend>
2929
<depend>libboost-dev</depend>
3030
<depend>rclcpp</depend>
31-
<depend>tier4_planning_msgs</depend>
3231
<depend>visualization_msgs</depend>
3332

3433
<test_depend>ament_cmake_ros</test_depend>

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml

-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,6 @@
3939
<depend>tf2_geometry_msgs</depend>
4040
<depend>tf2_ros</depend>
4141
<depend>tier4_metric_msgs</depend>
42-
<depend>tier4_planning_msgs</depend>
4342
<depend>visualization_msgs</depend>
4443

4544
<exec_depend>rosidl_default_runtime</exec_depend>

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp

-5
Original file line numberDiff line numberDiff line change
@@ -357,7 +357,6 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s
357357
const geometry_msgs::msg::Pose current_pose = planner_data.current_odometry.pose.pose;
358358
const double v0 = planner_data.current_odometry.twist.twist.linear.x;
359359
const double a0 = planner_data.current_acceleration.accel.accel.linear.x;
360-
const auto & external_v_limit = planner_data.external_velocity_limit;
361360
const auto & smoother = planner_data.velocity_smoother_;
362361

363362
const auto traj_lateral_acc_filtered =
@@ -382,10 +381,6 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s
382381
if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories, false)) {
383382
RCLCPP_ERROR(get_logger(), "failed to smooth");
384383
}
385-
if (external_v_limit) {
386-
autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
387-
0LU, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed);
388-
}
389384
return traj_smoothed;
390385
}
391386

0 commit comments

Comments
 (0)