Public Types | Public Member Functions | Public Attributes | Protected Attributes | List of all members
tsid::tasks::TaskTwoFramesEquality Class Reference

#include <task-two-frames-equality.hpp>

Inheritance diagram for tsid::tasks::TaskTwoFramesEquality:
Inheritance graph
[legend]

Public Types

typedef math::ConstraintEquality ConstraintEquality
 
typedef pinocchio::Data Data
 
typedef pinocchio::Data::Matrix6x Matrix6x
 
typedef pinocchio::Motion Motion
 
typedef pinocchio::SE3 SE3
 
typedef trajectories::TrajectorySample TrajectorySample
 
typedef math::Vector Vector
 
- Public Types inherited from tsid::tasks::TaskMotion
typedef trajectories::TrajectorySample TrajectorySample
 
- Public Types inherited from tsid::tasks::TaskBase
typedef math::ConstRefVector ConstRefVector
 
typedef pinocchio::Data Data
 
typedef robots::RobotWrapper RobotWrapper
 

Public Member Functions

const ConstraintBasecompute (const double t, ConstRefVector q, ConstRefVector v, Data &data) override
 
int dim () const override
 Return the dimension of the task. \info should be overloaded in the child class. More...
 
Index frame_id1 () const
 
Index frame_id2 () const
 
Vector getAcceleration (ConstRefVector dv) const override
 
const ConstraintBasegetConstraint () const override
 
const VectorgetDesiredAcceleration () const override
 
const VectorKd () const
 
void Kd (ConstRefVector Kp)
 
const VectorKp () const
 
void Kp (ConstRefVector Kp)
 
const Vectorposition_error () const override
 
virtual void setMask (math::ConstRefVector mask) override
 
 TaskTwoFramesEquality (const std::string &name, RobotWrapper &robot, const std::string &frameName1, const std::string &frameName2)
 
void useLocalFrame (bool local_frame)
 Specifies if the jacobian and desired acceloration should be expressed in the local frame or the local world-oriented frame. More...
 
const Vectorvelocity_error () const override
 
- Public Member Functions inherited from tsid::tasks::TaskMotion
virtual const VectorgetMask () const
 
virtual const TrajectorySamplegetReference () const
 
virtual bool hasMask ()
 
virtual const Vectorposition () const
 
virtual const Vectorposition_ref () const
 
 TaskMotion (const std::string &name, RobotWrapper &robot)
 
virtual const Vectorvelocity () const
 
virtual const Vectorvelocity_ref () const
 
- Public Member Functions inherited from tsid::tasks::TaskBase
const std::string & name () const
 
void name (const std::string &name)
 
 TaskBase (const std::string &name, RobotWrapper &robot)
 
virtual ~TaskBase ()=default
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index Index
 
- Public Attributes inherited from tsid::tasks::TaskMotion
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Vector Vector
 
- Public Attributes inherited from tsid::tasks::TaskBase
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::ConstraintBase ConstraintBase
 

Protected Attributes

Vector m_a_des
 
Vector m_a_des_masked
 
Motion m_a_ref
 
ConstraintEquality m_constraint
 
Motion m_drift
 
Vector m_drift_masked
 
Index m_frame_id1
 
Index m_frame_id2
 
std::string m_frame_name1
 
std::string m_frame_name2
 
Matrix6x m_J1
 
Matrix6x m_J1_rotated
 
Matrix6x m_J2
 
Matrix6x m_J2_rotated
 
Vector m_Kd
 
Vector m_Kp
 
Vector m_p
 
Motion m_p_error
 
Vector m_p_error_masked_vec
 
Vector m_p_error_vec
 
Vector m_p_ref
 
Vector m_v
 
Motion m_v_error
 
Vector m_v_error_masked_vec
 
Vector m_v_error_vec
 
Motion m_v_ref
 
Vector m_v_ref_vec
 
SE3 m_wMl1
 
SE3 m_wMl2
 
- Protected Attributes inherited from tsid::tasks::TaskMotion
Vector m_dummy
 
Vector m_mask
 
trajectories::TrajectorySample TrajectorySample_dummy
 
- Protected Attributes inherited from tsid::tasks::TaskBase
std::string m_name
 
RobotWrapperm_robot
 Reference on the robot model. More...
 

Detailed Description

Definition at line 31 of file tasks/task-two-frames-equality.hpp.

Member Typedef Documentation

◆ ConstraintEquality

Definition at line 38 of file tasks/task-two-frames-equality.hpp.

◆ Data

Definition at line 39 of file tasks/task-two-frames-equality.hpp.

◆ Matrix6x

Definition at line 40 of file tasks/task-two-frames-equality.hpp.

◆ Motion

Definition at line 41 of file tasks/task-two-frames-equality.hpp.

◆ SE3

Definition at line 42 of file tasks/task-two-frames-equality.hpp.

◆ TrajectorySample

Definition at line 36 of file tasks/task-two-frames-equality.hpp.

◆ Vector

Definition at line 37 of file tasks/task-two-frames-equality.hpp.

Constructor & Destructor Documentation

◆ TaskTwoFramesEquality()

tsid::tasks::TaskTwoFramesEquality::TaskTwoFramesEquality ( const std::string &  name,
RobotWrapper robot,
const std::string &  frameName1,
const std::string &  frameName2 
)

Definition at line 29 of file src/tasks/task-two-frames-equality.cpp.

Member Function Documentation

◆ compute()

const ConstraintBase & tsid::tasks::TaskTwoFramesEquality::compute ( const double  t,
ConstRefVector  q,
ConstRefVector  v,
Data data 
)
overridevirtual

Implements tsid::tasks::TaskBase.

Definition at line 115 of file src/tasks/task-two-frames-equality.cpp.

◆ dim()

int tsid::tasks::TaskTwoFramesEquality::dim ( ) const
overridevirtual

Return the dimension of the task. \info should be overloaded in the child class.

Implements tsid::tasks::TaskBase.

Definition at line 75 of file src/tasks/task-two-frames-equality.cpp.

◆ frame_id1()

Index tsid::tasks::TaskTwoFramesEquality::frame_id1 ( ) const

Definition at line 107 of file src/tasks/task-two-frames-equality.cpp.

◆ frame_id2()

Index tsid::tasks::TaskTwoFramesEquality::frame_id2 ( ) const

Definition at line 109 of file src/tasks/task-two-frames-equality.cpp.

◆ getAcceleration()

Vector tsid::tasks::TaskTwoFramesEquality::getAcceleration ( ConstRefVector  dv) const
overridevirtual

Return the task acceleration (after applying the specified mask). The value is expressed in local frame is the local_frame flag is true, otherwise it is expressed in a local world-oriented frame.

Reimplemented from tsid::tasks::TaskMotion.

Definition at line 103 of file src/tasks/task-two-frames-equality.cpp.

◆ getConstraint()

const ConstraintBase & tsid::tasks::TaskTwoFramesEquality::getConstraint ( ) const
overridevirtual

Implements tsid::tasks::TaskBase.

Definition at line 111 of file src/tasks/task-two-frames-equality.cpp.

◆ getDesiredAcceleration()

const Vector & tsid::tasks::TaskTwoFramesEquality::getDesiredAcceleration ( ) const
overridevirtual

Return the desired task acceleration (after applying the specified mask). The value is expressed in local frame is the local_frame flag is true, otherwise it is expressed in a local world-oriented frame.

Reimplemented from tsid::tasks::TaskMotion.

Definition at line 99 of file src/tasks/task-two-frames-equality.cpp.

◆ Kd() [1/2]

const Vector & tsid::tasks::TaskTwoFramesEquality::Kd ( ) const

Definition at line 79 of file src/tasks/task-two-frames-equality.cpp.

◆ Kd() [2/2]

void tsid::tasks::TaskTwoFramesEquality::Kd ( ConstRefVector  Kp)

Definition at line 86 of file src/tasks/task-two-frames-equality.cpp.

◆ Kp() [1/2]

const Vector & tsid::tasks::TaskTwoFramesEquality::Kp ( ) const

Definition at line 77 of file src/tasks/task-two-frames-equality.cpp.

◆ Kp() [2/2]

void tsid::tasks::TaskTwoFramesEquality::Kp ( ConstRefVector  Kp)

Definition at line 81 of file src/tasks/task-two-frames-equality.cpp.

◆ position_error()

const Vector & tsid::tasks::TaskTwoFramesEquality::position_error ( ) const
overridevirtual

Return the position tracking error (after applying the specified mask). The error is expressed in local frame is the local_frame flag is true, otherwise it is expressed in a local world-oriented frame.

Reimplemented from tsid::tasks::TaskMotion.

Definition at line 91 of file src/tasks/task-two-frames-equality.cpp.

◆ setMask()

void tsid::tasks::TaskTwoFramesEquality::setMask ( math::ConstRefVector  mask)
overridevirtual

Reimplemented from tsid::tasks::TaskMotion.

Definition at line 65 of file src/tasks/task-two-frames-equality.cpp.

◆ useLocalFrame()

void tsid::tasks::TaskTwoFramesEquality::useLocalFrame ( bool  local_frame)

Specifies if the jacobian and desired acceloration should be expressed in the local frame or the local world-oriented frame.

Parameters
local_frameIf true, represent jacobian and acceloration in the local frame. If false, represent them in the local world-oriented frame.

◆ velocity_error()

const Vector & tsid::tasks::TaskTwoFramesEquality::velocity_error ( ) const
overridevirtual

Return the velocity tracking error (after applying the specified mask). The error is expressed in local frame is the local_frame flag is true, otherwise it is expressed in a local world-oriented frame.

Reimplemented from tsid::tasks::TaskMotion.

Definition at line 95 of file src/tasks/task-two-frames-equality.cpp.

Member Data Documentation

◆ Index

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::tasks::TaskTwoFramesEquality::Index

Definition at line 35 of file tasks/task-two-frames-equality.hpp.

◆ m_a_des

Vector tsid::tasks::TaskTwoFramesEquality::m_a_des
protected

Definition at line 112 of file tasks/task-two-frames-equality.hpp.

◆ m_a_des_masked

Vector tsid::tasks::TaskTwoFramesEquality::m_a_des_masked
protected

Definition at line 112 of file tasks/task-two-frames-equality.hpp.

◆ m_a_ref

Motion tsid::tasks::TaskTwoFramesEquality::m_a_ref
protected

Definition at line 108 of file tasks/task-two-frames-equality.hpp.

◆ m_constraint

ConstraintEquality tsid::tasks::TaskTwoFramesEquality::m_constraint
protected

Definition at line 117 of file tasks/task-two-frames-equality.hpp.

◆ m_drift

Motion tsid::tasks::TaskTwoFramesEquality::m_drift
protected

Definition at line 113 of file tasks/task-two-frames-equality.hpp.

◆ m_drift_masked

Vector tsid::tasks::TaskTwoFramesEquality::m_drift_masked
protected

Definition at line 114 of file tasks/task-two-frames-equality.hpp.

◆ m_frame_id1

Index tsid::tasks::TaskTwoFramesEquality::m_frame_id1
protected

Definition at line 101 of file tasks/task-two-frames-equality.hpp.

◆ m_frame_id2

Index tsid::tasks::TaskTwoFramesEquality::m_frame_id2
protected

Definition at line 102 of file tasks/task-two-frames-equality.hpp.

◆ m_frame_name1

std::string tsid::tasks::TaskTwoFramesEquality::m_frame_name1
protected

Definition at line 99 of file tasks/task-two-frames-equality.hpp.

◆ m_frame_name2

std::string tsid::tasks::TaskTwoFramesEquality::m_frame_name2
protected

Definition at line 100 of file tasks/task-two-frames-equality.hpp.

◆ m_J1

Matrix6x tsid::tasks::TaskTwoFramesEquality::m_J1
protected

Definition at line 115 of file tasks/task-two-frames-equality.hpp.

◆ m_J1_rotated

Matrix6x tsid::tasks::TaskTwoFramesEquality::m_J1_rotated
protected

Definition at line 116 of file tasks/task-two-frames-equality.hpp.

◆ m_J2

Matrix6x tsid::tasks::TaskTwoFramesEquality::m_J2
protected

Definition at line 115 of file tasks/task-two-frames-equality.hpp.

◆ m_J2_rotated

Matrix6x tsid::tasks::TaskTwoFramesEquality::m_J2_rotated
protected

Definition at line 116 of file tasks/task-two-frames-equality.hpp.

◆ m_Kd

Vector tsid::tasks::TaskTwoFramesEquality::m_Kd
protected

Definition at line 111 of file tasks/task-two-frames-equality.hpp.

◆ m_Kp

Vector tsid::tasks::TaskTwoFramesEquality::m_Kp
protected

Definition at line 110 of file tasks/task-two-frames-equality.hpp.

◆ m_p

Vector tsid::tasks::TaskTwoFramesEquality::m_p
protected

Definition at line 106 of file tasks/task-two-frames-equality.hpp.

◆ m_p_error

Motion tsid::tasks::TaskTwoFramesEquality::m_p_error
protected

Definition at line 103 of file tasks/task-two-frames-equality.hpp.

◆ m_p_error_masked_vec

Vector tsid::tasks::TaskTwoFramesEquality::m_p_error_masked_vec
protected

Definition at line 105 of file tasks/task-two-frames-equality.hpp.

◆ m_p_error_vec

Vector tsid::tasks::TaskTwoFramesEquality::m_p_error_vec
protected

Definition at line 104 of file tasks/task-two-frames-equality.hpp.

◆ m_p_ref

Vector tsid::tasks::TaskTwoFramesEquality::m_p_ref
protected

Definition at line 107 of file tasks/task-two-frames-equality.hpp.

◆ m_v

Vector tsid::tasks::TaskTwoFramesEquality::m_v
protected

Definition at line 106 of file tasks/task-two-frames-equality.hpp.

◆ m_v_error

Motion tsid::tasks::TaskTwoFramesEquality::m_v_error
protected

Definition at line 103 of file tasks/task-two-frames-equality.hpp.

◆ m_v_error_masked_vec

Vector tsid::tasks::TaskTwoFramesEquality::m_v_error_masked_vec
protected

Definition at line 105 of file tasks/task-two-frames-equality.hpp.

◆ m_v_error_vec

Vector tsid::tasks::TaskTwoFramesEquality::m_v_error_vec
protected

Definition at line 104 of file tasks/task-two-frames-equality.hpp.

◆ m_v_ref

Motion tsid::tasks::TaskTwoFramesEquality::m_v_ref
protected

Definition at line 108 of file tasks/task-two-frames-equality.hpp.

◆ m_v_ref_vec

Vector tsid::tasks::TaskTwoFramesEquality::m_v_ref_vec
protected

Definition at line 107 of file tasks/task-two-frames-equality.hpp.

◆ m_wMl1

SE3 tsid::tasks::TaskTwoFramesEquality::m_wMl1
protected

Definition at line 109 of file tasks/task-two-frames-equality.hpp.

◆ m_wMl2

SE3 tsid::tasks::TaskTwoFramesEquality::m_wMl2
protected

Definition at line 109 of file tasks/task-two-frames-equality.hpp.


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


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:17