lgtm fixes (#19610)

* pass matrices by reference

* suppress that

* destructor

* that's wrong, suppress it
pull/19618/head
Adeeb Shihadeh 2020-12-28 20:36:23 -08:00 committed by GitHub
parent e158014a26
commit 4096f86e21
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
5 changed files with 7 additions and 6 deletions

View File

@ -39,7 +39,7 @@ Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat){
return quat.toRotationMatrix(); return quat.toRotationMatrix();
} }
Eigen::Quaterniond rot2quat(Eigen::Matrix3d rot){ Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot){
return ensure_unique(Eigen::Quaterniond(rot)); return ensure_unique(Eigen::Quaterniond(rot));
} }
@ -47,7 +47,7 @@ Eigen::Matrix3d euler2rot(Eigen::Vector3d euler){
return quat2rot(euler2quat(euler)); return quat2rot(euler2quat(euler));
} }
Eigen::Vector3d rot2euler(Eigen::Matrix3d rot){ Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot){
return quat2euler(rot2quat(rot)); return quat2euler(rot2quat(rot));
} }

View File

@ -8,9 +8,9 @@ Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat);
Eigen::Quaterniond euler2quat(Eigen::Vector3d euler); Eigen::Quaterniond euler2quat(Eigen::Vector3d euler);
Eigen::Vector3d quat2euler(Eigen::Quaterniond quat); Eigen::Vector3d quat2euler(Eigen::Quaterniond quat);
Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat); Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat);
Eigen::Quaterniond rot2quat(Eigen::Matrix3d rot); Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot);
Eigen::Matrix3d euler2rot(Eigen::Vector3d euler); Eigen::Matrix3d euler2rot(Eigen::Vector3d euler);
Eigen::Vector3d rot2euler(Eigen::Matrix3d rot); Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot);
Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw); Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw);
Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle); Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle);
Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose); Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose);

View File

@ -70,7 +70,7 @@ def mpc_vwr_thread(addr="127.0.0.1"):
l_poly = np.array(md.model.leftLane.poly) l_poly = np.array(md.model.leftLane.poly)
r_poly = np.array(md.model.rightLane.poly) r_poly = np.array(md.model.rightLane.poly)
p_path_y = np.polyval(p_poly, path_x) p_path_y = np.polyval(p_poly, path_x) # lgtm[py/multiple-definition]
l_path_y = np.polyval(r_poly, path_x) l_path_y = np.polyval(r_poly, path_x)
r_path_y = np.polyval(l_poly, path_x) r_path_y = np.polyval(l_poly, path_x)

View File

@ -378,7 +378,7 @@ class LocKalman():
self.dim_state_err = self.dim_main_err + self.dim_augment_err * self.N self.dim_state_err = self.dim_main_err + self.dim_augment_err * self.N
if self.N > 0: if self.N > 0:
x_initial, P_initial, Q = self.pad_augmented(self.x_initial, self.P_initial, self.Q) # pylint: disable=unbalanced-tuple-unpacking x_initial, P_initial, Q = self.pad_augmented(self.x_initial, self.P_initial, self.Q) # lgtm[py/mismatched-multiple-assignment] pylint: disable=unbalanced-tuple-unpacking
self.computer = LstSqComputer(generated_dir, N) self.computer = LstSqComputer(generated_dir, N)
self.max_tracks = max_tracks self.max_tracks = max_tracks

View File

@ -4,6 +4,7 @@
class Sensor { class Sensor {
public: public:
virtual ~Sensor() {};
virtual int init() = 0; virtual int init() = 0;
virtual void get_event(cereal::SensorEventData::Builder &event) = 0; virtual void get_event(cereal::SensorEventData::Builder &event) = 0;
}; };