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(obstacle_velocity_limiter): use motion_utils instead of motion_common #2273

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 @@ -19,7 +19,6 @@
#include "obstacle_velocity_limiter/parameters.hpp"
#include "obstacle_velocity_limiter/types.hpp"

#include <experimental/optional>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/self_pose_listener.hpp>
#include <tier4_autoware_utils/ros/transform_listener.hpp>
Expand All @@ -32,6 +31,8 @@
#include <std_msgs/msg/int64.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <boost/optional.hpp>

#include <lanelet2_core/LaneletMap.h>

#include <memory>
Expand Down Expand Up @@ -101,7 +102,7 @@ class ObstacleVelocityLimiterNode : public rclcpp::Node
/// @brief validate the inputs of the node
/// @param[in] ego_idx trajectory index closest to the current ego pose
/// @return true if the inputs are valid
bool validInputs(const std::experimental::fundamentals_v1::optional<size_t> & ego_idx);
bool validInputs(const boost::optional<size_t> & ego_idx);
};
} // namespace obstacle_velocity_limiter

Expand Down
2 changes: 1 addition & 1 deletion planning/obstacle_velocity_limiter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<depend>lanelet2_core</depend>
<depend>lanelet2_extension</depend>
<depend>libboost-dev</depend>
<depend>motion_common</depend>
<depend>motion_utils</depend>
<depend>nav_msgs</depend>
<depend>pcl_ros</depend>
<depend>rclcpp</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "obstacle_velocity_limiter/types.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <motion_common/trajectory_common.hpp>
#include <motion_utils/motion_utils.hpp>
#include <rclcpp/duration.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp/qos.hpp>
Expand Down Expand Up @@ -177,8 +177,7 @@ void ObstacleVelocityLimiterNode::onTrajectory(const Trajectory::ConstSharedPtr
get_logger(), *get_clock(), rcutils_duration_value_t(1000), "Waiting for current pose");
return;
}
const auto ego_idx =
autoware::motion::motion_common::findNearestIndex(msg->points, current_pose_ptr->pose);
const auto ego_idx = motion_utils::findNearestIndex(msg->points, current_pose_ptr->pose);
if (!validInputs(ego_idx)) return;
auto original_traj = *msg;
if (preprocessing_params_.calculate_steering_angles)
Expand Down Expand Up @@ -235,8 +234,7 @@ void ObstacleVelocityLimiterNode::onTrajectory(const Trajectory::ConstSharedPtr
}
}

bool ObstacleVelocityLimiterNode::validInputs(
const std::experimental::fundamentals_v1::optional<size_t> & ego_idx)
bool ObstacleVelocityLimiterNode::validInputs(const boost::optional<size_t> & ego_idx)
{
constexpr auto one_sec = rcutils_duration_value_t(1000);
if (!occupancy_grid_ptr_)
Expand Down