Commit 9e8d498c authored by Joseph Mirabel's avatar Joseph Mirabel
Browse files

[Doc] Clarifies default arguments of integrate, difference and interpolate.

parent df3b348a
......@@ -44,7 +44,10 @@ namespace hpp {
/// Integrate a constant velocity during unit time.
///
/// \tparam saturateConfig when true, calls saturate at the end
/// \tparam saturateConfig when true, calls
/// \c hpp::pinocchio::saturate(robot, result) at the end
/// \tparam LieGroup is a compile-time map of joint type to Lie group type,
/// that defines the joint-wise operations.
/// \param robot robot that describes the kinematic chain
/// \param configuration initial and result configurations
/// \param velocity velocity vector
......@@ -55,24 +58,29 @@ namespace hpp {
/// \li \f$q_i += v_i \mbox{ modulo } 2\pi\f$ for unbounded rotation joints,
/// \li constant rotation velocity for SO(3) joints.
///
/// \note bounded degrees of freedom are saturated if the result of the
/// above operation is beyond a bound.
/// \note The default template arguments correspond to
/// \c integrate<true,DefaultLieGroupMap>.
template<bool saturateConfig, typename LieGroup>
void integrate (const DevicePtr_t& robot,
ConfigurationIn_t configuration,
vectorIn_t velocity, ConfigurationOut_t result);
/// Same as integrate<true, DefaultLieGroupMap>
void integrate (const DevicePtr_t& robot,
ConfigurationIn_t configuration,
vectorIn_t velocity, ConfigurationOut_t result);
/// Interpolate between two configurations of the robot
///
/// \tparam LieGroup is a compile-time map of joint type to Lie group type,
/// that defines the joint-wise operations.
/// \param robot robot that describes the kinematic chain
/// \param q0, q1 two configurations to interpolate
/// \param u in [0,1] position along the interpolation: q0 for u=0,
/// q1 for u=1
/// \retval result interpolated configuration
///
/// \note The default template arguments correspond to
/// \c interpolate<RnxSOnLieGroupMap>.
template <typename LieGroup>
void interpolate (const DevicePtr_t& robot,
ConfigurationIn_t q0,
......@@ -88,6 +96,8 @@ namespace hpp {
/// Difference between two configurations as a vector
///
/// \tparam LieGroup is a compile-time map of joint type to Lie group type,
/// that defines the joint-wise operations.
/// \param robot robot that describes the kinematic chain
/// \param q1 first configuration,
/// \param q2 second configuration,
......@@ -96,6 +106,9 @@ namespace hpp {
/// \f$\textbf{v}\f$
/// \note If the configuration space is a vector space, this is
/// \f$\textbf{v} = q_1 - q_2\f$
///
/// \note The default template arguments correspond to
/// \c difference<RnxSOnLieGroupMap>.
template <typename LieGroup>
void difference (const DevicePtr_t& robot, ConfigurationIn_t q1,
ConfigurationIn_t q2, vectorOut_t result);
......
......@@ -163,8 +163,9 @@ namespace hpp {
{
public:
/// Constructor
/// \param device to lock
/// \param lock whether to acquire the lock.
DeviceSync (const DevicePtr_t& d, bool lock = true);
DeviceSync (const DevicePtr_t& device, bool lock = true);
/// Destructor.
/// The lock is released if necessary.
......
......@@ -178,6 +178,7 @@ namespace hpp {
JointJacobian_t& jacobian (const bool localFrame=true) const { return jacobian (data(), localFrame); }
/// Get reference to Jacobian
/// \param data a DeviceData (see hpp::pinocchio::DeviceSync for details).
/// \param localFrame if true, compute the jacobian (6d) in the local frame,
/// whose linear part corresponds to the velocity of the center of the frame.
/// If false, the jacobian is expressed in the global frame and its linear part
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment