tasks/task-se3-equality.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2017 CNRS, NYU, MPI Tübingen
3 //
4 // This file is part of tsid
5 // tsid is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 // tsid is distributed in the hope that it will be
10 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12 // General Lesser Public License for more details. You should have
13 // received a copy of the GNU Lesser General Public License along with
14 // tsid If not, see
15 // <http://www.gnu.org/licenses/>.
16 //
17 
18 #ifndef __invdyn_task_se3_equality_hpp__
19 #define __invdyn_task_se3_equality_hpp__
20 
24 
25 #include <pinocchio/multibody/model.hpp>
26 #include <pinocchio/multibody/data.hpp>
27 
28 namespace tsid {
29 namespace tasks {
30 
31 class TaskSE3Equality : public TaskMotion {
32  public:
33  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
34 
35  typedef math::Index Index;
43 
44  TaskSE3Equality(const std::string& name, RobotWrapper& robot,
45  const std::string& frameName);
46 
47  virtual ~TaskSE3Equality() {}
48 
49  int dim() const;
50 
51  const ConstraintBase& compute(const double t, ConstRefVector q,
52  ConstRefVector v, Data& data);
53 
54  const ConstraintBase& getConstraint() const;
55 
56  void setReference(TrajectorySample& ref);
57  void setReference(const SE3& ref);
58  const TrajectorySample& getReference() const;
59 
64  const Vector& getDesiredAcceleration() const;
65 
70  Vector getAcceleration(ConstRefVector dv) const;
71 
72  virtual void setMask(math::ConstRefVector mask);
73 
78  const Vector& position_error() const;
79 
84  const Vector& velocity_error() const;
85 
86  const Vector& position() const;
87  const Vector& velocity() const;
88  const Vector& position_ref() const;
89  const Vector& velocity_ref() const;
90 
91  const Vector& Kp() const;
92  const Vector& Kd() const;
93  void Kp(ConstRefVector Kp);
94  void Kd(ConstRefVector Kp);
95 
96  Index frame_id() const;
97 
105  void useLocalFrame(bool local_frame);
106 
107  protected:
108  std::string m_frame_name;
109  Index m_frame_id;
113  Vector m_p, m_v;
115  Motion m_v_ref, m_a_ref;
117  Vector m_Kp;
118  Vector m_Kd;
120  Motion m_drift;
122  Matrix6x m_J;
123  Matrix6x m_J_rotated;
124  ConstraintEquality m_constraint;
125  TrajectorySample m_ref;
127 };
128 
129 } // namespace tasks
130 } // namespace tsid
131 
132 #endif // ifndef __invdyn_task_se3_equality_hpp__
std::size_t Index
Definition: math/fwd.hpp:53
math::ConstraintEquality ConstraintEquality
const std::string & name() const
Definition: task-base.cpp:25
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hpp:35
const TrajectorySample & getReference() const
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...
data
Definition: setup.in.py:48
pinocchio::Data::Matrix6x Matrix6x
math::ConstRefVector ConstRefVector
Definition: task-base.hpp:39
virtual void setMask(math::ConstRefVector mask)
void setReference(TrajectorySample &ref)
const Eigen::Ref< const Vector > ConstRefVector
Definition: math/fwd.hpp:48
Wrapper for a robot based on pinocchio.
trajectories::TrajectorySample TrajectorySample
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Index Index
Eigen::TensorRef< Tensor > ref(Eigen::TensorRef< Tensor > tensor)
Transform3f t
const ConstraintBase & compute(const double t, ConstRefVector q, ConstRefVector v, Data &data)
Vector getAcceleration(ConstRefVector dv) const
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
string frameName
Definition: test_Contact.py:29
int dim() const
Return the dimension of the task. should be overloaded in the child class.
const ConstraintBase & getConstraint() const


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sun Jul 2 2023 02:21:51