Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Sep 26, 2023
1 parent bced5d0 commit 13d9b1e
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,6 @@ double getPitchByPose(const Quaternion & quaternion);
double getPitchByTraj(
const Trajectory & trajectory, const size_t start_idx, const double wheel_base);


/**
* @brief calculate vehicle pose after time delay by moving the vehicle at current velocity and
* acceleration for delayed time
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -975,13 +975,18 @@ PidLongitudinalController::StateAfterDelay PidLongitudinalController::predictedS
double PidLongitudinalController::applyVelocityFeedback(const ControlData & control_data)
{
const double current_vel = control_data.current_motion.vel;
const double target_vel = control_data.interpolated_traj.points.at(control_data.target_idx).longitudinal_velocity_mps;

const double target_vel =
control_data.interpolated_traj.points.at(control_data.target_idx).longitudinal_velocity_mps;

const double vel_after_delay= control_data.state_after_delay.vel;
const bool is_under_control = m_current_operation_mode.is_autoware_control_enabled &&
m_current_operation_mode.mode == OperationModeState::AUTONOMOUS; // NOTE: Acceleration command is always positive even if the ego drives backward.
const double vel_sign = (control_data.shift == Shift::Forward) ? 1.0 : (control_data.shift == Shift::Reverse ? -1.0 : 0.0);
const double vel_after_delay = control_data.state_after_delay.vel;
const bool is_under_control =
m_current_operation_mode.is_autoware_control_enabled &&
m_current_operation_mode.mode ==
OperationModeState::AUTONOMOUS; // NOTE: Acceleration command is always positive even if the
// ego drives backward.
const double vel_sign = (control_data.shift == Shift::Forward)
? 1.0
: (control_data.shift == Shift::Reverse ? -1.0 : 0.0);
const double diff_vel = (target_vel - vel_after_delay) * vel_sign;

const bool enable_integration =
Expand Down

0 comments on commit 13d9b1e

Please sign in to comment.