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(motion_velocity_smoother): remove duplicated implementation #2798

Merged
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 @@ -208,6 +208,10 @@ class MotionVelocitySmootherNode : public rclcpp::Node
Trajectory toTrajectoryMsg(
const TrajectoryPoints & points, const std_msgs::msg::Header * header = nullptr) const;

TrajectoryPoint calcProjectedTrajectoryPoint(
const TrajectoryPoints & trajectory, const Pose & pose) const;
TrajectoryPoint calcProjectedTrajectoryPointFromEgo(const TrajectoryPoints & trajectory) const;

// parameter handling
void initCommonParam();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -399,12 +399,7 @@ void MotionVelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstShar

// calculate prev closest point
if (!prev_output_.empty()) {
const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
prev_output_, current_odometry_ptr_->pose.pose, node_param_.ego_nearest_dist_threshold,
node_param_.ego_nearest_yaw_threshold);
const auto closest_point = trajectory_utils::calcInterpolatedTrajectoryPoint(
prev_output_, current_odometry_ptr_->pose.pose, current_seg_idx);
current_closest_point_from_prev_output_ = closest_point;
current_closest_point_from_prev_output_ = calcProjectedTrajectoryPointFromEgo(prev_output_);
}

// calculate distance to insert external velocity limit
Expand Down Expand Up @@ -884,11 +879,7 @@ void MotionVelocitySmootherNode::publishClosestVelocity(
const TrajectoryPoints & trajectory, const Pose & current_pose,
const rclcpp::Publisher<Float32Stamped>::SharedPtr pub) const
{
const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
trajectory, current_pose, node_param_.ego_nearest_dist_threshold,
node_param_.ego_nearest_yaw_threshold);
const auto closest_point =
trajectory_utils::calcInterpolatedTrajectoryPoint(trajectory, current_pose, current_seg_idx);
const auto closest_point = calcProjectedTrajectoryPoint(trajectory, current_pose);

Float32Stamped vel_data{};
vel_data.stamp = this->now();
Expand All @@ -898,11 +889,7 @@ void MotionVelocitySmootherNode::publishClosestVelocity(

void MotionVelocitySmootherNode::publishClosestState(const TrajectoryPoints & trajectory)
{
const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
trajectory, current_odometry_ptr_->pose.pose, node_param_.ego_nearest_dist_threshold,
node_param_.ego_nearest_yaw_threshold);
const auto closest_point = trajectory_utils::calcInterpolatedTrajectoryPoint(
trajectory, current_odometry_ptr_->pose.pose, current_seg_idx);
const auto closest_point = calcProjectedTrajectoryPointFromEgo(trajectory);

auto publishFloat = [=](const double data, const auto pub) {
Float32Stamped msg{};
Expand Down Expand Up @@ -938,12 +925,7 @@ void MotionVelocitySmootherNode::publishClosestState(const TrajectoryPoints & tr
void MotionVelocitySmootherNode::updatePrevValues(const TrajectoryPoints & final_result)
{
prev_output_ = final_result;
const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
final_result, current_odometry_ptr_->pose.pose, node_param_.ego_nearest_dist_threshold,
node_param_.ego_nearest_yaw_threshold);
const auto closest_point = trajectory_utils::calcInterpolatedTrajectoryPoint(
final_result, current_odometry_ptr_->pose.pose, current_seg_idx);
prev_closest_point_ = closest_point;
prev_closest_point_ = calcProjectedTrajectoryPointFromEgo(final_result);
}

MotionVelocitySmootherNode::AlgorithmType MotionVelocitySmootherNode::getAlgorithmType(
Expand All @@ -968,11 +950,7 @@ MotionVelocitySmootherNode::AlgorithmType MotionVelocitySmootherNode::getAlgorit

double MotionVelocitySmootherNode::calcTravelDistance() const
{
const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
prev_output_, current_odometry_ptr_->pose.pose, node_param_.ego_nearest_dist_threshold,
node_param_.ego_nearest_yaw_threshold);
const auto closest_point = trajectory_utils::calcInterpolatedTrajectoryPoint(
prev_output_, current_odometry_ptr_->pose.pose, current_seg_idx);
const auto closest_point = calcProjectedTrajectoryPointFromEgo(prev_output_);

if (prev_closest_point_) {
const double travel_dist =
Expand Down Expand Up @@ -1027,6 +1005,21 @@ void MotionVelocitySmootherNode::publishStopWatchTime()
debug_calculation_time_->publish(calculation_time_data);
}

TrajectoryPoint MotionVelocitySmootherNode::calcProjectedTrajectoryPoint(
const TrajectoryPoints & trajectory, const Pose & pose) const
{
const size_t current_seg_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
trajectory, pose, node_param_.ego_nearest_dist_threshold,
node_param_.ego_nearest_yaw_threshold);
return trajectory_utils::calcInterpolatedTrajectoryPoint(trajectory, pose, current_seg_idx);
}

TrajectoryPoint MotionVelocitySmootherNode::calcProjectedTrajectoryPointFromEgo(
const TrajectoryPoints & trajectory) const
{
return calcProjectedTrajectoryPoint(trajectory, current_odometry_ptr_->pose.pose);
}

} // namespace motion_velocity_smoother

#include "rclcpp_components/register_node_macro.hpp"
Expand Down