|
static RelativePosePtr_t | create (const std::string &name, const DevicePtr_t &robot, const JointConstPtr_t &joint1, const JointConstPtr_t &joint2, const Transform3f &frame1, const Transform3f &frame2, std::vector< bool > mask=std::vector< bool >(6, true), ComparisonTypes_t comp=std::vector< ComparisonType >(), vectorIn_t rhs=vector_t()) |
|
static RelativePosePtr_t | createCopy (const RelativePosePtr_t &other) |
|
static ExplicitPtr_t | create (const DevicePtr_t &robot, const DifferentiableFunctionPtr_t &function, const segments_t &inputConf, const segments_t &outputConf, const segments_t &inputVelocity, const segments_t &outputVelocity, const ComparisonTypes_t &comp=ComparisonTypes_t()) HPP_CONSTRAINTS_DEPRECATED |
|
static ExplicitPtr_t | create (const LiegroupSpacePtr_t &configSpace, const DifferentiableFunctionPtr_t &function, const segments_t &inputConf, const segments_t &outputConf, const segments_t &inputVelocity, const segments_t &outputVelocity, const ComparisonTypes_t &comp=ComparisonTypes_t()) |
|
static ExplicitPtr_t | createCopy (const ExplicitPtr_t &other) |
| Create a copy and return shared pointer. More...
|
|
static ImplicitPtr_t | create (const DifferentiableFunctionPtr_t &function) |
|
static ImplicitPtr_t | create (const DifferentiableFunctionPtr_t &function, ComparisonTypes_t comp) |
|
static ImplicitPtr_t | create (const DifferentiableFunctionPtr_t &function, ComparisonTypes_t comp, vectorIn_t rhs) |
|
static ImplicitPtr_t | createCopy (const ImplicitPtr_t &other) |
| Create a copy and return shared pointer. More...
|
|
static RelativePosePtr_t | create (const std::string &name, const DevicePtr_t &robot, const JointConstPtr_t &joint1, const JointConstPtr_t &joint2, const Transform3f &frame1, const Transform3f &frame2, std::vector< bool > mask=std::vector< bool >(6, true), ComparisonTypes_t comp=std::vector< ComparisonType >(), vectorIn_t rhs=vector_t()) |
|
static RelativePosePtr_t | createCopy (const RelativePosePtr_t &other) |
|
|
| RelativePose (const std::string &name, const DevicePtr_t &robot, const JointConstPtr_t &joint1, const JointConstPtr_t &joint2, const Transform3f &frame1, const Transform3f &frame2, std::vector< bool > mask=std::vector< bool >(6, true), ComparisonTypes_t comp=std::vector< ComparisonType >(), vectorIn_t rhs=vector_t()) |
|
| RelativePose (const RelativePose &other) |
| Copy constructor. More...
|
|
void | init (RelativePoseWkPtr_t weak) |
| Store weak pointer to itself. More...
|
|
| Explicit (const DevicePtr_t &robot, const DifferentiableFunctionPtr_t &function, const segments_t &inputConf, const segments_t &outputConf, const segments_t &inputVelocity, const segments_t &outputVelocity, const ComparisonTypes_t &comp) HPP_CONSTRAINTS_DEPRECATED |
|
| Explicit (const LiegroupSpacePtr_t &configSpace, const DifferentiableFunctionPtr_t &function, const segments_t &inputConf, const segments_t &outputConf, const segments_t &inputVelocity, const segments_t &outputVelocity, const ComparisonTypes_t &comp) |
|
| Explicit (const Explicit &other) |
| Copy constructor. More...
|
|
void | init (const ExplicitWkPtr_t &weak) |
|
| Implicit (const DifferentiableFunctionPtr_t &function, ComparisonTypes_t comp) |
|
| Implicit (const DifferentiableFunctionPtr_t &function, ComparisonTypes_t comp, vectorIn_t rhs) |
|
| Implicit (const Implicit &other) |
| Copy constructor. More...
|
|
virtual bool | isEqual (const Implicit &other, bool swapAndTest) const |
|
void | init (const ImplicitWkPtr_t &weak) |
|
| RelativePose (const std::string &name, const DevicePtr_t &robot, const JointConstPtr_t &joint1, const JointConstPtr_t &joint2, const Transform3f &frame1, const Transform3f &frame2, std::vector< bool > mask=std::vector< bool >(6, true), ComparisonTypes_t comp=std::vector< ComparisonType >(), vectorIn_t rhs=vector_t()) |
|
| RelativePose (const RelativePose &other) |
| Copy constructor. More...
|
|
void | init (RelativePoseWkPtr_t weak) |
| Store shared pointer to itself. More...
|
|
Constraint of relative pose between two frames on a kinematic chain.
virtual void hpp::constraints::explicit_::RelativePose::explicitToImplicitRhs |
( |
vectorIn_t |
explicitRhs, |
|
|
vectorOut_t |
implicitRhs |
|
) |
| const |
|
virtual |
Convert right hand side
- Parameters
-
explicitRhs | right hand side of explicit formulation, |
- Return values
-
implicitRhs | right hand side of implicit formulation. |
For this constraint, the implicit formulation does not derive from the explicit formulation. The explicit form writes
\begin{eqnarray} rhs_{expl} &=& \log_{SE(3)} \left(F_{2/J_2} F_{1/J_1}^{-1} J_1^{-1} J_2\right)\\ rhs_{impl} &=& \log_{\mathbf{R}^3\times SO(3)} \left(F_{1/J_1}^{-1} J_1^{-1}J_2 F_{2/J_2}\right) \end{eqnarray}
Thus
\begin{equation} rhs_{impl} = \log_{\mathbf{R}^3\times SO(3)}\left( F_{2/J_2}^{-1} \exp_{SE(3)} (rhs_{expl}) F_{2/J_2}\right) \end{equation}
Reimplemented from hpp::constraints::Explicit.
virtual void hpp::constraints::explicit_::RelativePose::implicitToExplicitRhs |
( |
vectorIn_t |
implicitRhs, |
|
|
vectorOut_t |
explicitRhs |
|
) |
| const |
|
virtual |
Convert right hand side
- Parameters
-
implicitRhs | right hand side of implicit formulation, |
- Return values
-
explicitRhs | right hand side of explicit formulation. |
For this constraint, the implicit formulation does not derive from the explicit formulation. The explicit form writes
\begin{eqnarray} rhs_{expl} &=& \log_{SE(3)} \left(F_{2/J_2} F_{1/J_1}^{-1} J_1^{-1} J_2\right)\\ rhs_{impl} &=& \log_{\mathbf{R}^3\times SO(3)} \left(F_{1/J_1}^{-1} J_1^{-1}J_2 F_{2/J_2}\right) \end{eqnarray}
Thus
\begin{equation} rhs_{expl} = \log_{SE(3)}\left( F_{2/J_2}\exp_{\mathbf{R}^3\times SO(3)} (rhs_{impl}) F_{2/J_2}^{-1}\right) \end{equation}
Reimplemented from hpp::constraints::Explicit.