- 3.0.2 rigid body dynamics module.
TermTaskspaceGeometricJacobian.hpp
Go to the documentation of this file.
1 /**********************************************************************************************************************
2 This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-toolbox), copyright by ETH Zurich
3 Licensed under the BSD-2 license (see LICENSE file in main directory)
4 **********************************************************************************************************************/
5 
6 #pragma once
7 
8 #include <ct/optcon/optcon.h>
9 
11 #include <ct/rbd/state/RBDState.h>
12 
13 namespace ct {
14 namespace rbd {
15 
23 template <class KINEMATICS, size_t STATE_DIM, size_t CONTROL_DIM>
24 class TermTaskspaceGeometricJacobian : public optcon::TermBase<STATE_DIM, CONTROL_DIM, double, double>
25 {
26 public:
27  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
28 
30 
32 
33  using state_matrix_t = Eigen::Matrix<double, STATE_DIM, STATE_DIM>;
34  using control_matrix_t = Eigen::Matrix<double, CONTROL_DIM, CONTROL_DIM>;
35  using control_state_matrix_t = Eigen::Matrix<double, CONTROL_DIM, STATE_DIM>;
36 
37 
40 
43  const Eigen::Matrix3d& Qpos,
44  const Eigen::Matrix3d& Qrot,
45  const core::StateVector<3>& w_pos_des,
46  const Eigen::Quaterniond& w_q_des,
47  const std::string& name = "TermTaskSpace")
48  : BASE(name), eeInd_(eeInd), Q_pos_(Qpos), Q_rot_(Qrot)
49  {
50  setReferencePosition(w_pos_des);
51  setReferenceOrientation(w_q_des);
52  }
53 
56  const Eigen::Matrix3d& Qpos,
57  const Eigen::Matrix3d& Qrot,
58  const ct::rbd::RigidBodyPose& rbdPose,
59  const std::string& name = "TermTaskSpace")
60  // delegate constructor
62  Qpos,
63  Qrot,
64  rbdPose.position().toImplementation(),
65  rbdPose.getRotationQuaternion().toImplementation(),
66  name)
67  {
68  }
69 
72  const Eigen::Matrix3d& Qpos,
73  const Eigen::Matrix3d& Qrot,
74  const core::StateVector<3>& w_pos_des,
75  const Eigen::Matrix3d& eulerXyz,
76  const std::string& name = "TermTaskSpace")
77  // delegate constructor
79  Qpos,
80  Qrot,
81  w_pos_des,
82  Eigen::Quaterniond(Eigen::AngleAxisd(eulerXyz(0), Eigen::Vector3d::UnitX()) *
83  Eigen::AngleAxisd(eulerXyz(1), Eigen::Vector3d::UnitY()) *
84  Eigen::AngleAxisd(eulerXyz(2), Eigen::Vector3d::UnitZ())),
85  name)
86  {
87  }
88 
91  const Eigen::Matrix3d& Qpos,
92  const Eigen::Matrix3d& Qrot,
93  const std::string& name = "TermTaskSpace")
94  : BASE(name), eeInd_(eeInd), Q_pos_(Qpos), Q_rot_(Qrot)
95  {
96  // arbitrary dummy values
97  Eigen::Quaterniond w_q_des(0.0, 0.0, 0.0, 1.0);
98  setReferenceOrientation(w_q_des);
100  }
101 
103  TermTaskspaceGeometricJacobian(const std::string& configFile, const std::string& termName, bool verbose = false)
104  {
105  loadConfigFile(configFile, termName, verbose);
106  }
107 
110  : BASE(arg),
111  eeInd_(arg.eeInd_),
112  kinematics_(KINEMATICS()),
113  Q_pos_(arg.Q_pos_),
114  Q_rot_(arg.Q_rot_),
115  x_ref_(arg.x_ref_),
116  R_ref_(arg.R_ref_)
117  {
118  }
119 
121  virtual ~TermTaskspaceGeometricJacobian() = default;
122 
125  {
126  return new TermTaskspaceGeometricJacobian(*this);
127  }
128 
130  virtual double evaluate(const Eigen::Matrix<double, STATE_DIM, 1>& x,
131  const Eigen::Matrix<double, CONTROL_DIM, 1>& u,
132  const double& t) override
133  {
134  // transform the robot state vector into a CT RBDState
135  RBDState rbdState;
136  rbdState.jointPositions() = x.template head<KINEMATICS::NJOINTS>();
137 
138  // position difference in world frame
139  Eigen::Matrix<double, 3, 1> xCurr = kinematics_.getEEPositionInWorld(eeInd_, rbdState.basePose(), rbdState.jointPositions()).toImplementation();
140  Eigen::Matrix<double, 3, 1> xDiff = xCurr - x_ref_;
141 
142  // compute the cost from the position error
143  double pos_cost = 0.5 * (xDiff.transpose() * Q_pos_ * xDiff)(0, 0);
144 
145  // get current end-effector rotation in world frame
146  Eigen::Matrix<double, 3, 3> ee_rot = kinematics_.getEERotInBase(eeInd_, rbdState.jointPositions());
147  Eigen::Quaterniond orientation(ee_rot);
148  Eigen::Quaterniond orientation_d_(R_ref_);
149  Eigen::Quaterniond error_quaternion(orientation * orientation_d_.inverse());
150  // convert to axis angle
151  Eigen::AngleAxis<double> error_quaternion_angle_axis(error_quaternion);
152  // compute "orientation position_error"
153  Eigen::Matrix<double, 3, 1> qDiff = error_quaternion_angle_axis.axis() * error_quaternion_angle_axis.angle();
154 
155  double rot_cost = 0.5 * (qDiff.transpose() * Q_rot_ * qDiff)(0, 0);
156 
157  return pos_cost + rot_cost;
158  }
159 
160 
164  const double& t) override
165  {
167  grad.setZero();
168 
169  RBDState rbdState;
170  rbdState.jointPositions() = x.template head<KINEMATICS::NJOINTS>();
171 
172  Eigen::Matrix<double, 6, KINEMATICS::NJOINTS> J = kinematics_.getJacobianBaseEEbyId(eeInd_, rbdState);
173  Eigen::Matrix<double, 3, KINEMATICS::NJOINTS> J_pos = J.template bottomRows<3>();
174  Eigen::Matrix<double, 3, KINEMATICS::NJOINTS> J_q = J.template topRows<3>();
175 
176  // position difference in world frame
177  Eigen::Matrix<double, 3, 1> xCurr =
178  kinematics_.getEEPositionInWorld(eeInd_, rbdState.basePose(), rbdState.jointPositions()).toImplementation();
179  Eigen::Matrix<double, 3, 1> xDiff = xCurr - x_ref_;
180 
181  grad.template head<KINEMATICS::NJOINTS>() += J_pos.transpose() * Q_pos_ * xDiff;
182 
183 
184  // get current end-effector rotation in world frame
185  Eigen::Matrix<double, 3, 3> ee_rot = kinematics_.getEERotInBase(eeInd_, rbdState.jointPositions());
186  Eigen::Quaterniond orientation(ee_rot);
187  Eigen::Quaterniond orientation_d_(R_ref_);
188  Eigen::Quaterniond error_quaternion(orientation * orientation_d_.inverse());
189  // convert to axis angle
190  Eigen::AngleAxis<double> error_quaternion_angle_axis(error_quaternion);
191  // compute "orientation position_error"
192  Eigen::Matrix<double, 3, 1> qDiff = error_quaternion_angle_axis.axis() * error_quaternion_angle_axis.angle();
193 
194  grad.template head<KINEMATICS::NJOINTS>() += J_q.transpose() * Q_rot_ * qDiff;
195 
196  return grad;
197  }
198 
202  const double& t) override
203  {
205  }
206 
210  const double& t) override
211  {
212  RBDState rbdState;
213  rbdState.jointPositions() = x.template head<KINEMATICS::NJOINTS>();
214 
215  Eigen::Matrix<double, 6, KINEMATICS::NJOINTS> J = kinematics_.getJacobianBaseEEbyId(eeInd_, rbdState);
216  Eigen::Matrix<double, 3, KINEMATICS::NJOINTS> J_pos = J.template bottomRows<3>();
217  Eigen::Matrix<double, 3, KINEMATICS::NJOINTS> J_q = J.template topRows<3>();
218 
219  state_matrix_t Q = state_matrix_t::Zero();
220  Q.template topLeftCorner<KINEMATICS::NJOINTS, KINEMATICS::NJOINTS>() += J_pos.transpose() * Q_pos_ * J_pos;
221  Q.template topLeftCorner<KINEMATICS::NJOINTS, KINEMATICS::NJOINTS>() += J_q.transpose() * Q_rot_ * J_q;
222 
223  return Q;
224  }
225 
229  const double& t) override
230  {
231  return control_matrix_t::Zero();
232  }
233 
237  const double& t) override
238  {
239  return control_state_matrix_t::Zero();
240  }
241 
242 
244  void loadConfigFile(const std::string& filename, const std::string& termName, bool verbose = false) override
245  {
246  if (verbose)
247  std::cout << "Loading TermTaskspaceGeometricJacobian from file " << filename << std::endl;
248 
249  ct::optcon::loadScalarCF(filename, "eeId", eeInd_, termName);
250  ct::optcon::loadMatrixCF(filename, "Q_rot", Q_rot_, termName);
251  ct::optcon::loadMatrixCF(filename, "Q_pos", Q_pos_, termName);
252 
253  Eigen::Matrix<double, 3, 1> w_p_ref;
254  ct::optcon::loadMatrixCF(filename, "x_des", w_p_ref, termName);
255  setReferencePosition(w_p_ref);
256 
257 
258  // try loading euler angles
259  if (verbose)
260  std::cout << "trying to load Euler angles" << std::endl;
261  try
262  {
263  Eigen::Vector3d eulerXyz;
264  ct::optcon::loadMatrixCF(filename, "eulerXyz_des", eulerXyz, termName);
265  Eigen::Quaternion<double> quat_des(Eigen::AngleAxisd(eulerXyz(0), Eigen::Vector3d::UnitX()) *
266  Eigen::AngleAxisd(eulerXyz(1), Eigen::Vector3d::UnitY()) *
267  Eigen::AngleAxisd(eulerXyz(2), Eigen::Vector3d::UnitZ()));
268  setReferenceOrientation(quat_des);
269  if (verbose)
270  std::cout << "Read desired Euler Angles Xyz as = \n" << eulerXyz.transpose() << std::endl;
271  } catch (const std::exception& e)
272  {
273  throw std::runtime_error(
274  "Failed to load TermTaskspaceGeometricJacobian, could not find a desired end effector orientation in "
275  "file.");
276  }
277 
278  if (verbose)
279  {
280  std::cout << "Read eeId as eeId = \n" << eeInd_ << std::endl;
281  std::cout << "Read Q_pos as Q_pos = \n" << Q_pos_ << std::endl;
282  std::cout << "Read Q_rot as Q_rot = \n" << Q_rot_ << std::endl;
283  std::cout << "Read x_des as x_des = \n" << getReferencePosition().transpose() << std::endl;
284  }
285  }
286 
287 
289  const Eigen::Matrix<double, 3, 1> getReferencePosition() const { return x_ref_; }
291  void setReferencePosition(Eigen::Matrix<double, 3, 1> p_ref) { x_ref_ = p_ref; }
293  const Eigen::Quaterniond getReferenceOrientation() const { return Eigen::Quaterniond(R_ref_); }
295  void setReferenceOrientation(const Eigen::Matrix<double, 3, 3>& w_R_ref) { R_ref_ = w_R_ref; }
296 
298  void setReferenceOrientation(const Eigen::Quaterniond& w_q_des)
299  {
300  setReferenceOrientation(w_q_des.normalized().toRotationMatrix());
301  }
302 
305  {
307  }
308 
309 
310 private:
312  size_t eeInd_;
313 
315  KINEMATICS kinematics_;
316 
318  Eigen::Matrix3d Q_pos_;
319 
321  Eigen::Matrix3d Q_rot_;
322 
323  Eigen::Matrix<double, 3, 1> x_ref_; // ref position
324  Eigen::Matrix<double, 3, 3> R_ref_; // ref rotation
325 };
326 
327 
328 } // namespace rbd
329 } // namespace ct
void loadConfigFile(const std::string &filename, const std::string &termName, bool verbose=false) override
load term information from configuration file (stores data in member variables)
Definition: TermTaskspaceGeometricJacobian.hpp:244
void setReferenceOrientation(const Eigen::Quaterniond &w_q_des)
set desired end-effector orientation in world frame
Definition: TermTaskspaceGeometricJacobian.hpp:298
Eigen::Matrix< double, STATE_DIM, STATE_DIM > state_matrix_t
Definition: TermTaskspaceGeometricJacobian.hpp:33
TermTaskspaceGeometricJacobian(size_t eeInd, const Eigen::Matrix3d &Qpos, const Eigen::Matrix3d &Qrot, const ct::rbd::RigidBodyPose &rbdPose, const std::string &name="TermTaskSpace")
constructor taking a full RigidBodyPose
Definition: TermTaskspaceGeometricJacobian.hpp:55
RigidBodyPose_t & basePose()
get base pose
Definition: RBDState.h:67
JointState< NJOINTS, SCALAR >::JointPositionBlock jointPositions()
get joint positions
Definition: RBDState.h:99
Cored::Vector3 Vector3d
Definition: rbd.h:137
tpl::RigidBodyPose< double > RigidBodyPose
Definition: RigidBodyPose.h:426
Definition: eigen_traits.h:23
TermTaskspaceGeometricJacobian(const TermTaskspaceGeometricJacobian &arg)
copy constructor
Definition: TermTaskspaceGeometricJacobian.hpp:109
joint states and base states
Definition: RBDState.h:27
A costfunction term that defines a cost on a task-space pose, for fix-base robots only...
Definition: TermTaskspaceGeometricJacobian.hpp:24
virtual core::ControlVector< CONTROL_DIM > controlDerivative(const core::StateVector< STATE_DIM > &x, const core::ControlVector< CONTROL_DIM > &u, const double &t) override
compute derivative of this cost term w.r.t. the control input
Definition: TermTaskspaceGeometricJacobian.hpp:200
const Eigen::Quaterniond getReferenceOrientation() const
retrieve reference ee orientation in world frame
Definition: TermTaskspaceGeometricJacobian.hpp:293
virtual control_matrix_t controlSecondDerivative(const core::StateVector< STATE_DIM > &x, const core::ControlVector< CONTROL_DIM > &u, const double &t) override
compute second order derivative of this cost term w.r.t. the control input
Definition: TermTaskspaceGeometricJacobian.hpp:227
virtual control_state_matrix_t stateControlDerivative(const core::StateVector< STATE_DIM > &x, const core::ControlVector< CONTROL_DIM > &u, const double &t) override
compute the cross-term derivative (state-control) of this cost function term
Definition: TermTaskspaceGeometricJacobian.hpp:235
TermTaskspaceGeometricJacobian(size_t eeInd, const Eigen::Matrix3d &Qpos, const Eigen::Matrix3d &Qrot, const core::StateVector< 3 > &w_pos_des, const Eigen::Quaterniond &w_q_des, const std::string &name="TermTaskSpace")
constructor using a quaternion for orientation
Definition: TermTaskspaceGeometricJacobian.hpp:42
TermTaskspaceGeometricJacobian()=default
default constructor
bool verbose
Definition: rbdJITtests.h:15
virtual ~TermTaskspaceGeometricJacobian()=default
destructor
const Eigen::Matrix< double, 3, 1 > getReferencePosition() const
retrieve reference position in world frame
Definition: TermTaskspaceGeometricJacobian.hpp:289
virtual double evaluate(const Eigen::Matrix< double, STATE_DIM, 1 > &x, const Eigen::Matrix< double, CONTROL_DIM, 1 > &u, const double &t) override
evaluate
Definition: TermTaskspaceGeometricJacobian.hpp:130
TermTaskspaceGeometricJacobian(const std::string &configFile, const std::string &termName, bool verbose=false)
construct this term with info loaded from a configuration file
Definition: TermTaskspaceGeometricJacobian.hpp:103
void setReferenceOrientation(const Eigen::Matrix< double, 3, 3 > &w_R_ref)
set desired end-effector orientation in world frame
Definition: TermTaskspaceGeometricJacobian.hpp:295
void setReferencePosition(Eigen::Matrix< double, 3, 1 > p_ref)
set the end-effector reference position (in base coordinates)
Definition: TermTaskspaceGeometricJacobian.hpp:291
Eigen::Matrix< double, CONTROL_DIM, CONTROL_DIM > control_matrix_t
Definition: TermTaskspaceGeometricJacobian.hpp:34
void loadScalarCF(const std::string &filename, const std::string &scalarName, SCALAR &scalar, const std::string &termName="")
double Qrot
Definition: rbdJITtests.h:28
virtual TermTaskspaceGeometricJacobian< KINEMATICS, STATE_DIM, CONTROL_DIM > * clone() const override
deep cloning
Definition: TermTaskspaceGeometricJacobian.hpp:124
TermTaskspaceGeometricJacobian(size_t eeInd, const Eigen::Matrix3d &Qpos, const Eigen::Matrix3d &Qrot, const core::StateVector< 3 > &w_pos_des, const Eigen::Matrix3d &eulerXyz, const std::string &name="TermTaskSpace")
constructor using Euler angles for orientation
Definition: TermTaskspaceGeometricJacobian.hpp:71
virtual state_matrix_t stateSecondDerivative(const core::StateVector< STATE_DIM > &x, const core::ControlVector< CONTROL_DIM > &u, const double &t) override
compute second order derivative of this cost term w.r.t. the state
Definition: TermTaskspaceGeometricJacobian.hpp:208
TermTaskspaceGeometricJacobian(size_t eeInd, const Eigen::Matrix3d &Qpos, const Eigen::Matrix3d &Qrot, const std::string &name="TermTaskSpace")
constructor which sets the target pose to dummy values
Definition: TermTaskspaceGeometricJacobian.hpp:90
const ct::rbd::RigidBodyPose getReferencePose() const
return the reference pose as RigidBodyPose
Definition: TermTaskspaceGeometricJacobian.hpp:304
const Eigen::Matrix< double, 3, 3 > Qpos
Definition: rbdJITtests.h:27
void loadMatrixCF(const std::string &filename, const std::string &matrixName, Eigen::Matrix< SCALAR, ROW, COL > &matrix, const std::string &termName="")
Eigen::Matrix< double, CONTROL_DIM, STATE_DIM > control_state_matrix_t
Definition: TermTaskspaceGeometricJacobian.hpp:35
virtual core::StateVector< STATE_DIM > stateDerivative(const core::StateVector< STATE_DIM > &x, const core::ControlVector< CONTROL_DIM > &u, const double &t) override
compute derivative of this cost term w.r.t. the state
Definition: TermTaskspaceGeometricJacobian.hpp:162