Class Cartesian

Inheritance Relationships

Base Type

Class Documentation

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

The Cartesian class implements a Cartesian Impedance Controller rsulting in a Catesian Wrench to track:

W = M(xddot_d - Jdotqdot) + K(x_d-x) + D(xdot_d - xdot) + F_d

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, const AffineHelper &wrench)

Cartesian.

Parameters
  • task_id

  • robot

  • distal_link – controlled frame

  • base_link – base_frame where motion, impedance and force quantities are expressed

  • wrench – affine helper variable NOTICE: at the moment, the term M(xddot_d - Jdotqdot) is NOT computed!

void resetReference()

resetReference reset internal velocities and force references

void setReference(const Eigen::Affine3d &pose_ref)

setReference for desired pose and velocities

Parameters
  • pose_ref

  • vel_ref

void setReference(const Eigen::Affine3d &pose_ref, Eigen::Vector6d &vel_ref)
void setForceReference(const Eigen::Vector6d &_force_ref)

setForceReference

Parameters

_force_ref

void getReference(Eigen::Affine3d &pose_des)

getReference

Parameters
  • pose_des

  • twist_des

void getReference(Eigen::Affine3d &pose_des, Eigen::Vector6d &twist_des)
void setCartesianStiffness(const Eigen::Matrix6d &Kp)

setCartesianStiffness

Parameters
  • Kp

  • Kd

void setCartesianDamping(const Eigen::Matrix6d &Kd)
void getCartesianStiffness(Eigen::Matrix6d &Kp)

getCartesianStiffness

Parameters
  • Kp

  • Kd

void getCartesianDamping(Eigen::Matrix6d &Kd)
inline const std::string &getBaseLink() const

getBaseLink

Returns

base frame

inline const std::string &getDistalLink() const

getDistalLink

Returns

distal frame