From 2a8875ac12e756bd34e96afd392f9743c657527c Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 20 Jun 2024 19:25:29 -0700 Subject: [PATCH] Address code quality warnings (1/N: readability-avoid-const-params-in-decls) (#19) Summary: Pull Request resolved: https://github.com/facebookincubator/momentum/pull/19 Reviewed By: EscapeZero Differential Revision: D58825200 fbshipit-source-id: 7e8e8478702593780b9965b49d20dc5276ad2a2e --- momentum/character/blend_shape.h | 2 +- momentum/character/blend_shape_base.h | 2 +- momentum/character/joint_state.h | 8 ++++---- momentum/character/linear_skinning.h | 2 +- momentum/character/parameter_limits.h | 2 +- .../multipose_solver_function.h | 6 +++--- .../sequence_solver_function.h | 12 +++++------- momentum/character_solver/aim_error_function.h | 4 ++-- .../character_solver/constraint_error_function.h | 2 +- .../character_solver/fixed_axis_error_function.h | 6 +++--- momentum/character_solver/normal_error_function.h | 2 +- .../character_solver/orientation_error_function.h | 2 +- momentum/character_solver/plane_error_function.h | 4 ++-- .../character_solver/position_error_function.h | 2 +- .../character_solver/simd_normal_error_function.h | 4 ++-- .../character_solver/simd_plane_error_function.h | 6 +++--- .../simd_position_error_function.h | 4 ++-- momentum/character_solver/vertex_error_function.h | 8 ++++---- momentum/gui/rerun/logger.h | 2 +- momentum/io/character_io.h | 6 +++--- momentum/io/fbx/fbx_io.h | 4 ++-- momentum/io/gltf/gltf_builder.hpp | 12 ++++++------ momentum/io/gltf/gltf_io.h | 8 ++++---- momentum/io/openfbx/polygon_data.h | 4 ++-- momentum/io/skeleton/locator_io.h | 2 +- momentum/math/online_householder_qr.h | 14 +++++++------- momentum/math/utility.h | 2 +- momentum/solver/solver.h | 2 +- momentum/test/character/character_helpers.h | 2 +- 29 files changed, 67 insertions(+), 69 deletions(-) diff --git a/momentum/character/blend_shape.h b/momentum/character/blend_shape.h index bc81ea47..e90f852a 100644 --- a/momentum/character/blend_shape.h +++ b/momentum/character/blend_shape.h @@ -39,7 +39,7 @@ struct BlendShape : public BlendShapeBase { VectorXf estimateCoefficients( gsl::span vertices, - const float regularization = 1.0f, + float regularization = 1.0f, const VectorXf& weights = VectorXf()) const; void setShapeVector(size_t index, gsl::span shapeVector); diff --git a/momentum/character/blend_shape_base.h b/momentum/character/blend_shape_base.h index 073cd8b8..83b3a007 100644 --- a/momentum/character/blend_shape_base.h +++ b/momentum/character/blend_shape_base.h @@ -18,7 +18,7 @@ namespace momentum { struct BlendShapeBase { public: BlendShapeBase() {} - BlendShapeBase(const size_t modelSize, const size_t numShapes); + BlendShapeBase(size_t modelSize, size_t numShapes); void setShapeVectors(const MatrixXf& shapeVectors) { shapeVectors_ = shapeVectors; diff --git a/momentum/character/joint_state.h b/momentum/character/joint_state.h index 052330d6..8150d643 100644 --- a/momentum/character/joint_state.h +++ b/momentum/character/joint_state.h @@ -60,13 +60,13 @@ struct JointStateT { // possible as this is part of many inner loops. /// The derivative of a global vector ref wrt the rotation parameters of the global /// transformation. - [[nodiscard]] Eigen::Vector3 getRotationDerivative( - const size_t index, - const Eigen::Vector3& ref) const; + [[nodiscard]] Eigen::Vector3 getRotationDerivative(size_t index, const Eigen::Vector3& ref) + const; /// The derivative of any global vector wrt the translation parameters of the global /// transformation. - [[nodiscard]] Eigen::Vector3 getTranslationDerivative(const size_t index) const; + [[nodiscard]] Eigen::Vector3 getTranslationDerivative(size_t index) const; + /// The derivative of a global vector ref wrt the scaling parameter of the global transformation. [[nodiscard]] Eigen::Vector3 getScaleDerivative(const Eigen::Vector3& ref) const noexcept; diff --git a/momentum/character/linear_skinning.h b/momentum/character/linear_skinning.h index 42ea1ed8..35548dea 100644 --- a/momentum/character/linear_skinning.h +++ b/momentum/character/linear_skinning.h @@ -41,7 +41,7 @@ Affine3f getInverseSSDTransformation( const TransformationList& inverseBindPose, const SkinWeights& skin, const SkeletonState& state, - const size_t index); + size_t index); std::vector applyInverseSSD( const TransformationList& inverseBindPose, diff --git a/momentum/character/parameter_limits.h b/momentum/character/parameter_limits.h index e7186a9c..5aa4a9f9 100644 --- a/momentum/character/parameter_limits.h +++ b/momentum/character/parameter_limits.h @@ -87,7 +87,7 @@ JointParameters applyJointParameterLimits( ParameterLimits getPoseConstraintParameterLimits( const std::string& name, const ParameterTransform& pt, - const float weight = 1.0f); + float weight = 1.0f); MOMENTUM_DEFINE_POINTERS(ParameterLimits) } // namespace momentum diff --git a/momentum/character_sequence_solver/multipose_solver_function.h b/momentum/character_sequence_solver/multipose_solver_function.h index f9616445..7f6ab844 100644 --- a/momentum/character_sequence_solver/multipose_solver_function.h +++ b/momentum/character_sequence_solver/multipose_solver_function.h @@ -23,7 +23,7 @@ class MultiposeSolverFunctionT : public SolverFunctionT { const Skeleton* skel, const ParameterTransformT* parameterTransform, gsl::span universal, - const size_t frames); + size_t frames); double getError(const Eigen::VectorX& parameters) final; @@ -38,7 +38,7 @@ class MultiposeSolverFunctionT : public SolverFunctionT { void updateParameters(Eigen::VectorX& parameters, const Eigen::VectorX& gradient) final; void setEnabledParameters(const ParameterSet&) final; - void addErrorFunction(const size_t frame, SkeletonErrorFunctionT* errorFunction); + void addErrorFunction(size_t frame, SkeletonErrorFunctionT* errorFunction); size_t getNumFrames() const { return states_.size(); @@ -48,7 +48,7 @@ class MultiposeSolverFunctionT : public SolverFunctionT { return frameParameters_[frame]; } - void setFrameParameters(const size_t frame, const ModelParametersT& parameters); + void setFrameParameters(size_t frame, const ModelParametersT& parameters); Eigen::VectorX getUniversalParameters(); Eigen::VectorX getJoinedParameterVector() const; void setJoinedParameterVector(const Eigen::VectorX& joinedParameters); diff --git a/momentum/character_sequence_solver/sequence_solver_function.h b/momentum/character_sequence_solver/sequence_solver_function.h index 6ba33a93..1f018cc8 100644 --- a/momentum/character_sequence_solver/sequence_solver_function.h +++ b/momentum/character_sequence_solver/sequence_solver_function.h @@ -27,7 +27,7 @@ class SequenceSolverFunctionT : public SolverFunctionT { const Skeleton* skel, const ParameterTransformT* parameterTransform, const ParameterSet& universal, - const size_t nFrames); + size_t nFrames); double getError(const Eigen::VectorX& parameters) final; @@ -50,22 +50,20 @@ class SequenceSolverFunctionT : public SolverFunctionT { // is convenient for e.g. limit errors but requires that the error function be stateless. Note: // you are allowed to call this in a multithreaded context but you must ensure the frame indices // are different between the different threads. - void addErrorFunction( - const size_t frame, - std::shared_ptr> errorFunction); + void addErrorFunction(size_t frame, std::shared_ptr> errorFunction); void addSequenceErrorFunction( - const size_t startFrame, + size_t startFrame, std::shared_ptr> errorFunction); size_t getNumFrames() const { return states_.size(); } - const ModelParametersT& getFrameParameters(const size_t frame) const { + const ModelParametersT& getFrameParameters(size_t frame) const { return frameParameters_[frame]; } - void setFrameParameters(const size_t frame, const ModelParametersT& parameters); + void setFrameParameters(size_t frame, const ModelParametersT& parameters); ModelParametersT getUniversalParameters() const; Eigen::VectorX getJoinedParameterVector() const; void setJoinedParameterVector(const Eigen::VectorX& joinedParameters); diff --git a/momentum/character_solver/aim_error_function.h b/momentum/character_solver/aim_error_function.h index 543b245b..a5552de8 100644 --- a/momentum/character_solver/aim_error_function.h +++ b/momentum/character_solver/aim_error_function.h @@ -66,7 +66,7 @@ class AimDistErrorFunctionT : public ConstraintErrorFunctionT, 3, protected: void evalFunction( - const size_t constrIndex, + size_t constrIndex, const JointStateT& state, Vector3&, optional_ref, 2>> v = {}, @@ -103,7 +103,7 @@ class AimDirErrorFunctionT : public ConstraintErrorFunctionT, 3, protected: void evalFunction( - const size_t constrIndex, + size_t constrIndex, const JointStateT& state, Vector3&, optional_ref, 2>> v = {}, diff --git a/momentum/character_solver/constraint_error_function.h b/momentum/character_solver/constraint_error_function.h index bfe7b350..9448cacd 100644 --- a/momentum/character_solver/constraint_error_function.h +++ b/momentum/character_solver/constraint_error_function.h @@ -213,7 +213,7 @@ class ConstraintErrorFunctionT : public SkeletonErrorFunctionT { /// @param[out] v: if valid, output the vector v=T*source; there could be NumVec of vs /// @param[out] dfdv: if valid, output the matrix df/dv of dimension FuncDim x 3 per v virtual void evalFunction( - const size_t constrIndex, + size_t constrIndex, const JointStateT& state, FuncType& f, optional_ref> v = {}, diff --git a/momentum/character_solver/fixed_axis_error_function.h b/momentum/character_solver/fixed_axis_error_function.h index f9898738..4b565a43 100644 --- a/momentum/character_solver/fixed_axis_error_function.h +++ b/momentum/character_solver/fixed_axis_error_function.h @@ -60,7 +60,7 @@ class FixedAxisDiffErrorFunctionT : public ConstraintErrorFunctionT& state, Vector3& f, optional_ref, 1>> v = {}, @@ -94,7 +94,7 @@ class FixedAxisCosErrorFunctionT : public ConstraintErrorFunctionT& state, Vector& f, optional_ref, 1>> v = {}, @@ -129,7 +129,7 @@ class FixedAxisAngleErrorFunctionT protected: void evalFunction( - const size_t constrIndex, + size_t constrIndex, const JointStateT& state, Vector& f, optional_ref, 1>> v = {}, diff --git a/momentum/character_solver/normal_error_function.h b/momentum/character_solver/normal_error_function.h index 83c50e3d..390dde8e 100644 --- a/momentum/character_solver/normal_error_function.h +++ b/momentum/character_solver/normal_error_function.h @@ -64,7 +64,7 @@ class NormalErrorFunctionT : public ConstraintErrorFunctionT, protected: void evalFunction( - const size_t constrIndex, + size_t constrIndex, const JointStateT& state, Vector&, optional_ref, 2>> v = {}, diff --git a/momentum/character_solver/orientation_error_function.h b/momentum/character_solver/orientation_error_function.h index 3836abc4..e55e9d2e 100644 --- a/momentum/character_solver/orientation_error_function.h +++ b/momentum/character_solver/orientation_error_function.h @@ -64,7 +64,7 @@ class OrientationErrorFunctionT : public ConstraintErrorFunctionT& state, Vector& f, optional_ref, 3>> v = {}, diff --git a/momentum/character_solver/plane_error_function.h b/momentum/character_solver/plane_error_function.h index f1204b3e..7105d2ac 100644 --- a/momentum/character_solver/plane_error_function.h +++ b/momentum/character_solver/plane_error_function.h @@ -36,7 +36,7 @@ std::vector> createFloorConstraints( const LocatorList& locators, const Vector3& floorNormal, const T& floorOffset, - const float weight); + float weight); /// The PlaneErrorFunction computes the 3D positional errors from a list of Constraints. /// Each constraint specifies a locator on the skeleton (parent joint and offset), and its target 3D @@ -86,7 +86,7 @@ class PlaneErrorFunctionT : public ConstraintErrorFunctionT, 1> protected: void evalFunction( - const size_t constrIndex, + size_t constrIndex, const JointStateT& state, Vector& f, optional_ref, 1>> = {}, diff --git a/momentum/character_solver/position_error_function.h b/momentum/character_solver/position_error_function.h index a3174f02..c39422c1 100644 --- a/momentum/character_solver/position_error_function.h +++ b/momentum/character_solver/position_error_function.h @@ -65,7 +65,7 @@ class PositionErrorFunctionT : public ConstraintErrorFunctionT& state, Vector3&, optional_ref, 1>> = {}, diff --git a/momentum/character_solver/simd_normal_error_function.h b/momentum/character_solver/simd_normal_error_function.h index c0fcf3b3..47fdeccb 100644 --- a/momentum/character_solver/simd_normal_error_function.h +++ b/momentum/character_solver/simd_normal_error_function.h @@ -26,11 +26,11 @@ struct SimdNormalConstraints { void clearConstraints(); bool addConstraint( - const size_t jointIndex, + size_t jointIndex, const Vector3f& offset, const Vector3f& normal, const Vector3f& target, - const float targetWeight); + float targetWeight); VectorXi getNumConstraints() const; diff --git a/momentum/character_solver/simd_plane_error_function.h b/momentum/character_solver/simd_plane_error_function.h index eccec632..2622ac15 100644 --- a/momentum/character_solver/simd_plane_error_function.h +++ b/momentum/character_solver/simd_plane_error_function.h @@ -28,11 +28,11 @@ struct SimdPlaneConstraints final { void clearConstraints(); void addConstraint( - const size_t jointIndex, + size_t jointIndex, const Vector3f& offset, const Vector3f& targetNormal, - const float targetOffset, - const float targetWeight); + float targetOffset, + float targetWeight); VectorXi getNumConstraints() const; diff --git a/momentum/character_solver/simd_position_error_function.h b/momentum/character_solver/simd_position_error_function.h index e81bdacb..593f2bcc 100644 --- a/momentum/character_solver/simd_position_error_function.h +++ b/momentum/character_solver/simd_position_error_function.h @@ -28,10 +28,10 @@ struct SimdPositionConstraints final { void clearConstraints(); void addConstraint( - const size_t jointIndex, + size_t jointIndex, const Vector3f& offset, const Vector3f& target, - const float targetWeight); + float targetWeight); VectorXi getNumConstraints() const; diff --git a/momentum/character_solver/vertex_error_function.h b/momentum/character_solver/vertex_error_function.h index b6b244e1..8b2fcccf 100644 --- a/momentum/character_solver/vertex_error_function.h +++ b/momentum/character_solver/vertex_error_function.h @@ -92,8 +92,8 @@ class VertexErrorFunctionT : public SkeletonErrorFunctionT { const ModelParametersT& modelParameters, const SkeletonStateT& state, const VertexConstraintT& constr, - const T sourceNormalWeight, - const T targetNormalWeight, + T sourceNormalWeight, + T targetNormalWeight, Ref> jac, T& res) const; @@ -107,8 +107,8 @@ class VertexErrorFunctionT : public SkeletonErrorFunctionT { const ModelParametersT& modelParameters, const SkeletonStateT& state, const VertexConstraintT& constr, - const T sourceNormalWeight, - const T targetNormalWeight, + T sourceNormalWeight, + T targetNormalWeight, Eigen::Ref> jointGrad) const; // Utility function used now in calculateNormalJacobian and calculatePositionGradient diff --git a/momentum/gui/rerun/logger.h b/momentum/gui/rerun/logger.h index 9d46336c..f7674032 100644 --- a/momentum/gui/rerun/logger.h +++ b/momentum/gui/rerun/logger.h @@ -40,7 +40,7 @@ void logMarkerLocatorCorrespondence( const std::map& locatorLookup, const LocatorState& locatorState, gsl::span markers, - const float kPositionErrorThreshold); + float kPositionErrorThreshold); void logBvh( const rerun::RecordingStream& rec, diff --git a/momentum/io/character_io.h b/momentum/io/character_io.h index e5b3e9af..5e6bbc1a 100644 --- a/momentum/io/character_io.h +++ b/momentum/io/character_io.h @@ -48,8 +48,8 @@ enum class CharacterFormat : uint8_t { /// @return The loaded Character object. [[nodiscard]] Character loadFullCharacterFromBuffer( CharacterFormat format, - const gsl::span characterBuffer, - const gsl::span paramBuffer = gsl::span(), - const gsl::span locBuffer = gsl::span()); + gsl::span characterBuffer, + gsl::span paramBuffer = gsl::span(), + gsl::span locBuffer = gsl::span()); } // namespace momentum diff --git a/momentum/io/fbx/fbx_io.h b/momentum/io/fbx/fbx_io.h index 3af89642..8a03944c 100644 --- a/momentum/io/fbx/fbx_io.h +++ b/momentum/io/fbx/fbx_io.h @@ -24,8 +24,8 @@ void saveFbx( const Character& character, const MatrixXf& poses = MatrixXf(), const VectorXf& identity = VectorXf(), - const double framerate = 120.0, - const bool saveMesh = false); + double framerate = 120.0, + bool saveMesh = false); // A shorthand of saveFbx() to save both the skeleton and mesh as a model but without any animation void saveFbxModel(const filesystem::path& filename, const Character& character); diff --git a/momentum/io/gltf/gltf_builder.hpp b/momentum/io/gltf/gltf_builder.hpp index bd09dd6d..f1699ca9 100644 --- a/momentum/io/gltf/gltf_builder.hpp +++ b/momentum/io/gltf/gltf_builder.hpp @@ -62,10 +62,10 @@ class GltfBuilder final { // the motion, the character will be automatically added with the default settings. void addMotion( const Character& character, - const float fps = 120.0f, + float fps = 120.0f, const MotionParameters& motion = {}, const IdentityParameters& offsets = {}, - const bool addExtensions = true, + bool addExtensions = true, const std::string& customName = "default"); // Add a skeleton states to the provided character. If addCharacter is not called before adding @@ -85,9 +85,9 @@ class GltfBuilder final { /// MarkerMesh::None). /// @param[in] animName Optional parameter specifying the animation name (default is "default"). void addMarkerSequence( - const float fps, + float fps, gsl::span> markerSequence, - const MarkerMesh markerMesh = MarkerMesh::None, + MarkerMesh markerMesh = MarkerMesh::None, const std::string& animName = "default"); // Save the file with the provided filename. If the fileFormat is 'GltfFileFormat::EXTENSION', @@ -95,13 +95,13 @@ class GltfBuilder final { // When embedResources is true, it will set all the existing buffers to embed the data. void save( const filesystem::path& filename, - const GltfFileFormat fileFormat = GltfFileFormat::EXTENSION, + GltfFileFormat fileFormat = GltfFileFormat::EXTENSION, bool embedResources = false); static void save( fx::gltf::Document& document, const filesystem::path& filename, - const GltfFileFormat fileFormat = GltfFileFormat::EXTENSION, + GltfFileFormat fileFormat = GltfFileFormat::EXTENSION, bool embedResources = false); // Set all existing buffers to embed resources. diff --git a/momentum/io/gltf/gltf_io.h b/momentum/io/gltf/gltf_io.h index d0f9aee4..2cc2d98d 100644 --- a/momentum/io/gltf/gltf_io.h +++ b/momentum/io/gltf/gltf_io.h @@ -71,7 +71,7 @@ std::tuple loadMotionOnCharacter( /// represented as joint parameters, and the fps. The model parameters and joint parameters are /// mapped to the input character by name matching. std::tuple loadMotionOnCharacter( - const gsl::span byteSpan, + gsl::span byteSpan, const Character& character); /// Loads a MarkerSequence from a file. @@ -82,7 +82,7 @@ MarkerSequence loadMarkerSequence(const filesystem::path& filename); fx::gltf::Document makeCharacterDocument( const Character& character, - const float fps = 120.0f, + float fps = 120.0f, const MotionParameters& motion = {}, const IdentityParameters& offsets = {}, const std::vector>& markerSequence = {}, @@ -97,11 +97,11 @@ fx::gltf::Document makeCharacterDocument( void saveCharacter( const filesystem::path& filename, const Character& Character, - const float fps = 120.0f, + float fps = 120.0f, const MotionParameters& motion = {}, const IdentityParameters& offsets = {}, const std::vector>& markerSequence = {}, - const GltfFileFormat fileFormat = GltfFileFormat::EXTENSION); + GltfFileFormat fileFormat = GltfFileFormat::EXTENSION); /// Saves character skeleton states to a glb file. /// diff --git a/momentum/io/openfbx/polygon_data.h b/momentum/io/openfbx/polygon_data.h index 2fc95e47..b5c7b898 100644 --- a/momentum/io/openfbx/polygon_data.h +++ b/momentum/io/openfbx/polygon_data.h @@ -46,10 +46,10 @@ struct PolygonData { // If everything is kosher, returns an empty string. // This function is used in a few places when reading the mesh from // disk to make sure it's valid. - std::string errorMessage(const size_t numVertices) const; + [[nodiscard]] std::string errorMessage(size_t numVertices) const; // Similar to errorMessage, but the issue is not severe enough to terminate. - std::string warnMessage(const size_t numTexVertices) const; + [[nodiscard]] std::string warnMessage(size_t numTexVertices) const; size_t numPolygons() const; }; diff --git a/momentum/io/skeleton/locator_io.h b/momentum/io/skeleton/locator_io.h index ccceb0fb..1efe7f8d 100644 --- a/momentum/io/skeleton/locator_io.h +++ b/momentum/io/skeleton/locator_io.h @@ -36,6 +36,6 @@ void saveLocators( const filesystem::path& filename, const LocatorList& locators, const Skeleton& skeleton, - const LocatorSpace space = LocatorSpace::Global); + LocatorSpace space = LocatorSpace::Global); } // namespace momentum diff --git a/momentum/math/online_householder_qr.h b/momentum/math/online_householder_qr.h index b16f86b9..42de1bfe 100644 --- a/momentum/math/online_householder_qr.h +++ b/momentum/math/online_householder_qr.h @@ -178,7 +178,7 @@ class OnlineHouseholderQR { // extra matrix: // | [ lambda * I ] [ x ] - [ 0 ] |^2 // | [ A ] [ b ] | - explicit OnlineHouseholderQR(const Eigen::Index n, T lambda = T(0)); + explicit OnlineHouseholderQR(Eigen::Index n, T lambda = T(0)); void addMutating(Eigen::Ref A, Eigen::Ref b) { addMutating(ColumnIndexedMatrix(A), b); @@ -205,7 +205,7 @@ class OnlineHouseholderQR { VectorType At_times_b() const; void reset(); - void reset(const Eigen::Index n, T lambda = T(0)); + void reset(Eigen::Index n, T lambda = T(0)); private: // R is defined by @@ -252,7 +252,7 @@ class OnlineBlockHouseholderQR { // extra matrix: // | [ lambda * I ] [ x ] - [ 0 ] |^2 // | [ A ] [ b ] | - explicit OnlineBlockHouseholderQR(const Eigen::Index n_common, T lambda = T(0)); + explicit OnlineBlockHouseholderQR(Eigen::Index n_common, T lambda = T(0)); void add(size_t iBlock, MatrixType A_diag, MatrixType A_common, VectorType b) { addMutating(iBlock, A_diag, A_common, b); @@ -379,9 +379,9 @@ class OnlineBandedHouseholderQR { // | [ lambda * I ] [ x ] - [ 0 ] |^2 // | [ A ] [ b ] | explicit OnlineBandedHouseholderQR( - const Eigen::Index n_band, + Eigen::Index n_band, Eigen::Index n_common, - const Eigen::Index bandwidth, + Eigen::Index bandwidth, T lambda = T(0)); void add(size_t iCol_offset, MatrixType A_band, MatrixType A_common, VectorType b) { @@ -416,7 +416,7 @@ class OnlineBandedHouseholderQR { // Mutating addition operator that also remaps the columns, allowing passing in arbitrary subsets // of the columns in A_diag and A_common. void addMutating( - const Eigen::Index iCol_offset, + Eigen::Index iCol_offset, ColumnIndexedMatrix A_band, ColumnIndexedMatrix A_common, Eigen::Ref b); @@ -434,7 +434,7 @@ class OnlineBandedHouseholderQR { // is much smaller than the number of banded variables this can provide a substantial // speedup in practice. void zeroBandedPart( - const Eigen::Index iCol_offset, + Eigen::Index iCol_offset, ColumnIndexedMatrix A_band, ColumnIndexedMatrix A_common, Eigen::Ref b); diff --git a/momentum/math/utility.h b/momentum/math/utility.h index fae32150..ffb986ae 100644 --- a/momentum/math/utility.h +++ b/momentum/math/utility.h @@ -201,7 +201,7 @@ template const Eigen::Vector3& d1, const Eigen::Vector3& o2, const Eigen::Vector3& d2, - const T maxDist = std::numeric_limits::max()); + T maxDist = std::numeric_limits::max()); // The skew-symmetric matrix that corresponds to the // cross product v x (something): diff --git a/momentum/solver/solver.h b/momentum/solver/solver.h index e68aece4..cc9904d5 100644 --- a/momentum/solver/solver.h +++ b/momentum/solver/solver.h @@ -58,7 +58,7 @@ class SolverT { void setParameters(const Eigen::VectorX& params); /// Sets the flag whether to store iteration history. - void setStoreHistory(const bool b); + void setStoreHistory(bool b); /// Returns the history of the solver's iterations. const std::unordered_map>& getHistory() const; diff --git a/momentum/test/character/character_helpers.h b/momentum/test/character/character_helpers.h index 421105d7..91178560 100644 --- a/momentum/test/character/character_helpers.h +++ b/momentum/test/character/character_helpers.h @@ -14,7 +14,7 @@ namespace momentum { // Matching methods void compareMeshes(const Mesh_u& refMesh, const Mesh_u& mesh); -void compareChars(const Character& refChar, const Character& character, const bool withMesh = true); +void compareChars(const Character& refChar, const Character& character, bool withMesh = true); /// Creates a character with a customizable number of joints. ///