Skip to content

Commit f46c980

Browse files
style(pre-commit): autofix
1 parent d0cfc56 commit f46c980

File tree

2 files changed

+41
-21
lines changed
  • control/mpc_lateral_controller

2 files changed

+41
-21
lines changed

control/mpc_lateral_controller/include/mpc_lateral_controller/mpc.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -380,8 +380,8 @@ class MPC
380380
const MPCTrajectory & reference_trajectory, const MPCData & mpc_data_traj_raw,
381381
const MPCData & mpc_data, const MPCMatrix & mpc_matrix,
382382
const AckermannLateralCommand & ctrl_cmd, const VectorXd & Uex,
383-
const Odometry & current_kinematics,
384-
bool success_data_for_diagnostic , bool success_data_traj_raw) const;
383+
const Odometry & current_kinematics, bool success_data_for_diagnostic,
384+
bool success_data_traj_raw) const;
385385

386386
/**
387387
* @brief calculate steering rate limit along with the target trajectory

control/mpc_lateral_controller/src/mpc.cpp

+39-19
Original file line numberDiff line numberDiff line change
@@ -127,7 +127,8 @@ bool MPC::calculateMPC(
127127
Float32MultiArrayStamped MPC::generateDiagData(
128128
const MPCTrajectory & reference_trajectory, const MPCData & mpc_data_traj_raw,
129129
const MPCData & mpc_data, const MPCMatrix & mpc_matrix, const AckermannLateralCommand & ctrl_cmd,
130-
const VectorXd & Uex, const Odometry & current_kinematics, bool success_data_for_diagnostic , bool success_data_traj_raw) const
130+
const VectorXd & Uex, const Odometry & current_kinematics, bool success_data_for_diagnostic,
131+
bool success_data_traj_raw) const
131132
{
132133
Float32MultiArrayStamped diagnostic;
133134

@@ -147,31 +148,50 @@ Float32MultiArrayStamped MPC::generateDiagData(
147148
const auto append_diag = [&](const auto & val) -> void {
148149
diagnostic.data.push_back(static_cast<DiagnosticValueType>(val));
149150
};
150-
append_diag(ctrl_cmd.steering_tire_angle); // [0] final steering command (MPC + LPF)
151-
append_diag(Uex(0)); // [1] mpc calculation result
152-
append_diag(mpc_matrix.Uref_ex(0)); // [2] feed-forward steering value
153-
append_diag(success_data_for_diagnostic ? std::atan(nearest_smooth_k * wb) : -1.0); // [3] feed-forward steering value raw
154-
append_diag(success_data_for_diagnostic ? mpc_data.steer : -1.0); // [4] current steering angle
155-
append_diag(success_data_for_diagnostic ? mpc_data.lateral_err : -1.0); // [5] lateral error (the actual error used for MPC)
151+
append_diag(ctrl_cmd.steering_tire_angle); // [0] final steering command (MPC + LPF)
152+
append_diag(Uex(0)); // [1] mpc calculation result
153+
append_diag(mpc_matrix.Uref_ex(0)); // [2] feed-forward steering value
154+
append_diag(
155+
success_data_for_diagnostic ? std::atan(nearest_smooth_k * wb)
156+
: -1.0); // [3] feed-forward steering value raw
157+
append_diag(success_data_for_diagnostic ? mpc_data.steer : -1.0); // [4] current steering angle
158+
append_diag(
159+
success_data_for_diagnostic ? mpc_data.lateral_err
160+
: -1.0); // [5] lateral error (the actual error used for MPC)
156161
append_diag(tf2::getYaw(current_kinematics.pose.pose.orientation)); // [6] current_pose yaw
157-
append_diag(success_data_for_diagnostic ? tf2::getYaw(mpc_data.nearest_pose.orientation) : -1.0); // [7] nearest_pose yaw
158-
append_diag(success_data_for_diagnostic ? mpc_data.yaw_err : -1.0); // [8] yaw error
159-
append_diag(success_data_for_diagnostic ? reference_trajectory.vx.at(mpc_data.nearest_idx) : -1.0); // [9] reference velocity
160-
append_diag(current_velocity); // [10] measured velocity
161-
append_diag(wz_command); // [11] angular velocity from steer command
162-
append_diag(success_data_for_diagnostic ? wz_measured : -1.0); // [12] angular velocity from measured steer
163-
append_diag(success_data_for_diagnostic ? current_velocity * nearest_smooth_k : -1.0); // [13] angular velocity from path curvature
164-
append_diag(success_data_for_diagnostic ? nearest_smooth_k : -1.0); // [14] nearest path curvature (used for feed-forward)
165-
append_diag(success_data_for_diagnostic ? nearest_k : -1.0); // [15] nearest path curvature (not smoothed)
166-
append_diag(success_data_for_diagnostic ? mpc_data.predicted_steer : -1.0); // [16] predicted steer
167-
append_diag(success_data_for_diagnostic ? wz_predicted : -1.0); // [17] angular velocity from predicted steer
162+
append_diag(
163+
success_data_for_diagnostic ? tf2::getYaw(mpc_data.nearest_pose.orientation)
164+
: -1.0); // [7] nearest_pose yaw
165+
append_diag(success_data_for_diagnostic ? mpc_data.yaw_err : -1.0); // [8] yaw error
166+
append_diag(
167+
success_data_for_diagnostic ? reference_trajectory.vx.at(mpc_data.nearest_idx)
168+
: -1.0); // [9] reference velocity
169+
append_diag(current_velocity); // [10] measured velocity
170+
append_diag(wz_command); // [11] angular velocity from steer command
171+
append_diag(
172+
success_data_for_diagnostic ? wz_measured : -1.0); // [12] angular velocity from measured steer
173+
append_diag(
174+
success_data_for_diagnostic ? current_velocity * nearest_smooth_k
175+
: -1.0); // [13] angular velocity from path curvature
176+
append_diag(
177+
success_data_for_diagnostic ? nearest_smooth_k
178+
: -1.0); // [14] nearest path curvature (used for feed-forward)
179+
append_diag(
180+
success_data_for_diagnostic ? nearest_k : -1.0); // [15] nearest path curvature (not smoothed)
181+
append_diag(
182+
success_data_for_diagnostic ? mpc_data.predicted_steer : -1.0); // [16] predicted steer
183+
append_diag(
184+
success_data_for_diagnostic ? wz_predicted
185+
: -1.0); // [17] angular velocity from predicted steer
168186
append_diag(iteration_num); // [18] iteration number
169187
append_diag(runtime); // [19] runtime of the latest problem solved
170188
append_diag(objective_value); // [20] objective value of the latest problem solved
171189
append_diag(std::clamp(
172190
Uex(0), -m_steer_lim,
173191
m_steer_lim)); // [21] control signal after the saturation constraint (clamp)
174-
append_diag(success_data_traj_raw ? mpc_data_traj_raw.lateral_err : -1.0); // [22] lateral error from raw trajectory
192+
append_diag(
193+
success_data_traj_raw ? mpc_data_traj_raw.lateral_err
194+
: -1.0); // [22] lateral error from raw trajectory
175195

176196
return diagnostic;
177197
}

0 commit comments

Comments
 (0)