32 m_frame_name(frameName),
33 m_constraint(name, 6, robot.
nv()),
37 "The frame with name '" + frameName +
"' does not exist");
53 m_J.setZero(6, robot.
nv());
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() *
204 for (
int i = 0;
i < 6;
i++) {
void SE3ToVector(const pinocchio::SE3 &M, RefVector vec)
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
#define TSID_DISABLE_WARNING_POP
RobotWrapper & m_robot
Reference on the robot model.
#define TSID_DISABLE_WARNING_PUSH
const Vector & Kp() const
const math::Vector & getDerivative() const
const TrajectorySample & getReference() const
ConstraintEquality m_constraint
const Model & model() const
Accessor to model.
#define TSID_DISABLE_WARNING_DEPRECATED
Motion frameClassicAcceleration(const Data &data, const Model::FrameIndex index) const
const Vector & vector() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW TSID_DEPRECATED math::Vector pos
TaskSE3Equality(const std::string &name, RobotWrapper &robot, const std::string &frameName)
void useLocalFrame(bool local_frame)
Specifies if the jacobian and desired acceloration should be expressed in the local frame or the loca...
const Vector & getDesiredAcceleration() const
const Vector & position() const
const Vector & velocity_ref() const
SE3 framePosition(const Data &data, const Model::FrameIndex index) const
Eigen::Map< const Eigen::Matrix< double, 3, 3 > > MapMatrix3
math::ConstRefVector ConstRefVector
virtual void setMask(math::ConstRefVector mask)
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
void errorInSE3(const pinocchio::SE3 &M, const pinocchio::SE3 &Mdes, pinocchio::Motion &error)
void setReference(TrajectorySample &ref)
const Eigen::Ref< const Vector > ConstRefVector
const Vector & velocity_error() const
const Vector & Kd() const
void frameJacobianLocal(Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
const Vector & position_error() const
Wrapper for a robot based on pinocchio.
ToVectorConstReturnType toVector() const
const math::Vector & getSecondDerivative() const
Vector m_v_error_masked_vec
Vector m_p_error_masked_vec
const Vector & velocity() const
virtual const Matrix & matrix() const
const Vector & position_ref() const
const ConstraintBase & compute(const double t, ConstRefVector q, ConstRefVector v, Data &data)
Motion frameVelocity(const Data &data, const Model::FrameIndex index) const
MotionTpl< _Scalar, _Options > & setZero()
Vector getAcceleration(ConstRefVector dv) const
virtual void setMask(math::ConstRefVector mask)
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
int dim() const
Return the dimension of the task. should be overloaded in the child class.
void resize(const unsigned int r, const unsigned int c)
const ConstraintBase & getConstraint() const