Skip to content

Commit

Permalink
Merge pull request #2348 from stephane-caron/docs/parameters
Browse files Browse the repository at this point in the history
Fix two equations and typos in the documentation
  • Loading branch information
jcarpent committed Jul 25, 2024
2 parents 5fd5eba + e304609 commit b29e85e
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 20 deletions.
33 changes: 18 additions & 15 deletions include/pinocchio/algorithm/constrained-dynamics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,16 +40,18 @@ namespace pinocchio

///
/// \brief Computes the forward dynamics with contact constraints according to a given list of
/// Contact information.
/// When using forwardDynamics for the first time, you should call first
/// contact information.
///
/// \note When using forwardDynamics for the first time, you should call first
/// initConstraintDynamics to initialize the internal memory used in the algorithm.
///
/// \note It computes the following problem: <BR>
/// <CENTER> \f$ \begin{eqnarray} \underset{\ddot{q}}{\min} & & \| \ddot{q} -
/// \ddot{q}_{\text{free}} \|_{M(q)} \\ %
/// \text{s.t.} & & J (q) \ddot{q} + \gamma (q, \dot{q}) = 0 \end{eqnarray} \f$
/// </CENTER> <BR>
/// where \f$ \ddot{q}_{\text{free}} \f$ is the free acceleration (i.e. without
/// It computes the following problem: \[
/// \f[
/// \begin{eqnarray}
/// \underset{\ddot{q}}{\min} & & \| \ddot{q} - \ddot{q}_{\text{free}} \|_{M(q)} \\
/// \text{s.t.} & & J (q) \ddot{q} + \gamma (q, \dot{q}) = 0
/// \end{eqnarray}
/// \f] where \f$ \ddot{q}_{\text{free}} \f$ is the free acceleration (i.e. without
/// constraints), \f$ M \f$ is the mass matrix, \f$ J \f$ the constraint Jacobian and \f$
/// \gamma \f$ is the constraint drift.
/// By default, the constraint Jacobian is assumed to be full rank, and undamped Cholesky inverse
Expand Down Expand Up @@ -101,15 +103,16 @@ namespace pinocchio
///
/// \brief Computes the forward dynamics with contact constraints according to a given list of
/// Contact information.
/// When using forwardDynamics for the first time, you should call first
///
/// \note When using forwardDynamics for the first time, you should call first
/// initConstraintDynamics to initialize the internal memory used in the algorithm.
///
/// \note It computes the following problem: <BR>
/// <CENTER> \f$ \begin{eqnarray} \underset{\ddot{q}}{\min} & & \| \ddot{q} -
/// \ddot{q}_{\text{free}} \|_{M(q)} \\ %
/// \text{s.t.} & & J (q) \ddot{q} + \gamma (q, \dot{q}) = 0 \end{eqnarray} \f$
/// </CENTER> <BR>
/// where \f$ \ddot{q}_{\text{free}} \f$ is the free acceleration (i.e. without
/// It computes the following problem: \f[
/// \begin{eqnarray}
/// \underset{\ddot{q}}{\min} & & \| \ddot{q} - \ddot{q}_{\text{free}} \|_{M(q)} \\
/// \text{s.t.} & & J (q) \ddot{q} + \gamma (q, \dot{q}) = 0
/// \end{eqnarray}
/// \f] where \f$ \ddot{q}_{\text{free}} \f$ is the free acceleration (i.e. without
/// constraints), \f$ M \f$ is the mass matrix, \f$ J \f$ the constraint Jacobian and \f$
/// \gamma \f$ is the constraint drift.
/// By default, the constraint Jacobian is assumed to be full rank, and undamped Cholesky inverse
Expand Down
4 changes: 2 additions & 2 deletions include/pinocchio/algorithm/proximal.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ namespace pinocchio
{

///
/// \brief Structure containing all the settings paramters for the proximal algorithms.
/// \brief Structure containing all the settings parameters for the proximal algorithms.
///
///  \tparam _Scalar Scalar type of the for the regularization and the accuracy parameter.
///
Expand Down Expand Up @@ -91,7 +91,7 @@ namespace pinocchio
/// \brief Relative proximal accuracy between two iterates.
Scalar relative_accuracy;

/// \brief Regularization parameter of the Proximal algorithms.
/// \brief Regularization parameter of the proximal algorithm.
Scalar mu;

/// \brief Maximal number of iterations.
Expand Down
6 changes: 3 additions & 3 deletions include/pinocchio/bindings/python/algorithm/proximal.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,11 @@ namespace pinocchio
cl.def(bp::init<>("Default constructor.", bp::arg("self")))
.def(bp::init<const Scalar, const Scalar, int>(
(bp::arg("self"), bp::arg("accuracy"), bp::arg("mu"), bp::arg("max_iter")),
"Structure containing all the settings paramters for the proximal algorithms."))
"Structure containing all the settings parameters for the proximal algorithms."))
.def(bp::init<const Scalar, const Scalar, const Scalar, int>(
(bp::arg("self"), bp::arg("absolute_accuracy"), bp::arg("relative_accuracy"),
bp::arg("mu"), bp::arg("max_iter")),
"Structure containing all the settings paramters for the proximal algorithms."))
"Structure containing all the settings parameters for the proximal algorithms."))

.add_property(
"absolute_accuracy", &ProximalSettings::absolute_accuracy,
Expand Down Expand Up @@ -61,7 +61,7 @@ namespace pinocchio
{
bp::class_<ProximalSettings>(
"ProximalSettings",
"Structure containing all the settings paramters for Proximal algorithms.", bp::no_init)
"Structure containing all the settings parameters for proximal algorithms.", bp::no_init)
.def(ProximalSettingsPythonVisitor<ProximalSettings>());
}

Expand Down

0 comments on commit b29e85e

Please sign in to comment.