Skip to content

Commit

Permalink
Use MT_PROFILE_FUNCTION() for function level profile
Browse files Browse the repository at this point in the history
Summary: The custom event names are outdated and inconsistent; using the function name in the profiler is more consistent and will always be up-to-date.

Reviewed By: EscapeZero

Differential Revision: D68530787
  • Loading branch information
jeongseok-meta authored and facebook-github-bot committed Jan 23, 2025
1 parent 82a82a9 commit 773683b
Show file tree
Hide file tree
Showing 26 changed files with 47 additions and 47 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -102,13 +102,12 @@ double ModelParametersSequenceErrorFunctionT<T>::getJacobian(
Eigen::Ref<Eigen::MatrixX<T>> jacobian,
Eigen::Ref<Eigen::VectorX<T>> residual,
int& usedRows) const {
MT_PROFILE_FUNCTION();
MT_CHECK(
jacobian.cols() ==
gsl::narrow_cast<Eigen::Index>(
numFrames() * this->parameterTransform_.numAllModelParameters()));

MT_PROFILE_EVENT("MotionError: getJacobian");

usedRows = 0;

const auto np = gsl::narrow_cast<Eigen::Index>(this->parameterTransform_.numAllModelParameters());
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_sequence_solver/multipose_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ void MultiposeSolverT<T>::initializeSolver() {}

template <typename T>
void MultiposeSolverT<T>::doIteration() {
MT_PROFILE_EVENT("MultiposeIteration");
MT_PROFILE_FUNCTION();

MultiposeSolverFunctionT<T>* fn =
dynamic_cast<MultiposeSolverFunctionT<T>*>(this->solverFunction_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -240,7 +240,7 @@ double MultiposeSolverFunctionT<T>::getJacobian(
Eigen::MatrixX<T>& jacobian,
Eigen::VectorX<T>& residual,
size_t& actualRows) {
MT_PROFILE_EVENT("GetMultiposeJacobian");
MT_PROFILE_FUNCTION();
// update states
MT_CHECK(
universal_.size() ==
Expand Down
4 changes: 2 additions & 2 deletions momentum/character_sequence_solver/sequence_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ void SequenceSolverT<T>::setOptions(const SolverOptions& options) {

template <typename T>
void SequenceSolverT<T>::initializeSolver() {
MT_PROFILE_EVENT("SequenceSolver_initializeSolver");
MT_PROFILE_FUNCTION();

auto* fn = dynamic_cast<SequenceSolverFunctionT<T>*>(this->solverFunction_);
MT_CHECK(fn != nullptr);
Expand Down Expand Up @@ -441,7 +441,7 @@ double SequenceSolverT<T>::processSequenceErrors_serial(

template <typename T>
void SequenceSolverT<T>::doIteration() {
MT_PROFILE_EVENT("SequenceSolver_doIteration");
MT_PROFILE_FUNCTION();

auto* fn = dynamic_cast<SequenceSolverFunctionT<T>*>(this->solverFunction_);
MT_CHECK(fn != nullptr);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ template <typename T>
double StateSequenceErrorFunctionT<T>::getError(
gsl::span<const ModelParametersT<T>> /* modelParameters */,
gsl::span<const SkeletonStateT<T>> skelStates) const {
MT_PROFILE_EVENT("StateSequenceError: getError");
MT_PROFILE_FUNCTION();

// loop over all joints and check for smoothness
double error = 0.0;
Expand Down Expand Up @@ -88,7 +88,7 @@ double StateSequenceErrorFunctionT<T>::getGradient(
gsl::span<const ModelParametersT<T>> /* modelParameters */,
gsl::span<const SkeletonStateT<T>> skelStates,
Eigen::Ref<Eigen::VectorX<T>> gradient) const {
MT_PROFILE_EVENT("StateSequenceError: getGradient");
MT_PROFILE_FUNCTION();

MT_CHECK(skelStates.size() == 2);
const auto& prevState = skelStates[0];
Expand Down Expand Up @@ -211,7 +211,7 @@ double StateSequenceErrorFunctionT<T>::getJacobian(
Eigen::Ref<Eigen::MatrixX<T>> jacobian_full,
Eigen::Ref<Eigen::VectorX<T>> residual_full,
int& usedRows) const {
MT_PROFILE_EVENT("StateSequenceError: getJacobian");
MT_PROFILE_FUNCTION();

MT_CHECK(skelStates.size() == 2);
const auto& prevState = skelStates[0];
Expand Down
4 changes: 2 additions & 2 deletions momentum/character_solver/aim_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ void AimDistErrorFunctionT<T>::evalFunction(
Vector3<T>& f,
optional_ref<std::array<Vector3<T>, 2>> v,
optional_ref<std::array<Eigen::Matrix3<T>, 2>> dfdv) const {
MT_PROFILE_EVENT("AimDist: evalFunction");
MT_PROFILE_FUNCTION();

const AimDataT<T>& constr = this->constraints_[constrIndex];
const Vector3<T> point = state.transformation * constr.localPoint;
Expand Down Expand Up @@ -52,7 +52,7 @@ void AimDirErrorFunctionT<T>::evalFunction(
Vector3<T>& f,
optional_ref<std::array<Vector3<T>, 2>> v,
optional_ref<std::array<Eigen::Matrix3<T>, 2>> dfdv) const {
MT_PROFILE_EVENT("AimDir: evalFunction");
MT_PROFILE_FUNCTION();

const AimDataT<T>& constr = this->constraints_[constrIndex];
const Vector3<T> point = state.transformation * constr.localPoint;
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/collision_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -420,7 +420,7 @@ double CollisionErrorFunctionT<T>::getJacobian(
Ref<MatrixX<T>> jacobian,
Ref<VectorX<T>> residual,
int& usedRows) {
MT_PROFILE_EVENT("Collision: getJacobian");
MT_PROFILE_FUNCTION();
MT_CHECK(
jacobian.rows() >= gsl::narrow<Eigen::Index>(getJacobianSize()),
"Jacobian rows mismatch: Actual {}, Expected {}",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -344,7 +344,7 @@ double CollisionErrorFunctionStatelessT<T>::getJacobian(
Ref<MatrixX<T>> jacobian,
Ref<VectorX<T>> residual,
int& usedRows) {
MT_PROFILE_EVENT("Collision: getJacobian");
MT_PROFILE_FUNCTION();
MT_CHECK(
jacobian.rows() >= gsl::narrow<Eigen::Index>(collisionPairs.size()),
"Jacobian rows mismatch: Actual {}, Expected {}",
Expand Down
6 changes: 3 additions & 3 deletions momentum/character_solver/constraint_error_function-inl.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ template <typename T, class Data, size_t FuncDim, size_t NumVec, size_t NumPos>
double ConstraintErrorFunctionT<T, Data, FuncDim, NumVec, NumPos>::getError(
const ModelParametersT<T>& /* params */,
const SkeletonStateT<T>& state) {
MT_PROFILE_EVENT("Constraint: getError");
MT_PROFILE_FUNCTION();

// loop over all constraints and calculate the error
FuncType f;
Expand Down Expand Up @@ -174,7 +174,7 @@ double ConstraintErrorFunctionT<T, Data, FuncDim, NumVec, NumPos>::getJacobian(
Ref<Eigen::MatrixX<T>> jacobian,
Ref<Eigen::VectorX<T>> residual,
int& usedRows) {
MT_PROFILE_EVENT("Constraint: getJacobian");
MT_PROFILE_FUNCTION();
usedRows = getJacobianSize();

double error = 0.0;
Expand Down Expand Up @@ -298,7 +298,7 @@ double ConstraintErrorFunctionT<T, Data, FuncDim, NumVec, NumPos>::getGradient(
const ModelParametersT<T>& /*unused*/,
const SkeletonStateT<T>& state,
Ref<Eigen::VectorX<T>> gradient) {
MT_PROFILE_EVENT("Contraint: getGradient");
MT_PROFILE_FUNCTION();

// initialize joint gradients storage
jointGrad_.setZero();
Expand Down
6 changes: 3 additions & 3 deletions momentum/character_solver/fixed_axis_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ void FixedAxisDiffErrorFunctionT<T>::evalFunction(
Vector3<T>& f,
optional_ref<std::array<Vector3<T>, 1>> v,
optional_ref<std::array<Matrix3<T>, 1>> dfdv) const {
MT_PROFILE_EVENT("FixedAxis Diff: evalFunction");
MT_PROFILE_FUNCTION();

const FixedAxisDataT<T>& constr = this->constraints_[constrIndex];
Vector3<T> vec = state.rotation() * constr.localAxis;
Expand All @@ -41,7 +41,7 @@ void FixedAxisCosErrorFunctionT<T>::evalFunction(
Vector<T, 1>& f,
optional_ref<std::array<Vector3<T>, 1>> v,
optional_ref<std::array<Eigen::Matrix<T, 1, 3>, 1>> dfdv) const {
MT_PROFILE_EVENT("FixedAxis Cos: evalFunction");
MT_PROFILE_FUNCTION();

const FixedAxisDataT<T>& constr = this->constraints_[constrIndex];
Vector3<T> vec = state.rotation() * constr.localAxis;
Expand All @@ -61,7 +61,7 @@ void FixedAxisAngleErrorFunctionT<T>::evalFunction(
Vector<T, 1>& f,
optional_ref<std::array<Vector3<T>, 1>> v,
optional_ref<std::array<Eigen::Matrix<T, 1, 3>, 1>> dfdv) const {
MT_PROFILE_EVENT("FixedAxis Angle: evalFunction");
MT_PROFILE_FUNCTION();

const FixedAxisDataT<T>& constr = this->constraints_[constrIndex];
Vector3<T> vec = state.rotation() * constr.localAxis;
Expand Down
8 changes: 4 additions & 4 deletions momentum/character_solver/limit_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,13 @@ template <typename T>
double LimitErrorFunctionT<T>::getError(
const ModelParametersT<T>& params,
const SkeletonStateT<T>& state) {
MT_PROFILE_FUNCTION();

// check all is valid
MT_CHECK(
state.jointParameters.size() ==
gsl::narrow<Eigen::Index>(this->skeleton_.joints.size() * kParametersPerJoint));

MT_PROFILE_EVENT("Limit: getError");

// loop over all joints and check for limit violations
double error = 0.0;

Expand Down Expand Up @@ -182,7 +182,7 @@ double LimitErrorFunctionT<T>::getGradient(
const ModelParametersT<T>& params,
const SkeletonStateT<T>& state,
Eigen::Ref<Eigen::VectorX<T>> gradient) {
MT_PROFILE_EVENT("Limit: getGradient");
MT_PROFILE_FUNCTION();

const auto& parameterTransform = this->parameterTransform_;

Expand Down Expand Up @@ -422,7 +422,7 @@ double LimitErrorFunctionT<T>::getJacobian(
Eigen::Ref<Eigen::MatrixX<T>> jacobian,
Eigen::Ref<Eigen::VectorX<T>> residual,
int& usedRows) {
MT_PROFILE_EVENT("Limit: getJacobian");
MT_PROFILE_FUNCTION();

const auto& parameterTransform = this->parameterTransform_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ double ModelParametersErrorFunctionT<T>::getJacobian(
Ref<Eigen::MatrixX<T>> jacobian,
Ref<Eigen::VectorX<T>> residual,
int& usedRows) {
MT_PROFILE_EVENT("MotionError: getJacobian");
MT_PROFILE_FUNCTION();

usedRows = 0;

Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/normal_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ void NormalErrorFunctionT<T>::evalFunction(
Vector<T, 1>& f,
optional_ref<std::array<Vector3<T>, 2>> v,
optional_ref<std::array<Eigen::Matrix<T, 1, 3>, 2>> dfdv) const {
MT_PROFILE_EVENT("Normal: evalFunction");
MT_PROFILE_FUNCTION();

const NormalDataT<T>& constr = this->constraints_[constrIndex];
Vector3<T> point = state.transformation * constr.localPoint;
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/orientation_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ void OrientationErrorFunctionT<T>::evalFunction(
Vector<T, 9>& f,
optional_ref<std::array<Vector3<T>, 3>> v,
optional_ref<std::array<Eigen::Matrix<T, 9, 3>, 3>> dfdv) const {
MT_PROFILE_EVENT("Orientation: evalFunction");
MT_PROFILE_FUNCTION();

const OrientationDataT<T>& constr = this->constraints_[constrIndex];
Matrix3<T> vec = state.rotation() * constr.offset.toRotationMatrix();
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/plane_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ void PlaneErrorFunctionT<T>::evalFunction(
Vector<T, 1>& f,
optional_ref<std::array<Vector3<T>, 1>> v,
optional_ref<std::array<Eigen::Matrix<T, 1, 3>, 1>> dfdv) const {
MT_PROFILE_EVENT("Plane: evalFunction");
MT_PROFILE_FUNCTION();

const PlaneDataT<T>& constr = this->constraints_[constrIndex];
Vector3<T> vec = state.transformation * constr.offset;
Expand Down
4 changes: 2 additions & 2 deletions momentum/character_solver/pose_prior_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ double PosePriorErrorFunctionT<T>::getGradient(
const ModelParametersT<T>& params,
const SkeletonStateT<T>& /* state */,
Eigen::Ref<Eigen::VectorX<T>> gradient) {
MT_PROFILE_EVENT("PosePrior: getGradient");
MT_PROFILE_FUNCTION();

// loop over all joints and check for smoothness
double error = 0.0;
Expand Down Expand Up @@ -149,7 +149,7 @@ double PosePriorErrorFunctionT<T>::getJacobian(
Eigen::Ref<Eigen::MatrixX<T>> jacobian,
Eigen::Ref<Eigen::VectorX<T>> residual,
int& usedRows) {
MT_PROFILE_EVENT("PosePrior: getJacobian");
MT_PROFILE_FUNCTION();

// loop over all joints and check for smoothness
double error = 0.0;
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/position_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ void PositionErrorFunctionT<T>::evalFunction(
Vector3<T>& f,
optional_ref<std::array<Vector3<T>, 1>> v,
optional_ref<std::array<Matrix3<T>, 1>> dfdv) const {
MT_PROFILE_EVENT("Position: evalFunction");
MT_PROFILE_FUNCTION();

const PositionDataT<T>& constr = this->constraints_[constrIndex];
Vector3<T> vec = state.transformation * constr.offset;
Expand Down
4 changes: 2 additions & 2 deletions momentum/character_solver/simd_normal_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,7 @@ double SimdNormalErrorFunction::getJacobian(
Ref<MatrixXf> jacobian,
Ref<VectorXf> residual,
int& usedRows) {
MT_PROFILE_EVENT("SimdJacobian");
MT_PROFILE_FUNCTION();
MT_CHECK(jacobian.cols() == static_cast<Eigen::Index>(parameterTransform_.transform.cols()));

if (constraints_ == nullptr) {
Expand Down Expand Up @@ -441,7 +441,7 @@ double SimdNormalErrorFunctionAVX::getJacobian(
Ref<MatrixXf> jacobian,
Ref<VectorXf> residual,
int& usedRows) {
MT_PROFILE_EVENT("SimdJacobian");
MT_PROFILE_FUNCTION();
MT_CHECK(jacobian.cols() == static_cast<Eigen::Index>(parameterTransform_.transform.cols()));

if (constraints_ == nullptr) {
Expand Down
4 changes: 2 additions & 2 deletions momentum/character_solver/simd_plane_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -304,7 +304,7 @@ double SimdPlaneErrorFunction::getJacobian(
Ref<MatrixXf> jacobian,
Ref<VectorXf> residual,
int& usedRows) {
MT_PROFILE_EVENT("SimdJacobian");
MT_PROFILE_FUNCTION();
MT_CHECK(jacobian.cols() == static_cast<Eigen::Index>(parameterTransform_.transform.cols()));

if (constraints_ == nullptr) {
Expand Down Expand Up @@ -747,7 +747,7 @@ double SimdPlaneErrorFunctionAVX::getJacobian(
Ref<MatrixXf> jacobian,
Ref<VectorXf> residual,
int& usedRows) {
MT_PROFILE_EVENT("SimdJacobian");
MT_PROFILE_FUNCTION();
MT_CHECK(jacobian.cols() == static_cast<Eigen::Index>(parameterTransform_.transform.cols()));

if (constraints_ == nullptr) {
Expand Down
3 changes: 2 additions & 1 deletion momentum/character_solver/simd_position_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -299,11 +299,12 @@ double SimdPositionErrorFunction::getJacobian(
Ref<MatrixXf> jacobian,
Ref<VectorXf> residual,
int& usedRows) {
MT_PROFILE_FUNCTION();

if (constraints_ == nullptr) {
return 0.0f;
}

MT_PROFILE_EVENT("SimdJacobian");
MT_CHECK(jacobian.cols() == static_cast<Eigen::Index>(parameterTransform_.transform.cols()));
MT_CHECK((size_t)constraints_->numJoints <= jacobianOffset_.size());

Expand Down
10 changes: 5 additions & 5 deletions momentum/character_solver/skeleton_solver_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ double SkeletonSolverFunctionT<T>::getGradient(
template <typename T>
std::pair<size_t, std::vector<size_t>> getDimensions(
const std::vector<std::shared_ptr<SkeletonErrorFunctionT<T>>>& error_func) {
MT_PROFILE_EVENT("GetJacobianSize");
MT_PROFILE_FUNCTION();
std::vector<size_t> offset(error_func.size());
size_t jacobianSize = 0;
for (size_t i = 0; i < error_func.size(); i++) {
Expand All @@ -111,9 +111,9 @@ double SkeletonSolverFunctionT<T>::getJacobian(
Eigen::MatrixX<T>& jacobian,
Eigen::VectorX<T>& residual,
size_t& actualRows) {
// update the state according to the transformed parameters
MT_PROFILE_EVENT("GetSkeletonJacobian");
MT_PROFILE_FUNCTION();

// update the state according to the transformed parameters
{
MT_PROFILE_EVENT("Skeleton: set state");
state_->set(parameterTransform_->apply(parameters), *skeleton_);
Expand Down Expand Up @@ -167,7 +167,7 @@ double SkeletonSolverFunctionT<T>::getJtJR(
const Eigen::VectorX<T>& parameters,
Eigen::MatrixX<T>& JtJ,
Eigen::VectorX<T>& JtR) {
MT_PROFILE_EVENT("GetSkeletonJacobian");
MT_PROFILE_FUNCTION();

// update the state according to the transformed parameters
{
Expand Down Expand Up @@ -247,7 +247,7 @@ double SkeletonSolverFunctionT<T>::getSolverDerivatives(
const Eigen::VectorX<T>& parameters,
Eigen::MatrixX<T>& hess,
Eigen::VectorX<T>& grad) {
MT_PROFILE_EVENT("getSolverDerivativesSkeleton");
MT_PROFILE_FUNCTION();

// update the state according to the transformed parameters
{
Expand Down
6 changes: 3 additions & 3 deletions momentum/character_solver/state_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ template <typename T>
double StateErrorFunctionT<T>::getError(
const ModelParametersT<T>& params,
const SkeletonStateT<T>& state) {
MT_PROFILE_EVENT("StateError: getError");
MT_PROFILE_FUNCTION();

if (state.jointState.empty())
return 0.0;
Expand Down Expand Up @@ -136,7 +136,7 @@ double StateErrorFunctionT<T>::getGradient(
const ModelParametersT<T>& params,
const SkeletonStateT<T>& state,
Ref<Eigen::VectorX<T>> gradient) {
MT_PROFILE_EVENT("StateError: getGradient");
MT_PROFILE_FUNCTION();

if (state.jointState.empty())
return 0.0;
Expand Down Expand Up @@ -259,7 +259,7 @@ double StateErrorFunctionT<T>::getJacobian(
Eigen::Ref<Eigen::MatrixX<T>> jacobian,
Eigen::Ref<Eigen::VectorX<T>> residual,
int& usedRows) {
MT_PROFILE_EVENT("StateError: getJacobian");
MT_PROFILE_FUNCTION();

// loop over all constraints and calculate the error
double error = 0.0;
Expand Down
2 changes: 1 addition & 1 deletion momentum/character_solver/vertex_error_function.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ template <typename T>
double VertexErrorFunctionT<T>::getError(
const ModelParametersT<T>& modelParameters,
const SkeletonStateT<T>& state) {
MT_PROFILE_EVENT("VertexErrorFunction - getError");
MT_PROFILE_FUNCTION();

updateMeshes(modelParameters, state);

Expand Down
2 changes: 1 addition & 1 deletion momentum/solver/gauss_newton_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void GaussNewtonSolverT<T>::initializeSolver() {

template <typename T>
void GaussNewtonSolverT<T>::doIteration() {
MT_PROFILE_EVENT("Solver: GaussNewtonIteration");
MT_PROFILE_FUNCTION();
if (denseIteration_) {
doIterationDense();
} else {
Expand Down
Loading

0 comments on commit 773683b

Please sign in to comment.