Class Cartesian

Inheritance Relationships

Base Type

Class Documentation

class Cartesian : public OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>

Public Types

typedef std::shared_ptr<Cartesian> Ptr

Public Functions

Cartesian(const std::string task_id, const XBot::ModelInterface &robot, const std::string &distal_link, const std::string &base_link)
Cartesian(const std::string task_id, const XBot::ModelInterface &robot, const std::string &distal_link, const std::string &base_link, const AffineHelper &qddot)
void setGainType(GainType type)
GainType getGainType() const
const std::string &getBaseLink() const
const std::string &getDistalLink() const
void setPositionReference(const Eigen::Vector3d &pos_ref)

setReference sets a new reference for the Cartesian task.

The task error IS NOT recomputed immediately, you need to call the _update(x) function Notice how the setReference(…) needs to be called before each _update(x) of the Cartesian task, since THE _update() RESETS THE FEED-FORWARD VELOCITY and ACCELERATION TERMS for safety reasons.

Parameters
  • pose_ref – the \(R^{4x4}\) homogeneous transform matrix describing the desired pose for the distal_link in the base_link frame of reference.

  • vel_ref – is a \(R^{6}\) twist describing the desired trajectory velocity

  • acc_ref – is a \(R^{6}\) twist describing the desired trajectory acceleration, and it represents a feed-forward term in the cartesian task computation.

void setReference(const Eigen::Affine3d &ref)
void setReference(const KDL::Frame &ref)
void setReference(const Eigen::Affine3d &pose_ref, const Eigen::Vector6d &vel_ref)
void setReference(const KDL::Frame &pose_ref, const KDL::Twist &vel_ref)
void setReference(const Eigen::Affine3d &pose_ref, const Eigen::Vector6d &vel_ref, const Eigen::Vector6d &acc_ref)
void setReference(const KDL::Frame &pose_ref, const KDL::Twist &vel_ref, const KDL::Twist &acc_ref)
void setVirtualForce(const Eigen::Vector6d &virtual_force_ref)

setVirtualForce this version permits to set a virtual force which is transformed into an acceleration using:

 xddot = (JB^1J')F
where F is the virtual force, J is the task Jacobian and B is the inertia matrix. NOTICE: if the SubTask is used, due to the coupling given by the inertia matrix, the provided reference F have to contain 0 in the non controlled directions. For example:

T%{0,2,4} : F = [fx, 0, fz, 0, fp, 0]’

Parameters

virtual_force_ref

void getReference(Eigen::Affine3d &ref) const
void getReference(KDL::Frame &ref) const
void getReference(Eigen::Affine3d &desiredPose, Eigen::Vector6d &desiredTwist) const
void getReference(KDL::Frame &desiredPose, KDL::Twist &desiredTwist) const
void getReference(Eigen::Affine3d &desiredPose, Eigen::Vector6d &desiredTwist, Eigen::Vector6d &desiredAcceleration) const
void getReference(KDL::Frame &desiredPose, KDL::Twist &desiredTwist, KDL::Twist &desiredAcceleration) const
const Eigen::Vector6d &getCachedVelocityReference() const

getCachedVelocityReference can be used to get Velocity reference after update(), it will reset next update()

Returns

internal velcity reference

const Eigen::Vector6d &getCachedAccelerationReference() const

getCachedAccelerationReference can be used to get Velocity reference after update(), it will reset next update()

Returns

internal acceleration reference

const Eigen::Vector6d &getCachedVirtualForceReference() const

getCachedVirtualForceReference can be used to get virtual force reference after update(), it will reset next update()

Returns

internal virtual force reference

const Eigen::Affine3d &getActualPose() const
void getActualPose(Eigen::Affine3d &actual) const
void getActualPose(KDL::Frame &actual)
const Eigen::Vector6d &getActualTwist() const
void getActualTwist(Eigen::Vector6d &actual) const
void getActualTwist(KDL::Twist &actual)
virtual bool reset()

reset permits to reset a task and all related variables.

The correctness of the implementation depends to the particular task. Default implementation does nothing and return false.

Returns

false

void setLambda(double lambda1, double lambda2)
virtual void setLambda(double lambda)
void getLambda(double &lambda, double &lambda2)

getLambda return both position and velocity convergence gains

Parameters
  • lambda – position gain

  • lambda2 – velocity gain

const double getLambda2() const

getLambda2 return velocity convergence gain

Returns

lambda2 gain

void setOrientationGain(double orientation_gain)
const double getOrientationErrorGain() const
const bool baseLinkIsWorld() const
bool setDistalLink(const std::string &distal_link)

Changes the distal link of the task.

It also resets the reference according to the current robot pose.

Parameters

distal_link – the new distal link

Returns

false if the distal link does not exists

bool setBaseLink(const std::string &base_link)

setBaseLink change the base link of the task

Parameters

base_link – the new base link

Returns

false if the base link does not exists

void setKp(const Eigen::Matrix6d &Kp)

setKp set position gain

Parameters

Kp – a SPD matrix

void setKd(const Eigen::Matrix6d &Kd)

setKd set velocity gain

Parameters

Kd – a SPD matrix

void setGains(const Eigen::Matrix6d &Kp, const Eigen::Matrix6d &Kd)

setGains set both position and velocity gains

Parameters
  • Kp – a SPD matrix

  • Kd – a SPD matrix

const Eigen::Matrix6d &getKp() const

getKp

Returns

position gain

const Eigen::Matrix6d &getKd() const

getKd

Returns

velocity gain

void getGains(Eigen::Matrix6d &Kp, Eigen::Matrix6d &Kd)

getGains return both position and velocity gains

Parameters
  • Kp

  • Kd

const Eigen::Vector6d &getError() const

getError returns the 6d cartesian error (position and orientation) between actual and reference pose

Returns

a \(R^{6}\) vector describing cartesian error between actual and reference pose

const Eigen::Vector6d &getVelocityError() const
inline const double getLambda() const

getLambda

Returns

the lambda weight of the task

Public Static Functions

static bool isCartesian(OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>::TaskPtr task)
static OpenSoT::tasks::acceleration::Cartesian::Ptr asCartesian(OpenSoT::Task<Eigen::MatrixXd, Eigen::VectorXd>::TaskPtr task)