Skip to content

Commit

Permalink
Address code quality warnings (1/N: readability-avoid-const-params-in…
Browse files Browse the repository at this point in the history
…-decls)

Differential Revision: D58825200
  • Loading branch information
jeongseok authored and facebook-github-bot committed Jun 20, 2024
1 parent bdf4158 commit 420c3eb
Show file tree
Hide file tree
Showing 29 changed files with 67 additions and 69 deletions.
2 changes: 1 addition & 1 deletion momentum/character/blend_shape.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ struct BlendShape : public BlendShapeBase {

VectorXf estimateCoefficients(
gsl::span<const Vector3f> vertices,
const float regularization = 1.0f,
float regularization = 1.0f,
const VectorXf& weights = VectorXf()) const;

void setShapeVector(size_t index, gsl::span<const Vector3f> shapeVector);
Expand Down
2 changes: 1 addition & 1 deletion momentum/character/blend_shape_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
8 changes: 4 additions & 4 deletions momentum/character/joint_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<T> getRotationDerivative(
const size_t index,
const Eigen::Vector3<T>& ref) const;
[[nodiscard]] Eigen::Vector3<T> getRotationDerivative(size_t index, const Eigen::Vector3<T>& ref)
const;

/// The derivative of any global vector wrt the translation parameters of the global
/// transformation.
[[nodiscard]] Eigen::Vector3<T> getTranslationDerivative(const size_t index) const;
[[nodiscard]] Eigen::Vector3<T> getTranslationDerivative(size_t index) const;

/// The derivative of a global vector ref wrt the scaling parameter of the global transformation.
[[nodiscard]] Eigen::Vector3<T> getScaleDerivative(const Eigen::Vector3<T>& ref) const noexcept;

Expand Down
2 changes: 1 addition & 1 deletion momentum/character/linear_skinning.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ Affine3f getInverseSSDTransformation(
const TransformationList& inverseBindPose,
const SkinWeights& skin,
const SkeletonState& state,
const size_t index);
size_t index);

std::vector<Vector3f> applyInverseSSD(
const TransformationList& inverseBindPose,
Expand Down
2 changes: 1 addition & 1 deletion momentum/character/parameter_limits.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class MultiposeSolverFunctionT : public SolverFunctionT<T> {
const Skeleton* skel,
const ParameterTransformT<T>* parameterTransform,
gsl::span<const int> universal,
const size_t frames);
size_t frames);

double getError(const Eigen::VectorX<T>& parameters) final;

Expand All @@ -38,7 +38,7 @@ class MultiposeSolverFunctionT : public SolverFunctionT<T> {
void updateParameters(Eigen::VectorX<T>& parameters, const Eigen::VectorX<T>& gradient) final;
void setEnabledParameters(const ParameterSet&) final;

void addErrorFunction(const size_t frame, SkeletonErrorFunctionT<T>* errorFunction);
void addErrorFunction(size_t frame, SkeletonErrorFunctionT<T>* errorFunction);

size_t getNumFrames() const {
return states_.size();
Expand All @@ -48,7 +48,7 @@ class MultiposeSolverFunctionT : public SolverFunctionT<T> {
return frameParameters_[frame];
}

void setFrameParameters(const size_t frame, const ModelParametersT<T>& parameters);
void setFrameParameters(size_t frame, const ModelParametersT<T>& parameters);
Eigen::VectorX<T> getUniversalParameters();
Eigen::VectorX<T> getJoinedParameterVector() const;
void setJoinedParameterVector(const Eigen::VectorX<T>& joinedParameters);
Expand Down
12 changes: 5 additions & 7 deletions momentum/character_sequence_solver/sequence_solver_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ class SequenceSolverFunctionT : public SolverFunctionT<T> {
const Skeleton* skel,
const ParameterTransformT<T>* parameterTransform,
const ParameterSet& universal,
const size_t nFrames);
size_t nFrames);

double getError(const Eigen::VectorX<T>& parameters) final;

Expand All @@ -50,22 +50,20 @@ class SequenceSolverFunctionT : public SolverFunctionT<T> {
// 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<SkeletonErrorFunctionT<T>> errorFunction);
void addErrorFunction(size_t frame, std::shared_ptr<SkeletonErrorFunctionT<T>> errorFunction);
void addSequenceErrorFunction(
const size_t startFrame,
size_t startFrame,
std::shared_ptr<SequenceErrorFunctionT<T>> errorFunction);

size_t getNumFrames() const {
return states_.size();
}

const ModelParametersT<T>& getFrameParameters(const size_t frame) const {
const ModelParametersT<T>& getFrameParameters(size_t frame) const {
return frameParameters_[frame];
}

void setFrameParameters(const size_t frame, const ModelParametersT<T>& parameters);
void setFrameParameters(size_t frame, const ModelParametersT<T>& parameters);
ModelParametersT<T> getUniversalParameters() const;
Eigen::VectorX<T> getJoinedParameterVector() const;
void setJoinedParameterVector(const Eigen::VectorX<T>& joinedParameters);
Expand Down
4 changes: 2 additions & 2 deletions momentum/character_solver/aim_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class AimDistErrorFunctionT : public ConstraintErrorFunctionT<T, AimDataT<T>, 3,

protected:
void evalFunction(
const size_t constrIndex,
size_t constrIndex,
const JointStateT<T>& state,
Vector3<T>&,
optional_ref<std::array<Vector3<T>, 2>> v = {},
Expand Down Expand Up @@ -103,7 +103,7 @@ class AimDirErrorFunctionT : public ConstraintErrorFunctionT<T, AimDataT<T>, 3,

protected:
void evalFunction(
const size_t constrIndex,
size_t constrIndex,
const JointStateT<T>& state,
Vector3<T>&,
optional_ref<std::array<Vector3<T>, 2>> v = {},
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/constraint_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ class ConstraintErrorFunctionT : public SkeletonErrorFunctionT<T> {
/// @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<T>& state,
FuncType& f,
optional_ref<std::array<VType, NumVec>> v = {},
Expand Down
6 changes: 3 additions & 3 deletions momentum/character_solver/fixed_axis_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class FixedAxisDiffErrorFunctionT : public ConstraintErrorFunctionT<T, FixedAxis

protected:
void evalFunction(
const size_t constrIndex,
size_t constrIndex,
const JointStateT<T>& state,
Vector3<T>& f,
optional_ref<std::array<Vector3<T>, 1>> v = {},
Expand Down Expand Up @@ -94,7 +94,7 @@ class FixedAxisCosErrorFunctionT : public ConstraintErrorFunctionT<T, FixedAxisD

protected:
void evalFunction(
const size_t constrIndex,
size_t constrIndex,
const JointStateT<T>& state,
Vector<T, 1>& f,
optional_ref<std::array<Vector3<T>, 1>> v = {},
Expand Down Expand Up @@ -129,7 +129,7 @@ class FixedAxisAngleErrorFunctionT

protected:
void evalFunction(
const size_t constrIndex,
size_t constrIndex,
const JointStateT<T>& state,
Vector<T, 1>& f,
optional_ref<std::array<Vector3<T>, 1>> v = {},
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/normal_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class NormalErrorFunctionT : public ConstraintErrorFunctionT<T, NormalDataT<T>,

protected:
void evalFunction(
const size_t constrIndex,
size_t constrIndex,
const JointStateT<T>& state,
Vector<T, 1>&,
optional_ref<std::array<Vector3<T>, 2>> v = {},
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/orientation_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class OrientationErrorFunctionT : public ConstraintErrorFunctionT<T, Orientation

protected:
void evalFunction(
const size_t constrIndex,
size_t constrIndex,
const JointStateT<T>& state,
Vector<T, 9>& f,
optional_ref<std::array<Vector3<T>, 3>> v = {},
Expand Down
4 changes: 2 additions & 2 deletions momentum/character_solver/plane_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ std::vector<PlaneDataT<T>> createFloorConstraints(
const LocatorList& locators,
const Vector3<T>& 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
Expand Down Expand Up @@ -86,7 +86,7 @@ class PlaneErrorFunctionT : public ConstraintErrorFunctionT<T, PlaneDataT<T>, 1>

protected:
void evalFunction(
const size_t constrIndex,
size_t constrIndex,
const JointStateT<T>& state,
Vector<T, 1>& f,
optional_ref<std::array<Vector3<T>, 1>> = {},
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/position_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ class PositionErrorFunctionT : public ConstraintErrorFunctionT<T, PositionDataT<

protected:
void evalFunction(
const size_t constrIndex,
size_t constrIndex,
const JointStateT<T>& state,
Vector3<T>&,
optional_ref<std::array<Vector3<T>, 1>> = {},
Expand Down
4 changes: 2 additions & 2 deletions momentum/character_solver/simd_normal_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
6 changes: 3 additions & 3 deletions momentum/character_solver/simd_plane_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
4 changes: 2 additions & 2 deletions momentum/character_solver/simd_position_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
8 changes: 4 additions & 4 deletions momentum/character_solver/vertex_error_function.h
Original file line number Diff line number Diff line change
Expand Up @@ -92,8 +92,8 @@ class VertexErrorFunctionT : public SkeletonErrorFunctionT<T> {
const ModelParametersT<T>& modelParameters,
const SkeletonStateT<T>& state,
const VertexConstraintT<T>& constr,
const T sourceNormalWeight,
const T targetNormalWeight,
T sourceNormalWeight,
T targetNormalWeight,
Ref<Eigen::MatrixX<T>> jac,
T& res) const;

Expand All @@ -107,8 +107,8 @@ class VertexErrorFunctionT : public SkeletonErrorFunctionT<T> {
const ModelParametersT<T>& modelParameters,
const SkeletonStateT<T>& state,
const VertexConstraintT<T>& constr,
const T sourceNormalWeight,
const T targetNormalWeight,
T sourceNormalWeight,
T targetNormalWeight,
Eigen::Ref<Eigen::VectorX<T>> jointGrad) const;

// Utility function used now in calculateNormalJacobian and calculatePositionGradient
Expand Down
2 changes: 1 addition & 1 deletion momentum/gui/rerun/logger.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ void logMarkerLocatorCorrespondence(
const std::map<std::string, size_t>& locatorLookup,
const LocatorState& locatorState,
gsl::span<const Marker> markers,
const float kPositionErrorThreshold);
float kPositionErrorThreshold);

void logBvh(
const rerun::RecordingStream& rec,
Expand Down
6 changes: 3 additions & 3 deletions momentum/io/character_io.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ enum class CharacterFormat : uint8_t {
/// @return The loaded Character object.
[[nodiscard]] Character loadFullCharacterFromBuffer(
CharacterFormat format,
const gsl::span<const std::byte> characterBuffer,
const gsl::span<const std::byte> paramBuffer = gsl::span<const std::byte>(),
const gsl::span<const std::byte> locBuffer = gsl::span<const std::byte>());
gsl::span<const std::byte> characterBuffer,
gsl::span<const std::byte> paramBuffer = gsl::span<const std::byte>(),
gsl::span<const std::byte> locBuffer = gsl::span<const std::byte>());

} // namespace momentum
4 changes: 2 additions & 2 deletions momentum/io/fbx/fbx_io.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
12 changes: 6 additions & 6 deletions momentum/io/gltf/gltf_builder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -85,23 +85,23 @@ 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<const std::vector<momentum::Marker>> 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',
// will deduct the file format by filename.
// 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.
Expand Down
8 changes: 4 additions & 4 deletions momentum/io/gltf/gltf_io.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ std::tuple<MatrixXf, VectorXf, float> 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<MatrixXf, VectorXf, float> loadMotionOnCharacter(
const gsl::span<const std::byte> byteSpan,
gsl::span<const std::byte> byteSpan,
const Character& character);

/// Loads a MarkerSequence from a file.
Expand All @@ -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<std::vector<Marker>>& markerSequence = {},
Expand All @@ -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<std::vector<Marker>>& markerSequence = {},
const GltfFileFormat fileFormat = GltfFileFormat::EXTENSION);
GltfFileFormat fileFormat = GltfFileFormat::EXTENSION);

/// Saves character skeleton states to a glb file.
///
Expand Down
4 changes: 2 additions & 2 deletions momentum/io/openfbx/polygon_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
};
Expand Down
Loading

0 comments on commit 420c3eb

Please sign in to comment.