Skip to content

Commit

Permalink
modify dependant packages
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <[email protected]>
  • Loading branch information
takayuki5168 committed Dec 24, 2024
1 parent d8464c8 commit 93aad5a
Show file tree
Hide file tree
Showing 13 changed files with 26 additions and 24 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
<depend>autoware_planning_msgs</depend>
<depend>autoware_route_handler</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_velocity_smoother</depend>
<depend>autoware_universe_velocity_smoother</depend>
<depend>diagnostic_msgs</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@
#include <autoware/behavior_velocity_planner_common/utilization/path_utilization.hpp>
#include <autoware/motion_utils/trajectory/path_with_lane_id.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/universe/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp>
#include <autoware/universe_utils/ros/wait_for_param.hpp>
#include <autoware/universe_utils/transform/transforms.hpp>
#include <autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp>
#include <autoware_lanelet2_extension/utility/message_conversion.hpp>

#include <diagnostic_msgs/msg/diagnostic_status.hpp>
Expand Down Expand Up @@ -133,7 +133,8 @@ void BehaviorVelocityPlannerNode::onParam()
// constructed. It would be required if it was a callback. std::lock_guard<std::mutex>
// lock(mutex_);
planner_data_.velocity_smoother_ =
std::make_unique<autoware::velocity_smoother::AnalyticalJerkConstrainedSmoother>(*this);
std::make_unique<autoware::universe::velocity_smoother::AnalyticalJerkConstrainedSmoother>(
*this);
planner_data_.velocity_smoother_->setWheelBase(planner_data_.vehicle_info_.wheel_base_m);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
const auto behavior_velocity_planner_dir =
ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_planner");
const auto velocity_smoother_dir =
ament_index_cpp::get_package_share_directory("autoware_velocity_smoother");
ament_index_cpp::get_package_share_directory("autoware_universe_velocity_smoother");

const auto get_behavior_velocity_module_config = [](const std::string & module) {
const auto package_name = "autoware_behavior_velocity_" + module + "_module";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "autoware/behavior_velocity_planner_common/utilization/util.hpp"
#include "autoware/route_handler/route_handler.hpp"
#include "autoware/velocity_smoother/smoother/smoother_base.hpp"
#include "autoware/universe/velocity_smoother/smoother/smoother_base.hpp"
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"

#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
Expand Down Expand Up @@ -68,7 +68,7 @@ struct PlannerData

bool is_simulation = false;

std::shared_ptr<autoware::velocity_smoother::SmootherBase> velocity_smoother_;
std::shared_ptr<autoware::universe::velocity_smoother::SmootherBase> velocity_smoother_;
std::shared_ptr<autoware::route_handler::RouteHandler> route_handler_;
autoware::vehicle_info_utils::VehicleInfo vehicle_info_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@
<depend>autoware_route_handler</depend>
<depend>autoware_rtc_interface</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_universe_velocity_smoother</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_velocity_smoother</depend>
<depend>diagnostic_msgs</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include <autoware/behavior_velocity_planner_common/utilization/trajectory_utils.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/velocity_smoother/trajectory_utils.hpp>
#include <autoware/universe/velocity_smoother/trajectory_utils.hpp>
#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/quaternion.hpp>
Expand Down Expand Up @@ -90,7 +90,7 @@ bool smoothPath(
traj_resampled.begin() + static_cast<std::ptrdiff_t>(traj_resampled_closest));

if (external_v_limit) {
autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
autoware::universe::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed);
}
out_path = autoware::motion_utils::convertToPathWithLaneId<TrajectoryPoints>(traj_smoothed);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
// limitations under the License.

#include "autoware/behavior_velocity_planner_common/utilization/trajectory_utils.hpp"
#include "autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp"
#include "autoware/universe/velocity_smoother/smoother/jerk_filtered_smoother.hpp"

#include <ament_index_cpp/get_package_share_directory.hpp>
#include <rclcpp/node.hpp>
Expand Down Expand Up @@ -41,13 +41,13 @@ TEST(smoothPath, nominal)
ament_index_cpp::get_package_share_directory("autoware_test_utils") +
"/config/test_vehicle_info.param.yaml",
"--params-file",
ament_index_cpp::get_package_share_directory("autoware_velocity_smoother") +
ament_index_cpp::get_package_share_directory("autoware_universe_velocity_smoother") +
"/config/default_common.param.yaml",
"--params-file",
ament_index_cpp::get_package_share_directory("autoware_velocity_smoother") +
ament_index_cpp::get_package_share_directory("autoware_universe_velocity_smoother") +
"/config/default_velocity_smoother.param.yaml",
"--params-file",
ament_index_cpp::get_package_share_directory("autoware_velocity_smoother") +
ament_index_cpp::get_package_share_directory("autoware_universe_velocity_smoother") +
"/config/JerkFiltered.param.yaml"});
auto node = std::make_shared<rclcpp::Node>("test_node", options);

Expand Down Expand Up @@ -76,7 +76,7 @@ TEST(smoothPath, nominal)
}());

planner_data->velocity_smoother_ =
std::make_shared<autoware::velocity_smoother::JerkFilteredSmoother>(
std::make_shared<autoware::universe::velocity_smoother::JerkFilteredSmoother>(
*node, std::make_shared<autoware::universe_utils::TimeKeeper>());

// Input path
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
#include <autoware/motion_utils/distance/distance.hpp>
#include <autoware/motion_velocity_planner_common/collision_checker.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <autoware/universe/velocity_smoother/smoother/smoother_base.hpp>
#include <autoware/universe_utils/geometry/boost_polygon_utils.hpp>
#include <autoware/velocity_smoother/smoother/smoother_base.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>

#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
Expand Down Expand Up @@ -75,7 +75,7 @@ struct PlannerData
std::optional<tier4_planning_msgs::msg::VelocityLimit> external_velocity_limit;

// velocity smoother
std::shared_ptr<autoware::velocity_smoother::SmootherBase> velocity_smoother_;
std::shared_ptr<autoware::universe::velocity_smoother::SmootherBase> velocity_smoother_;
// parameters
autoware::vehicle_info_utils::VehicleInfo vehicle_info_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
<depend>autoware_planning_msgs</depend>
<depend>autoware_route_handler</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_velocity_smoother</depend>
<depend>autoware_universe_velocity_smoother</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>libboost-dev</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,5 +53,5 @@ In addition, the following parameters should be provided to the node:
- [nearest search parameters](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/common/nearest_search.param.yaml);
- [vehicle info parameters](https://github.com/autowarefoundation/sample_vehicle_launch/blob/main/sample_vehicle_description/config/vehicle_info.param.yaml);
- [common planning parameters](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/common/common.param.yaml);
- [smoother parameters](https://autowarefoundation.github.io/autoware.universe/main/planning/autoware_velocity_smoother/#parameters)
- [smoother parameters](https://autowarefoundation.github.io/autoware.universe/main/planning/autoware_universe_velocity_smoother/#parameters)
- Parameters of each plugin that will be loaded.
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_velocity_smoother</depend>
<depend>autoware_universe_velocity_smoother</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>libboost-dev</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,13 @@

#include <autoware/motion_utils/resample/resample.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/universe/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp>
#include <autoware/universe/velocity_smoother/trajectory_utils.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/ros/update_param.hpp>
#include <autoware/universe_utils/ros/wait_for_param.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <autoware/universe_utils/transform/transforms.hpp>
#include <autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp>
#include <autoware/velocity_smoother/trajectory_utils.hpp>
#include <tf2_eigen/tf2_eigen.hpp>

#include <autoware_planning_msgs/msg/trajectory_point.hpp>
Expand Down Expand Up @@ -214,7 +214,8 @@ MotionVelocityPlannerNode::process_no_ground_pointcloud(
void MotionVelocityPlannerNode::set_velocity_smoother_params()
{
planner_data_.velocity_smoother_ =
std::make_shared<autoware::velocity_smoother::AnalyticalJerkConstrainedSmoother>(*this);
std::make_shared<autoware::universe::velocity_smoother::AnalyticalJerkConstrainedSmoother>(
*this);
}

void MotionVelocityPlannerNode::on_lanelet_map(
Expand Down Expand Up @@ -382,7 +383,7 @@ autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::s
RCLCPP_ERROR(get_logger(), "failed to smooth");
}
if (external_v_limit) {
autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
autoware::universe::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
0LU, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed);
}
return traj_smoothed;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ std::shared_ptr<MotionVelocityPlannerNode> generateNode()
const auto motion_velocity_planner_dir =
ament_index_cpp::get_package_share_directory("autoware_motion_velocity_planner_node");
const auto velocity_smoother_dir =
ament_index_cpp::get_package_share_directory("autoware_velocity_smoother");
ament_index_cpp::get_package_share_directory("autoware_universe_velocity_smoother");

const auto get_motion_velocity_module_config = [](const std::string & module) {
const auto package_name = "autoware_motion_velocity_" + module + "_module";
Expand Down

0 comments on commit 93aad5a

Please sign in to comment.