Go to the documentation of this file.
26 using namespace trajectories;
37 "The frame with name '" +
frameName +
"' does not exist");
81 "The size of the Kp vector needs to equal 6");
87 "The size of the Kd vector needs to equal 6");
96 ref.pos.size() == 12,
"The size of the reference vector needs to be 12");
166 m_wMl.rotation(oMi.rotation());
178 m_wMl.toActionMatrix() *
201 m_v = v_frame.toVector();
204 for (
int i = 0;
i < 6;
i++) {
SE3 framePosition(const Data &data, const Model::FrameIndex index) const
const Vector & position_error() const override
Motion frameVelocity(const Data &data, const Model::FrameIndex index) const
Vector m_v_error_masked_vec
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
void errorInSE3(const pinocchio::SE3 &M, const pinocchio::SE3 &Mdes, pinocchio::Motion &error)
const Vector & vector() const override
virtual void setMask(math::ConstRefVector mask) override
Abstract class representing a linear equality/inequality constraint. Equality constraints are represe...
virtual void setMask(math::ConstRefVector mask)
Vector getAcceleration(ConstRefVector dv) const override
const Vector & velocity_ref() const override
#define TSID_DISABLE_WARNING_POP
const ConstraintBase & compute(const double t, ConstRefVector q, ConstRefVector v, Data &data) override
#define TSID_DISABLE_WARNING_DEPRECATED
#define TSID_DISABLE_WARNING_PUSH
const ConstraintBase & getConstraint() const override
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
void resize(unsigned int r, unsigned int c) override
const TrajectorySample & getReference() const override
const Vector & getDesiredAcceleration() const override
Motion frameClassicAcceleration(const Data &data, const Model::FrameIndex index) const
const Vector & position() const override
const Model & model() const
Accessor to model.
TaskSE3Equality(const std::string &name, RobotWrapper &robot, const std::string &frameName)
virtual const Matrix & matrix() const
const Vector & velocity() const override
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
Eigen::Map< const Eigen::Matrix< double, 3, 3 > > MapMatrix3
void frameJacobianLocal(Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
const Vector & Kp() const
const typedef Eigen::Ref< const Vector > ConstRefVector
void SE3ToVector(const pinocchio::SE3 &M, RefVector vec)
ConstraintEquality m_constraint
Vector m_p_error_masked_vec
void setReference(TrajectorySample &ref)
Wrapper for a robot based on pinocchio.
int dim() const override
Return the dimension of the task. \info should be overloaded in the child class.
const Vector & Kd() const
RobotWrapper & m_robot
Reference on the robot model.
void useLocalFrame(bool local_frame)
Specifies if the jacobian and desired acceloration should be expressed in the local frame or the loca...
const Vector & position_ref() const override
math::ConstRefVector ConstRefVector
const Vector & velocity_error() const override
tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:16