diff --git a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp index 705d6ba56bb..dbd0949dfb6 100644 --- a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp +++ b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp @@ -245,7 +245,7 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity // Find look ahead distance and point on path and publish const double lookahead_dist = getLookAheadDistance(speed); auto carrot_pose = getLookAheadPoint(lookahead_dist, transformed_plan); - carrot_pub_->publish(std::move(createCarrotMsg(carrot_pose))); + carrot_pub_->publish(createCarrotMsg(carrot_pose)); double linear_vel, angular_vel;