#include <tsid/tasks/task-se3-equality.hpp>
◆ ConstraintEquality
◆ Data
◆ Matrix6x
◆ Motion
◆ SE3
◆ TrajectorySample
◆ Vector
◆ TaskSE3Equality()
tsid::tasks::TaskSE3Equality::TaskSE3Equality |
( |
const std::string & |
name, |
|
|
RobotWrapper & |
robot, |
|
|
const std::string & |
frameName |
|
) |
| |
◆ compute()
◆ dim()
int tsid::tasks::TaskSE3Equality::dim |
( |
| ) |
const |
|
overridevirtual |
Return the dimension of the task. \info should be overloaded in the child class.
Implements tsid::tasks::TaskBase.
◆ frame_id()
Index tsid::tasks::TaskSE3Equality::frame_id |
( |
| ) |
const |
◆ getAcceleration()
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.
◆ getConstraint()
const ConstraintBase & tsid::tasks::TaskSE3Equality::getConstraint |
( |
| ) |
const |
|
overridevirtual |
◆ getDesiredAcceleration()
const Vector & tsid::tasks::TaskSE3Equality::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.
◆ getReference()
◆ Kd() [1/2]
const Vector & tsid::tasks::TaskSE3Equality::Kd |
( |
| ) |
const |
◆ Kd() [2/2]
◆ Kp() [1/2]
const Vector & tsid::tasks::TaskSE3Equality::Kp |
( |
| ) |
const |
◆ Kp() [2/2]
◆ position()
const Vector & tsid::tasks::TaskSE3Equality::position |
( |
| ) |
const |
|
overridevirtual |
◆ position_error()
const Vector & tsid::tasks::TaskSE3Equality::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.
◆ position_ref()
const Vector & tsid::tasks::TaskSE3Equality::position_ref |
( |
| ) |
const |
|
overridevirtual |
◆ setMask()
◆ setReference() [1/2]
void tsid::tasks::TaskSE3Equality::setReference |
( |
const SE3 & |
ref | ) |
|
◆ setReference() [2/2]
◆ useLocalFrame()
void tsid::tasks::TaskSE3Equality::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_frame | If true, represent jacobian and acceloration in the local frame. If false, represent them in the local world-oriented frame. |
◆ velocity()
const Vector & tsid::tasks::TaskSE3Equality::velocity |
( |
| ) |
const |
|
overridevirtual |
◆ velocity_error()
const Vector & tsid::tasks::TaskSE3Equality::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.
◆ velocity_ref()
const Vector & tsid::tasks::TaskSE3Equality::velocity_ref |
( |
| ) |
const |
|
overridevirtual |
◆ Index
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index tsid::tasks::TaskSE3Equality::Index |
◆ m_a_des
Vector tsid::tasks::TaskSE3Equality::m_a_des |
|
protected |
◆ m_a_des_masked
Vector tsid::tasks::TaskSE3Equality::m_a_des_masked |
|
protected |
◆ m_a_ref
Motion tsid::tasks::TaskSE3Equality::m_a_ref |
|
protected |
◆ m_constraint
◆ m_drift
Motion tsid::tasks::TaskSE3Equality::m_drift |
|
protected |
◆ m_drift_masked
Vector tsid::tasks::TaskSE3Equality::m_drift_masked |
|
protected |
◆ m_frame_id
Index tsid::tasks::TaskSE3Equality::m_frame_id |
|
protected |
◆ m_frame_name
std::string tsid::tasks::TaskSE3Equality::m_frame_name |
|
protected |
◆ m_J
Matrix6x tsid::tasks::TaskSE3Equality::m_J |
|
protected |
◆ m_J_rotated
Matrix6x tsid::tasks::TaskSE3Equality::m_J_rotated |
|
protected |
◆ m_Kd
Vector tsid::tasks::TaskSE3Equality::m_Kd |
|
protected |
◆ m_Kp
Vector tsid::tasks::TaskSE3Equality::m_Kp |
|
protected |
◆ m_local_frame
bool tsid::tasks::TaskSE3Equality::m_local_frame |
|
protected |
◆ m_M_ref
SE3 tsid::tasks::TaskSE3Equality::m_M_ref |
|
protected |
◆ m_p
Vector tsid::tasks::TaskSE3Equality::m_p |
|
protected |
◆ m_p_error
Motion tsid::tasks::TaskSE3Equality::m_p_error |
|
protected |
◆ m_p_error_masked_vec
Vector tsid::tasks::TaskSE3Equality::m_p_error_masked_vec |
|
protected |
◆ m_p_error_vec
Vector tsid::tasks::TaskSE3Equality::m_p_error_vec |
|
protected |
◆ m_p_ref
Vector tsid::tasks::TaskSE3Equality::m_p_ref |
|
protected |
◆ m_ref
◆ m_v
Vector tsid::tasks::TaskSE3Equality::m_v |
|
protected |
◆ m_v_error
Motion tsid::tasks::TaskSE3Equality::m_v_error |
|
protected |
◆ m_v_error_masked_vec
Vector tsid::tasks::TaskSE3Equality::m_v_error_masked_vec |
|
protected |
◆ m_v_error_vec
Vector tsid::tasks::TaskSE3Equality::m_v_error_vec |
|
protected |
◆ m_v_ref
Motion tsid::tasks::TaskSE3Equality::m_v_ref |
|
protected |
◆ m_v_ref_vec
Vector tsid::tasks::TaskSE3Equality::m_v_ref_vec |
|
protected |
◆ m_wMl
SE3 tsid::tasks::TaskSE3Equality::m_wMl |
|
protected |
The documentation for this class was generated from the following files: