Skip to content

Commit

Permalink
use a constant distance margin instead of wheelbase length
Browse files Browse the repository at this point in the history
Signed-off-by: mohammad alqudah <[email protected]>
  • Loading branch information
mkquda committed Dec 19, 2024
1 parent cb975c2 commit a37f673
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -522,8 +522,6 @@ class MPC
* @param clock The shared pointer to the RCLCPP clock.
*/
inline void setClock(rclcpp::Clock::SharedPtr clock) { m_clock = clock; }

inline double get_wheelbase_length() { return m_vehicle_model_ptr->getWheelbase(); }
}; // class MPC
} // namespace autoware::motion::control::mpc_lateral_controller

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -419,15 +419,15 @@ bool MpcLateralController::isStoppedState() const
m_current_trajectory.points, m_current_kinematic_state.pose.pose, m_ego_nearest_dist_threshold,
m_ego_nearest_yaw_threshold);

const auto wheelbase_length = m_mpc->get_wheelbase_length();
static constexpr double distance_margin = 1.0;
const double target_vel = std::invoke([&]() -> double {
auto min_vel = m_current_trajectory.points.at(nearest).longitudinal_velocity_mps;
auto covered_distance = 0.0;
for (auto i = nearest + 1; i < m_current_trajectory.points.size(); ++i) {
min_vel = std::min(min_vel, m_current_trajectory.points.at(i).longitudinal_velocity_mps);
covered_distance += autoware::universe_utils::calcDistance2d(
m_current_trajectory.points.at(i - 1).pose, m_current_trajectory.points.at(i).pose);
if (covered_distance > wheelbase_length) break;
if (covered_distance > distance_margin) break;
}
return min_vel;
});
Expand Down

0 comments on commit a37f673

Please sign in to comment.