Skip to content

Commit

Permalink
feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs…
Browse files Browse the repository at this point in the history
… dependency (#9757)

* feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency

Signed-off-by: Takayuki Murooka <[email protected]>

* fix

Signed-off-by: Takayuki Murooka <[email protected]>

---------

Signed-off-by: Takayuki Murooka <[email protected]>
  • Loading branch information
takayuki5168 authored Dec 24, 2024
1 parent 7102a48 commit 24bcd0e
Show file tree
Hide file tree
Showing 8 changed files with 0 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>tf2</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@
<depend>sensor_msgs</depend>
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>tf2</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@

#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <tier4_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>

#include <lanelet2_core/LaneletMap.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@
#include <nav_msgs/msg/odometry.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/header.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>

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

// velocity smoother
std::shared_ptr<autoware::velocity_smoother::SmootherBase> velocity_smoother_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
<depend>geometry_msgs</depend>
<depend>libboost-dev</depend>
<depend>rclcpp</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_metric_msgs</depend>
<depend>tier4_planning_msgs</depend>
<depend>visualization_msgs</depend>

<exec_depend>rosidl_default_runtime</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -357,7 +357,6 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s
const geometry_msgs::msg::Pose current_pose = planner_data.current_odometry.pose.pose;
const double v0 = planner_data.current_odometry.twist.twist.linear.x;
const double a0 = planner_data.current_acceleration.accel.accel.linear.x;
const auto & external_v_limit = planner_data.external_velocity_limit;
const auto & smoother = planner_data.velocity_smoother_;

const auto traj_lateral_acc_filtered =
Expand All @@ -382,10 +381,6 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s
if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories, false)) {
RCLCPP_ERROR(get_logger(), "failed to smooth");
}
if (external_v_limit) {
autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
0LU, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed);
}
return traj_smoothed;
}

Expand Down

0 comments on commit 24bcd0e

Please sign in to comment.