Class CartesianVelocity

Inheritance Relationships

Base Type

Class Documentation

class CartesianVelocity : public OpenSoT::Constraint<Eigen::MatrixXd, Eigen::VectorXd>

The CartesianVelocity class applied Cartesian velocity limits to a Cartesian task.

Public Types

typedef std::shared_ptr<CartesianVelocity> Ptr

Public Functions

CartesianVelocity(const Eigen::Vector6d velocityLimits, const double dT, const OpenSoT::tasks::velocity::Cartesian::Ptr &task)

CartesianVelocity constructor.

Parameters
  • velocityLimits – a vector of 6 elements describing the maximum twist admissible for the specified Cartesian task, in the task frame of reference.

  • dT – the time constant at which we are performing velocity control [s]

  • task – a pointer to a Cartesian task. Notice how the task needs to be updated in order for the constraint to work

CartesianVelocity(const Eigen::Vector3d velocityLimits, const double dT, const OpenSoT::tasks::velocity::CoM::Ptr &task)
virtual void update()

Updates the A, b, Aeq, beq, Aineq, b*Bound matrices.

const Eigen::VectorXd &getVelocityLimits() const

getVelocityLimits

Returns

vector of velocity limits

void setVelocityLimits(const Eigen::Vector6d &velocityLimits)

setVelocityLimits

Parameters

velocityLimits – constraints

void setVelocityLimits(const Eigen::Vector3d &velocityLimits)