hpp-constraints  4.9.1
Definition of basic geometric constraints for motion planning
hpp::constraints::implicit::RelativePose Class Reference

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

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

Inheritance diagram for hpp::constraints::implicit::RelativePose:
Collaboration diagram for hpp::constraints::implicit::RelativePose:

Public Member Functions

virtual ImplicitPtr_t copy () const
 Copy object and return shared pointer to copy. More...
 
const JointConstPtr_tjoint1 () const
 Get joint1. More...
 
const JointConstPtr_tjoint2 () const
 Get joint2. 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)
 
void rightHandSide (vectorIn_t rhs)
 
vectorIn_t rightHandSide () const
 Return the right hand side of the equation. More...
 
size_type rhsSize () const HPP_CONSTRAINTS_DEPRECATED
 
size_type parameterSize () const
 
size_type rightHandSideSize () const
 
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
 
vectorOut_t rightHandSide ()
 
vectorOut_t nonConstRightHandSide () HPP_CONSTRAINTS_DEPRECATED
 
void rightHandSideFunction (const DifferentiableFunctionPtr_t &rhsF)
 
const DifferentiableFunctionPtr_trightHandSideFunction () const
 
vectorIn_t rightHandSideAt (const value_type &s)
 

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())
 
static RelativePosePtr_t createCopy (const RelativePosePtr_t &other)
 
- Static Public Member Functions inherited from hpp::constraints::Implicit
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...
 

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())
 
 RelativePose (const RelativePose &other)
 Copy constructor. More...
 
void init (RelativePoseWkPtr_t weak)
 Store shared pointer to itself. More...
 
- Protected Member Functions inherited from hpp::constraints::Implicit
 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)
 

Detailed Description

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

Constructor & Destructor Documentation

◆ RelativePose() [1/2]

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() 
)
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.

◆ RelativePose() [2/2]

hpp::constraints::implicit::RelativePose::RelativePose ( const RelativePose other)
protected

Copy constructor.

Member Function Documentation

◆ copy()

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

Copy object and return shared pointer to copy.

Reimplemented from hpp::constraints::Implicit.

Reimplemented in hpp::constraints::explicit_::RelativePose.

◆ create()

static RelativePosePtr_t hpp::constraints::implicit::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.

◆ createCopy()

static RelativePosePtr_t hpp::constraints::implicit::RelativePose::createCopy ( const RelativePosePtr_t other)
static

◆ init()

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

Store shared pointer to itself.

◆ joint1()

const JointConstPtr_t& hpp::constraints::implicit::RelativePose::joint1 ( ) const
inline

Get joint1.

◆ joint2()

const JointConstPtr_t& hpp::constraints::implicit::RelativePose::joint2 ( ) const
inline

Get joint2.


The documentation for this class was generated from the following file: