hpp::constraints::explicit_::RelativePose Class Reference

Constraint of relative pose between two frames on a kinematic chain. More...

#include <hpp/constraints/explicit/relative-pose.hh>

Inheritance diagram for hpp::constraints::explicit_::RelativePose:
[legend]
Collaboration diagram for hpp::constraints::explicit_::RelativePose:
[legend]

Public Member Functions

virtual ImplicitPtr_t copy () const
 Copy object and return shared pointer to copy. More...
 
virtual void implicitToExplicitRhs (vectorIn_t implicitRhs, vectorOut_t explicitRhs)
 Convert right hand side. More...
 
- Public Member Functions inherited from hpp::constraints::Explicit
virtual DifferentiableFunctionPtr_t explicitFunction () const
 Function that maps input to output. More...
 
const segments_toutputConf () const
 Get output configuration variables. More...
 
const segments_toutputVelocity () const
 Get output degrees of freedom. More...
 
const segments_tinputConf () const
 Get input configuration variables. More...
 
const segments_tinputVelocity () const
 Get input degrees of freedom. More...
 
- Public Member Functions inherited from hpp::constraints::Implicit
bool operator== (const Implicit &other) const
 Operator equality. More...
 
virtual ~Implicit ()
 
DifferentiableFunctionfunction () const
 Return a reference to function \(h\). More...
 
const DifferentiableFunctionPtr_tfunctionPtr () const
 Return a reference to function \(h\). More...
 
void rightHandSideFromConfig (ConfigurationIn_t config)
 Set the right hand side from a configuration. More...
 
void rightHandSide (vectorIn_t rhs)
 Set the right hand side of the equation. More...
 
vectorIn_t rightHandSide () const
 Return the right hand side of the equation. More...
 
size_type rhsSize () const HPP_CONSTRAINTS_DEPRECATED
 Return the dimension of the left hand side function tangent output space. More...
 
size_type parameterSize () const
 Get size of parameter defining the right hand side of the constraint. More...
 
size_type rightHandSideSize () const
 Get size of right hand side of the constraint. More...
 
const ComparisonTypes_tcomparisonType () const
 Return the ComparisonType. More...
 
void comparisonType (const ComparisonTypes_t &comp)
 Set the comparison type. More...
 
bool constantRightHandSide () const HPP_CONSTRAINTS_DEPRECATED
 Whether right hand side is constant. More...
 
vectorOut_t rightHandSide ()
 Return a modifiable reference to right hand side of equation. More...
 
vectorOut_t nonConstRightHandSide () HPP_CONSTRAINTS_DEPRECATED
 Return a modifiable reference to right hand side of equation. More...
 
void rightHandSideFunction (const DifferentiableFunctionPtr_t &rhsF)
 Set time-varying right hand side. More...
 
const DifferentiableFunctionPtr_trightHandSideFunction () const
 Get time-varying right hand side. More...
 
vectorIn_t rightHandSideAt (const value_type &s)
 Evaluate and set right hand side at given time. More...
 
- Public Member Functions inherited from hpp::constraints::implicit::RelativePose
const JointConstPtr_tjoint1 () const
 Get joint1. More...
 
const JointConstPtr_tjoint2 () const
 Get joint2. More...
 

Static Public Member Functions

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())
 Create instance and return shared pointer. More...
 
static RelativePosePtr_t createCopy (const RelativePosePtr_t &other)
 
- Static Public Member Functions inherited from hpp::constraints::Explicit
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
 Create instance and return shared pointer. More...
 
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())
 Create instance and return shared pointer. More...
 
static ExplicitPtr_t createCopy (const ExplicitPtr_t &other)
 Create a copy and return shared pointer. More...
 
- Static Public Member Functions inherited from hpp::constraints::Implicit
static ImplicitPtr_t create (const DifferentiableFunctionPtr_t &function)
 Create a shared pointer to a new instance. More...
 
static ImplicitPtr_t create (const DifferentiableFunctionPtr_t &function, ComparisonTypes_t comp)
 Create a shared pointer to a new instance. More...
 
static ImplicitPtr_t create (const DifferentiableFunctionPtr_t &function, ComparisonTypes_t comp, vectorIn_t rhs)
 Create a shared pointer to a new instance. More...
 
static ImplicitPtr_t createCopy (const ImplicitPtr_t &other)
 Create a copy and return shared pointer. More...
 
- Static Public Member Functions inherited from hpp::constraints::implicit::RelativePose
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())
 Create instance and return shared pointer. More...
 
static RelativePosePtr_t createCopy (const RelativePosePtr_t &other)
 

Protected Member Functions

 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())
 Constructor. More...
 
 RelativePose (const RelativePose &other)
 Copy constructor. More...
 
void init (RelativePoseWkPtr_t weak)
 Store weak pointer to itself. More...
 
- Protected Member Functions inherited from hpp::constraints::Explicit
 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
 Constructor. More...
 
 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)
 Constructor. More...
 
 Explicit (const Explicit &other)
 Copy constructor. More...
 
void init (const ExplicitWkPtr_t &weak)
 
- Protected Member Functions inherited from hpp::constraints::Implicit
 Implicit (const DifferentiableFunctionPtr_t &function, ComparisonTypes_t comp)
 Constructor. More...
 
 Implicit (const DifferentiableFunctionPtr_t &function, ComparisonTypes_t comp, vectorIn_t rhs)
 Constructor. More...
 
 Implicit (const Implicit &other)
 Copy constructor. More...
 
virtual bool isEqual (const Implicit &other, bool swapAndTest) const
 Test equality with other instance. More...
 
void init (const ImplicitWkPtr_t &weak)
 
- Protected Member Functions inherited from hpp::constraints::implicit::RelativePose
 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())
 Constructor. More...
 
 RelativePose (const RelativePose &other)
 Copy constructor. More...
 
void init (RelativePoseWkPtr_t weak)
 Store shared pointer to itself. More...
 

Additional Inherited Members

- Protected Attributes inherited from hpp::constraints::Explicit
DifferentiableFunctionPtr_t inputToOutput_
 
segments_t inputConf_
 
segments_t outputConf_
 
segments_t inputVelocity_
 
segments_t outputVelocity_
 

Detailed Description

Constraint of relative pose between two frames on a kinematic chain.

Constructor & Destructor Documentation

hpp::constraints::explicit_::RelativePose::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() 
)
protected

Constructor.

Parameters
namethe name of the constraints,
robotthe robot the constraints is applied to,
joint1the first joint the transformation of which is constrained,
joint2the second joint the transformation of which is constrained,
frame1position of a fixed frame in joint 1,
frame2position of a fixed frame in joint 2,
maskvector of 6 boolean defining which coordinates of the error vector to take into account.
Note
if joint1 is 0x0, joint 1 frame is considered to be the global frame.
hpp::constraints::explicit_::RelativePose::RelativePose ( const RelativePose other)
protected

Copy constructor.

Member Function Documentation

virtual ImplicitPtr_t hpp::constraints::explicit_::RelativePose::copy ( ) const
virtual

Copy object and return shared pointer to copy.

Reimplemented from hpp::constraints::Explicit.

static RelativePosePtr_t hpp::constraints::explicit_::RelativePose::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

Create instance and return shared pointer.

Parameters
namethe name of the constraints,
robotthe robot the constraints is applied to,
joint1the first joint the transformation of which is constrained,
joint2the second joint the transformation of which is constrained,
frame1position of a fixed frame in joint 1,
frame2position of a fixed frame in joint 2,
maskvector of 6 boolean defining which coordinates of the error vector to take into account.
Note
if joint1 is 0x0, joint 1 frame is considered to be the global frame.
static RelativePosePtr_t hpp::constraints::explicit_::RelativePose::createCopy ( const RelativePosePtr_t other)
static
virtual void hpp::constraints::explicit_::RelativePose::implicitToExplicitRhs ( vectorIn_t  implicitRhs,
vectorOut_t  explicitRhs 
)
virtual

Convert right hand side.

Parameters
implicitRhsright hand side of implicit formulation,
Return values
explicitRhsright 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.

void hpp::constraints::explicit_::RelativePose::init ( RelativePoseWkPtr_t  weak)
protected

Store weak pointer to itself.