| Line |
Branch |
Exec |
Source |
| 1 |
|
|
// |
| 2 |
|
|
// Copyright (c) 2016-2020 CNRS INRIA |
| 3 |
|
|
// |
| 4 |
|
|
|
| 5 |
|
|
#ifndef __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__ |
| 6 |
|
|
#define __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__ |
| 7 |
|
|
|
| 8 |
|
|
#include "pinocchio/multibody/liegroup/fwd.hpp" |
| 9 |
|
|
|
| 10 |
|
|
#include <limits> |
| 11 |
|
|
|
| 12 |
|
|
namespace pinocchio |
| 13 |
|
|
{ |
| 14 |
|
|
constexpr int SELF = 0; |
| 15 |
|
|
|
| 16 |
|
|
#define PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived, TYPENAME) \ |
| 17 |
|
|
typedef LieGroupBase<Derived> Base; \ |
| 18 |
|
|
typedef TYPENAME Base::Index Index; \ |
| 19 |
|
|
typedef TYPENAME traits<Derived>::Scalar Scalar; \ |
| 20 |
|
|
enum \ |
| 21 |
|
|
{ \ |
| 22 |
|
|
Options = traits<Derived>::Options, \ |
| 23 |
|
|
NQ = Base::NQ, \ |
| 24 |
|
|
NV = Base::NV \ |
| 25 |
|
|
}; \ |
| 26 |
|
|
typedef TYPENAME Base::ConfigVector_t ConfigVector_t; \ |
| 27 |
|
|
typedef TYPENAME Base::TangentVector_t TangentVector_t; \ |
| 28 |
|
|
typedef TYPENAME Base::JacobianMatrix_t JacobianMatrix_t |
| 29 |
|
|
|
| 30 |
|
|
#define PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE(Derived) \ |
| 31 |
|
|
PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived, PINOCCHIO_MACRO_EMPTY_ARG) |
| 32 |
|
|
|
| 33 |
|
|
#define PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE(Derived) \ |
| 34 |
|
|
PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived, typename) |
| 35 |
|
|
|
| 36 |
|
|
template<typename Derived> |
| 37 |
|
|
struct LieGroupBase |
| 38 |
|
|
{ |
| 39 |
|
|
typedef Derived LieGroupDerived; |
| 40 |
|
|
typedef int Index; |
| 41 |
|
|
typedef typename traits<LieGroupDerived>::Scalar Scalar; |
| 42 |
|
|
enum |
| 43 |
|
|
{ |
| 44 |
|
|
Options = traits<LieGroupDerived>::Options, |
| 45 |
|
|
NQ = traits<LieGroupDerived>::NQ, |
| 46 |
|
|
NV = traits<LieGroupDerived>::NV |
| 47 |
|
|
}; |
| 48 |
|
|
|
| 49 |
|
|
typedef Eigen::Matrix<Scalar, NQ, 1, Options> ConfigVector_t; |
| 50 |
|
|
typedef Eigen::Matrix<Scalar, NV, 1, Options> TangentVector_t; |
| 51 |
|
|
typedef Eigen::Matrix<Scalar, NV, NV, Options> JacobianMatrix_t; |
| 52 |
|
|
|
| 53 |
|
|
/// \name API with return value as argument |
| 54 |
|
|
/// \{ |
| 55 |
|
|
|
| 56 |
|
|
/** |
| 57 |
|
|
* @brief Integrate a joint's configuration with a tangent vector during one unit time |
| 58 |
|
|
* duration |
| 59 |
|
|
* |
| 60 |
|
|
* @param[in] q the initial configuration. |
| 61 |
|
|
* @param[in] v the tangent velocity. |
| 62 |
|
|
* |
| 63 |
|
|
* @param[out] qout the configuration integrated. |
| 64 |
|
|
*/ |
| 65 |
|
|
template<class ConfigIn_t, class Tangent_t, class ConfigOut_t> |
| 66 |
|
|
void integrate( |
| 67 |
|
|
const Eigen::MatrixBase<ConfigIn_t> & q, |
| 68 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 69 |
|
|
const Eigen::MatrixBase<ConfigOut_t> & qout) const; |
| 70 |
|
|
|
| 71 |
|
|
/** |
| 72 |
|
|
* @brief Computes the Jacobian of the integrate operator around zero. |
| 73 |
|
|
* |
| 74 |
|
|
* @details This function computes the Jacobian of the configuration vector variation |
| 75 |
|
|
* (component-vise) with respect to a small variation in the tangent. |
| 76 |
|
|
* |
| 77 |
|
|
* @param[in] q configuration vector. |
| 78 |
|
|
* |
| 79 |
|
|
* @param[out] J the Jacobian of the log of the Integrate operation w.r.t. the configuration |
| 80 |
|
|
* vector q. |
| 81 |
|
|
* |
| 82 |
|
|
* @remarks This function might be useful for instance when using google-ceres to compute the |
| 83 |
|
|
* Jacobian of the integrate operation. |
| 84 |
|
|
*/ |
| 85 |
|
|
template<class Config_t, class Jacobian_t> |
| 86 |
|
|
void integrateCoeffWiseJacobian( |
| 87 |
|
|
const Eigen::MatrixBase<Config_t> & q, const Eigen::MatrixBase<Jacobian_t> & J) const; |
| 88 |
|
|
|
| 89 |
|
|
/** |
| 90 |
|
|
* @brief Computes the Jacobian of a small variation of the configuration vector or the |
| 91 |
|
|
* tangent vector into tangent space at identity. |
| 92 |
|
|
* |
| 93 |
|
|
* @details This Jacobian corresponds to the Jacobian of \f$ (\mathbf{q} \oplus \delta |
| 94 |
|
|
* \mathbf{q}) \oplus \mathbf{v} \f$ with \f$ \delta \mathbf{q} \rightarrow 0 \f$ if arg == ARG0 |
| 95 |
|
|
* or \f$ \delta \mathbf{v} \rightarrow 0 \f$ if arg == ARG1. |
| 96 |
|
|
* |
| 97 |
|
|
* @param[in] q configuration vector. |
| 98 |
|
|
* @param[in] v tangent vector. |
| 99 |
|
|
* @param[in] op assignment operator (SETTO, ADDTO or RMTO). |
| 100 |
|
|
* @tparam arg ARG0 (resp. ARG1) to get the Jacobian with respect to q (resp. v). |
| 101 |
|
|
* |
| 102 |
|
|
* @param[out] J the Jacobian of the Integrate operation w.r.t. the argument arg. |
| 103 |
|
|
*/ |
| 104 |
|
|
template<ArgumentPosition arg, class Config_t, class Tangent_t, class JacobianOut_t> |
| 105 |
|
320 |
void dIntegrate( |
| 106 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 107 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 108 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & J, |
| 109 |
|
|
AssignmentOperatorType op = SETTO) const |
| 110 |
|
|
{ |
| 111 |
|
|
PINOCCHIO_STATIC_ASSERT(arg == ARG0 || arg == ARG1, arg_SHOULD_BE_ARG0_OR_ARG1); |
| 112 |
|
320 |
return dIntegrate( |
| 113 |
|
640 |
q.derived(), v.derived(), PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t, J), arg, op); |
| 114 |
|
|
} |
| 115 |
|
|
|
| 116 |
|
|
/** |
| 117 |
|
|
* @brief Computes the Jacobian of a small variation of the configuration vector or the |
| 118 |
|
|
* tangent vector into tangent space at identity. |
| 119 |
|
|
* |
| 120 |
|
|
* @details This Jacobian corresponds to the Jacobian of \f$ (\mathbf{q} \oplus \delta |
| 121 |
|
|
* \mathbf{q}) \oplus \mathbf{v} \f$ with \f$ \delta \mathbf{q} \rightarrow 0 \f$ if arg == ARG0 |
| 122 |
|
|
* or \f$ \delta \mathbf{v} \rightarrow 0 \f$ if arg == ARG1. |
| 123 |
|
|
* |
| 124 |
|
|
* @param[in] q configuration vector. |
| 125 |
|
|
* @param[in] v tangent vector. |
| 126 |
|
|
* @param[in] arg ARG0 (resp. ARG1) to get the Jacobian with respect to q (resp. v). |
| 127 |
|
|
* @param[in] op assignment operator (SETTO, ADDTO and RMTO). |
| 128 |
|
|
* |
| 129 |
|
|
* @param[out] J the Jacobian of the Integrate operation w.r.t. the argument arg. |
| 130 |
|
|
*/ |
| 131 |
|
|
template<class Config_t, class Tangent_t, class JacobianOut_t> |
| 132 |
|
|
void dIntegrate( |
| 133 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 134 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 135 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & J, |
| 136 |
|
|
const ArgumentPosition arg, |
| 137 |
|
|
const AssignmentOperatorType op = SETTO) const; |
| 138 |
|
|
|
| 139 |
|
|
/** |
| 140 |
|
|
* @brief Computes the Jacobian of a small variation of the configuration vector into |
| 141 |
|
|
* tangent space at identity. |
| 142 |
|
|
* |
| 143 |
|
|
* @details This Jacobian corresponds to the Jacobian of \f$ (\mathbf{q} \oplus \delta |
| 144 |
|
|
* \mathbf{q}) \oplus \mathbf{v} \f$ with \f$ \delta \mathbf{q} \rightarrow 0 \f$. |
| 145 |
|
|
* |
| 146 |
|
|
* @param[in] q configuration vector. |
| 147 |
|
|
* @param[in] v tangent vector. |
| 148 |
|
|
* @param[in] op assignment operator (SETTO, ADDTO or RMTO). |
| 149 |
|
|
* |
| 150 |
|
|
* @param[out] J the Jacobian of the Integrate operation w.r.t. the configuration vector q. |
| 151 |
|
|
*/ |
| 152 |
|
|
template<class Config_t, class Tangent_t, class JacobianOut_t> |
| 153 |
|
|
void dIntegrate_dq( |
| 154 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 155 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 156 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & J, |
| 157 |
|
|
const AssignmentOperatorType op = SETTO) const; |
| 158 |
|
|
|
| 159 |
|
|
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t> |
| 160 |
|
|
void dIntegrate_dq( |
| 161 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 162 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 163 |
|
|
const Eigen::MatrixBase<JacobianIn_t> & Jin, |
| 164 |
|
|
int self, |
| 165 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & Jout, |
| 166 |
|
|
const AssignmentOperatorType op = SETTO) const; |
| 167 |
|
|
|
| 168 |
|
|
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t> |
| 169 |
|
|
void dIntegrate_dq( |
| 170 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 171 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 172 |
|
|
int self, |
| 173 |
|
|
const Eigen::MatrixBase<JacobianIn_t> & Jin, |
| 174 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & Jout, |
| 175 |
|
|
const AssignmentOperatorType op = SETTO) const; |
| 176 |
|
|
|
| 177 |
|
|
/** |
| 178 |
|
|
* @brief Computes the Jacobian of a small variation of the tangent vector into tangent |
| 179 |
|
|
* space at identity. |
| 180 |
|
|
* |
| 181 |
|
|
* @details This Jacobian corresponds to the Jacobian of \f$ \mathbf{q} \oplus (\mathbf{v} + |
| 182 |
|
|
* \delta \mathbf{v}) \f$ with \f$ \delta \mathbf{v} \rightarrow 0 \f$. |
| 183 |
|
|
* |
| 184 |
|
|
* @param[in] q configuration vector. |
| 185 |
|
|
* @param[in] v tangent vector. |
| 186 |
|
|
* @param[in] op assignment operator (SETTO, ADDTO or RMTO). |
| 187 |
|
|
* |
| 188 |
|
|
* @param[out] J the Jacobian of the Integrate operation w.r.t. the tangent vector v. |
| 189 |
|
|
*/ |
| 190 |
|
|
template<class Config_t, class Tangent_t, class JacobianOut_t> |
| 191 |
|
|
void dIntegrate_dv( |
| 192 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 193 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 194 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & J, |
| 195 |
|
|
const AssignmentOperatorType op = SETTO) const; |
| 196 |
|
|
|
| 197 |
|
|
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t> |
| 198 |
|
|
void dIntegrate_dv( |
| 199 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 200 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 201 |
|
|
int self, |
| 202 |
|
|
const Eigen::MatrixBase<JacobianIn_t> & Jin, |
| 203 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & Jout, |
| 204 |
|
|
const AssignmentOperatorType op = SETTO) const; |
| 205 |
|
|
|
| 206 |
|
|
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t> |
| 207 |
|
|
void dIntegrate_dv( |
| 208 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 209 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 210 |
|
|
const Eigen::MatrixBase<JacobianIn_t> & Jin, |
| 211 |
|
|
int self, |
| 212 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & Jout, |
| 213 |
|
|
const AssignmentOperatorType op = SETTO) const; |
| 214 |
|
|
|
| 215 |
|
|
/** |
| 216 |
|
|
* |
| 217 |
|
|
* @brief Transport a matrix from the terminal to the initial tangent space of the integrate |
| 218 |
|
|
* operation, with respect to the configuration or the velocity arguments. |
| 219 |
|
|
* |
| 220 |
|
|
* @details This function performs the parallel transportation of an input matrix whose columns |
| 221 |
|
|
* are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the |
| 222 |
|
|
* tangent space at \f$ q \f$. In other words, this functions transforms a tangent vector |
| 223 |
|
|
* expressed at \f$ q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that |
| 224 |
|
|
* the change of configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of |
| 225 |
|
|
* this tangent vector. A typical example of parallel transportation is the action operated by a |
| 226 |
|
|
* rigid transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in |
| 227 |
|
|
* \text{se}(3)\f$. In the context of configuration spaces assimilated to vector spaces, this |
| 228 |
|
|
* operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector |
| 229 |
|
|
* field transportation. |
| 230 |
|
|
* |
| 231 |
|
|
* @param[in] q configuration vector. |
| 232 |
|
|
* @param[in] v tangent vector |
| 233 |
|
|
* @param[in] Jin the input matrix |
| 234 |
|
|
* @param[in] arg argument with respect to which the differentiation is performed (ARG0 |
| 235 |
|
|
* corresponding to q, and ARG1 to v) |
| 236 |
|
|
* |
| 237 |
|
|
* @param[out] Jout Transported matrix |
| 238 |
|
|
* |
| 239 |
|
|
*/ |
| 240 |
|
|
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t> |
| 241 |
|
|
void dIntegrateTransport( |
| 242 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 243 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 244 |
|
|
const Eigen::MatrixBase<JacobianIn_t> & Jin, |
| 245 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & Jout, |
| 246 |
|
|
const ArgumentPosition arg) const; |
| 247 |
|
|
|
| 248 |
|
|
/** |
| 249 |
|
|
* |
| 250 |
|
|
* @brief Transport a matrix from the terminal to the initial tangent space of the integrate |
| 251 |
|
|
* operation, with respect to the configuration argument. |
| 252 |
|
|
* |
| 253 |
|
|
* @details This function performs the parallel transportation of an input matrix whose columns |
| 254 |
|
|
* are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the |
| 255 |
|
|
* tangent space at \f$ q \f$. In other words, this functions transforms a tangent vector |
| 256 |
|
|
* expressed at \f$ q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that |
| 257 |
|
|
* the change of configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of |
| 258 |
|
|
* this tangent vector. A typical example of parallel transportation is the action operated by a |
| 259 |
|
|
* rigid transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in |
| 260 |
|
|
* \text{se}(3)\f$. In the context of configuration spaces assimilated to vector spaces, this |
| 261 |
|
|
* operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector |
| 262 |
|
|
* field transportation. |
| 263 |
|
|
* |
| 264 |
|
|
* @param[in] q configuration vector. |
| 265 |
|
|
* @param[in] v tangent vector |
| 266 |
|
|
* @param[in] Jin the input matrix |
| 267 |
|
|
* |
| 268 |
|
|
* @param[out] Jout Transported matrix |
| 269 |
|
|
*/ |
| 270 |
|
|
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t> |
| 271 |
|
|
void dIntegrateTransport_dq( |
| 272 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 273 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 274 |
|
|
const Eigen::MatrixBase<JacobianIn_t> & Jin, |
| 275 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & Jout) const; |
| 276 |
|
|
/** |
| 277 |
|
|
* |
| 278 |
|
|
* @brief Transport a matrix from the terminal to the initial tangent space of the integrate |
| 279 |
|
|
* operation, with respect to the velocity argument. |
| 280 |
|
|
* |
| 281 |
|
|
* @details This function performs the parallel transportation of an input matrix whose columns |
| 282 |
|
|
* are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the |
| 283 |
|
|
* tangent space at \f$ q \f$. In other words, this functions transforms a tangent vector |
| 284 |
|
|
* expressed at \f$ q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that |
| 285 |
|
|
* the change of configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of |
| 286 |
|
|
* this tangent vector. A typical example of parallel transportation is the action operated by a |
| 287 |
|
|
* rigid transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in |
| 288 |
|
|
* \text{se}(3)\f$. In the context of configuration spaces assimilated to vector spaces, this |
| 289 |
|
|
* operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector |
| 290 |
|
|
* field transportation. |
| 291 |
|
|
* |
| 292 |
|
|
* @param[in] q configuration vector. |
| 293 |
|
|
* @param[in] v tangent vector |
| 294 |
|
|
* @param[in] Jin the input matrix |
| 295 |
|
|
* |
| 296 |
|
|
* @param[out] Jout Transported matrix |
| 297 |
|
|
*/ |
| 298 |
|
|
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t> |
| 299 |
|
|
void dIntegrateTransport_dv( |
| 300 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 301 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 302 |
|
|
const Eigen::MatrixBase<JacobianIn_t> & Jin, |
| 303 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & Jout) const; |
| 304 |
|
|
|
| 305 |
|
|
/** |
| 306 |
|
|
* |
| 307 |
|
|
* @brief Transport in place a matrix from the terminal to the initial tangent space of the |
| 308 |
|
|
* integrate operation, with respect to the configuration or the velocity arguments. |
| 309 |
|
|
* |
| 310 |
|
|
* @details This function performs the parallel transportation of an input matrix whose columns |
| 311 |
|
|
* are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the |
| 312 |
|
|
* tangent space at \f$ q \f$. In other words, this functions transforms a tangent vector |
| 313 |
|
|
* expressed at \f$ q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that |
| 314 |
|
|
* the change of configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of |
| 315 |
|
|
* this tangent vector. A typical example of parallel transportation is the action operated by a |
| 316 |
|
|
* rigid transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in |
| 317 |
|
|
* \text{se}(3)\f$. In the context of configuration spaces assimilated to vector spaces, this |
| 318 |
|
|
* operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector |
| 319 |
|
|
* field transportation. |
| 320 |
|
|
* |
| 321 |
|
|
* @param[in] q configuration vector. |
| 322 |
|
|
* @param[in] v tangent vector |
| 323 |
|
|
* @param[in,out] J the inplace matrix |
| 324 |
|
|
* @param[in] arg argument with respect to which the differentiation is performed (ARG0 |
| 325 |
|
|
* corresponding to q, and ARG1 to v) |
| 326 |
|
|
*/ |
| 327 |
|
|
template<class Config_t, class Tangent_t, class Jacobian_t> |
| 328 |
|
|
void dIntegrateTransport( |
| 329 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 330 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 331 |
|
|
const Eigen::MatrixBase<Jacobian_t> & J, |
| 332 |
|
|
const ArgumentPosition arg) const; |
| 333 |
|
|
|
| 334 |
|
|
/** |
| 335 |
|
|
* |
| 336 |
|
|
* @brief Transport in place a matrix from the terminal to the initial tangent space of the |
| 337 |
|
|
* integrate operation, with respect to the configuration argument. |
| 338 |
|
|
* |
| 339 |
|
|
* @details This function performs the parallel transportation of an input matrix whose columns |
| 340 |
|
|
* are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the |
| 341 |
|
|
* tangent space at \f$ q \f$. In other words, this functions transforms a tangent vector |
| 342 |
|
|
* expressed at \f$ q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that |
| 343 |
|
|
* the change of configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of |
| 344 |
|
|
* this tangent vector. A typical example of parallel transportation is the action operated by a |
| 345 |
|
|
* rigid transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in |
| 346 |
|
|
* \text{se}(3)\f$. In the context of configuration spaces assimilated to vector spaces, this |
| 347 |
|
|
* operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector |
| 348 |
|
|
* field transportation. |
| 349 |
|
|
* |
| 350 |
|
|
* @param[in] q configuration vector. |
| 351 |
|
|
* @param[in] v tangent vector |
| 352 |
|
|
* @param[in,out] Jin the inplace matrix |
| 353 |
|
|
* |
| 354 |
|
|
*/ |
| 355 |
|
|
template<class Config_t, class Tangent_t, class Jacobian_t> |
| 356 |
|
|
void dIntegrateTransport_dq( |
| 357 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 358 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 359 |
|
|
const Eigen::MatrixBase<Jacobian_t> & J) const; |
| 360 |
|
|
/** |
| 361 |
|
|
* |
| 362 |
|
|
* @brief Transport in place a matrix from the terminal to the initial tangent space of the |
| 363 |
|
|
* integrate operation, with respect to the velocity argument. |
| 364 |
|
|
* |
| 365 |
|
|
* @details This function performs the parallel transportation of an input matrix whose columns |
| 366 |
|
|
* are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the |
| 367 |
|
|
* tangent space at \f$ q \f$. In other words, this functions transforms a tangent vector |
| 368 |
|
|
* expressed at \f$ q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that |
| 369 |
|
|
* the change of configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of |
| 370 |
|
|
* this tangent vector. A typical example of parallel transportation is the action operated by a |
| 371 |
|
|
* rigid transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in |
| 372 |
|
|
* \text{se}(3)\f$. In the context of configuration spaces assimilated to vector spaces, this |
| 373 |
|
|
* operation corresponds to Identity. For Lie groups, its corresponds to the canonical vector |
| 374 |
|
|
* field transportation. |
| 375 |
|
|
* |
| 376 |
|
|
* @param[in] q configuration vector. |
| 377 |
|
|
* @param[in] v tangent vector |
| 378 |
|
|
* @param[in,out] J the inplace matrix |
| 379 |
|
|
* |
| 380 |
|
|
*/ |
| 381 |
|
|
template<class Config_t, class Tangent_t, class Jacobian_t> |
| 382 |
|
|
void dIntegrateTransport_dv( |
| 383 |
|
|
const Eigen::MatrixBase<Config_t> & q, |
| 384 |
|
|
const Eigen::MatrixBase<Tangent_t> & v, |
| 385 |
|
|
const Eigen::MatrixBase<Jacobian_t> & J) const; |
| 386 |
|
|
|
| 387 |
|
|
/** |
| 388 |
|
|
* @brief Interpolation between two joint's configurations |
| 389 |
|
|
* |
| 390 |
|
|
* @param[in] q0 the initial configuration to interpolate. |
| 391 |
|
|
* @param[in] q1 the final configuration to interpolate. |
| 392 |
|
|
* @param[in] u in [0;1] the absicca along the interpolation. |
| 393 |
|
|
* |
| 394 |
|
|
* @param[out] qout the interpolated configuration (q0 if u = 0, q1 if u = 1) |
| 395 |
|
|
*/ |
| 396 |
|
|
template<class ConfigL_t, class ConfigR_t, class ConfigOut_t> |
| 397 |
|
|
void interpolate( |
| 398 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 399 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 400 |
|
|
const Scalar & u, |
| 401 |
|
|
const Eigen::MatrixBase<ConfigOut_t> & qout) const; |
| 402 |
|
|
|
| 403 |
|
|
/** |
| 404 |
|
|
* @brief Normalize the joint configuration given as input. |
| 405 |
|
|
* For instance, the quaternion must be unitary. |
| 406 |
|
|
* |
| 407 |
|
|
* @note If the input vector is too small (i.e., qout.norm()==0), then it is left |
| 408 |
|
|
* unchanged. It is therefore possible that after this method is called `isNormalized(qout)` is |
| 409 |
|
|
* still false. |
| 410 |
|
|
* |
| 411 |
|
|
* @param[in,out] qout the normalized joint configuration. |
| 412 |
|
|
*/ |
| 413 |
|
|
template<class Config_t> |
| 414 |
|
|
void normalize(const Eigen::MatrixBase<Config_t> & qout) const; |
| 415 |
|
|
|
| 416 |
|
|
/** |
| 417 |
|
|
* @brief Check whether the input joint configuration is normalized. |
| 418 |
|
|
* For instance, the quaternion must be unitary. |
| 419 |
|
|
* |
| 420 |
|
|
* @param[in] qin The joint configuration to check. |
| 421 |
|
|
* |
| 422 |
|
|
* @return true if the input vector is normalized, false otherwise. |
| 423 |
|
|
*/ |
| 424 |
|
|
template<class Config_t> |
| 425 |
|
|
bool isNormalized( |
| 426 |
|
|
const Eigen::MatrixBase<Config_t> & qin, |
| 427 |
|
|
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const; |
| 428 |
|
|
|
| 429 |
|
|
/** |
| 430 |
|
|
* @brief Generate a random joint configuration, normalizing quaternions when necessary. |
| 431 |
|
|
* |
| 432 |
|
|
* \warning Do not take into account the joint limits. To shoot a configuration uniformingly |
| 433 |
|
|
* depending on joint limits, see randomConfiguration. |
| 434 |
|
|
* |
| 435 |
|
|
* @param[out] qout the random joint configuration. |
| 436 |
|
|
*/ |
| 437 |
|
|
template<class Config_t> |
| 438 |
|
|
void random(const Eigen::MatrixBase<Config_t> & qout) const; |
| 439 |
|
|
|
| 440 |
|
|
/** |
| 441 |
|
|
* @brief Generate a configuration vector uniformly sampled among |
| 442 |
|
|
* provided limits. |
| 443 |
|
|
* |
| 444 |
|
|
* @param[in] lower_pos_limit the lower joint limit vector. |
| 445 |
|
|
* @param[in] upper_pos_limit the upper joint limit vector. |
| 446 |
|
|
* |
| 447 |
|
|
* @param[out] qout the random joint configuration in the two bounds. |
| 448 |
|
|
*/ |
| 449 |
|
|
template<class ConfigL_t, class ConfigR_t, class ConfigOut_t> |
| 450 |
|
|
void randomConfiguration( |
| 451 |
|
|
const Eigen::MatrixBase<ConfigL_t> & lower_pos_limit, |
| 452 |
|
|
const Eigen::MatrixBase<ConfigR_t> & upper_pos_limit, |
| 453 |
|
|
const Eigen::MatrixBase<ConfigOut_t> & qout) const; |
| 454 |
|
|
|
| 455 |
|
|
/** |
| 456 |
|
|
* @brief Computes the tangent vector that must be integrated during one unit time to go |
| 457 |
|
|
* from q0 to q1. |
| 458 |
|
|
* |
| 459 |
|
|
* @param[in] q0 the initial configuration vector. |
| 460 |
|
|
* @param[in] q1 the terminal configuration vector. |
| 461 |
|
|
* |
| 462 |
|
|
* @param[out] v the corresponding velocity. |
| 463 |
|
|
* |
| 464 |
|
|
* @note Both inputs must be well-formed configuration vectors. The output of this |
| 465 |
|
|
* function is unspecified if inputs contain NaNs or extremal values for the underlying scalar |
| 466 |
|
|
* type. |
| 467 |
|
|
* |
| 468 |
|
|
* \cheatsheet \f$ q_1 \ominus q_0 = - \left( q_0 \ominus q_1 \right) \f$ |
| 469 |
|
|
*/ |
| 470 |
|
|
template<class ConfigL_t, class ConfigR_t, class Tangent_t> |
| 471 |
|
|
void difference( |
| 472 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 473 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 474 |
|
|
const Eigen::MatrixBase<Tangent_t> & v) const; |
| 475 |
|
|
|
| 476 |
|
|
/** |
| 477 |
|
|
* |
| 478 |
|
|
* @brief Computes the Jacobian of the difference operation with respect to q0 or q1. |
| 479 |
|
|
* |
| 480 |
|
|
* @tparam arg ARG0 (resp. ARG1) to get the Jacobian with respect to q0 (resp. q1). |
| 481 |
|
|
* |
| 482 |
|
|
* @param[in] q0 the initial configuration vector. |
| 483 |
|
|
* @param[in] q1 the terminal configuration vector. |
| 484 |
|
|
* |
| 485 |
|
|
* @param[out] J the Jacobian of the difference operation. |
| 486 |
|
|
* |
| 487 |
|
|
* \warning because \f$ q_1 \ominus q_0 = - \left( q_0 \ominus q_1 \right) \f$, |
| 488 |
|
|
* you may be tempted to write |
| 489 |
|
|
* \f$ \frac{\partial\ominus}{\partial q_1} = - \frac{\partial\ominus}{\partial q_0} \f$. |
| 490 |
|
|
* This is **false** in the general case because |
| 491 |
|
|
* \f$ \frac{\partial\ominus}{\partial q_i} \f$ expects an input velocity relative to frame i. |
| 492 |
|
|
* See SpecialEuclideanOperationTpl<3,_Scalar,_Options>::dDifference_impl. |
| 493 |
|
|
* |
| 494 |
|
|
* \cheatsheet \f$ \frac{\partial\ominus}{\partial q_1} \frac{\partial\oplus}{\partial v} = I |
| 495 |
|
|
* \f$ |
| 496 |
|
|
*/ |
| 497 |
|
|
template<ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianOut_t> |
| 498 |
|
|
void dDifference( |
| 499 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 500 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 501 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & J) const; |
| 502 |
|
|
|
| 503 |
|
|
/** |
| 504 |
|
|
* |
| 505 |
|
|
* @brief Computes the Jacobian of the difference operation with respect to q0 or q1. |
| 506 |
|
|
* |
| 507 |
|
|
* @param[in] q0 the initial configuration vector. |
| 508 |
|
|
* @param[in] q1 the terminal configuration vector. |
| 509 |
|
|
* @param[in] arg ARG0 (resp. ARG1) to get the Jacobian with respect to q0 (resp. q1). |
| 510 |
|
|
* |
| 511 |
|
|
* @param[out] J the Jacobian of the difference operation. |
| 512 |
|
|
* |
| 513 |
|
|
*/ |
| 514 |
|
|
template<class ConfigL_t, class ConfigR_t, class JacobianOut_t> |
| 515 |
|
|
void dDifference( |
| 516 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 517 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 518 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & J, |
| 519 |
|
|
const ArgumentPosition arg) const; |
| 520 |
|
|
|
| 521 |
|
|
template< |
| 522 |
|
|
ArgumentPosition arg, |
| 523 |
|
|
class ConfigL_t, |
| 524 |
|
|
class ConfigR_t, |
| 525 |
|
|
class JacobianIn_t, |
| 526 |
|
|
class JacobianOut_t> |
| 527 |
|
|
void dDifference( |
| 528 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 529 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 530 |
|
|
const Eigen::MatrixBase<JacobianIn_t> & Jin, |
| 531 |
|
|
int self, |
| 532 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & Jout, |
| 533 |
|
|
const AssignmentOperatorType op = SETTO) const; |
| 534 |
|
|
|
| 535 |
|
|
template< |
| 536 |
|
|
ArgumentPosition arg, |
| 537 |
|
|
class ConfigL_t, |
| 538 |
|
|
class ConfigR_t, |
| 539 |
|
|
class JacobianIn_t, |
| 540 |
|
|
class JacobianOut_t> |
| 541 |
|
|
void dDifference( |
| 542 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 543 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 544 |
|
|
int self, |
| 545 |
|
|
const Eigen::MatrixBase<JacobianIn_t> & Jin, |
| 546 |
|
|
const Eigen::MatrixBase<JacobianOut_t> & Jout, |
| 547 |
|
|
const AssignmentOperatorType op = SETTO) const; |
| 548 |
|
|
|
| 549 |
|
|
/** |
| 550 |
|
|
* @brief Squared distance between two joint configurations. |
| 551 |
|
|
* |
| 552 |
|
|
* @param[in] q0 the initial configuration vector. |
| 553 |
|
|
* @param[in] q1 the terminal configuration vector. |
| 554 |
|
|
* |
| 555 |
|
|
* @param[out] d the corresponding distance betwenn q0 and q1. |
| 556 |
|
|
*/ |
| 557 |
|
|
template<class ConfigL_t, class ConfigR_t> |
| 558 |
|
|
Scalar squaredDistance( |
| 559 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, const Eigen::MatrixBase<ConfigR_t> & q1) const; |
| 560 |
|
|
|
| 561 |
|
|
/** |
| 562 |
|
|
* @brief Distance between two configurations of the joint |
| 563 |
|
|
* |
| 564 |
|
|
* @param[in] q0 the initial configuration vector. |
| 565 |
|
|
* @param[in] q1 the terminal configuration vector. |
| 566 |
|
|
* |
| 567 |
|
|
* @return The corresponding distance. |
| 568 |
|
|
*/ |
| 569 |
|
|
template<class ConfigL_t, class ConfigR_t> |
| 570 |
|
|
Scalar distance( |
| 571 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, const Eigen::MatrixBase<ConfigR_t> & q1) const; |
| 572 |
|
|
|
| 573 |
|
|
/** |
| 574 |
|
|
* @brief Check if two configurations are equivalent within the given precision. |
| 575 |
|
|
* |
| 576 |
|
|
* @param[in] q0 Configuration 0 |
| 577 |
|
|
* @param[in] q1 Configuration 1 |
| 578 |
|
|
* |
| 579 |
|
|
* \cheatsheet \f$ q_1 \equiv q_0 \oplus \left( q_1 \ominus q_0 \right) \f$ (\f$\equiv\f$ means |
| 580 |
|
|
* equivalent, not equal). |
| 581 |
|
|
*/ |
| 582 |
|
|
template<class ConfigL_t, class ConfigR_t> |
| 583 |
|
|
bool isSameConfiguration( |
| 584 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 585 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 586 |
|
|
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const; |
| 587 |
|
|
|
| 588 |
|
38 |
bool operator==(const LieGroupBase & other) const |
| 589 |
|
|
{ |
| 590 |
|
38 |
return derived().isEqual_impl(other.derived()); |
| 591 |
|
|
} |
| 592 |
|
|
|
| 593 |
|
|
bool operator!=(const LieGroupBase & other) const |
| 594 |
|
|
{ |
| 595 |
|
|
return derived().isDifferent_impl(other.derived()); |
| 596 |
|
|
} |
| 597 |
|
|
/// \} |
| 598 |
|
|
|
| 599 |
|
|
/// \name API that allocates memory |
| 600 |
|
|
/// \{ |
| 601 |
|
|
|
| 602 |
|
|
template<class Config_t, class Tangent_t> |
| 603 |
|
|
ConfigVector_t |
| 604 |
|
|
integrate(const Eigen::MatrixBase<Config_t> & q, const Eigen::MatrixBase<Tangent_t> & v) const; |
| 605 |
|
|
|
| 606 |
|
|
template<class ConfigL_t, class ConfigR_t> |
| 607 |
|
|
ConfigVector_t interpolate( |
| 608 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 609 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 610 |
|
|
const Scalar & u) const; |
| 611 |
|
|
|
| 612 |
|
|
ConfigVector_t random() const; |
| 613 |
|
|
|
| 614 |
|
|
template<class ConfigL_t, class ConfigR_t> |
| 615 |
|
|
ConfigVector_t randomConfiguration( |
| 616 |
|
|
const Eigen::MatrixBase<ConfigL_t> & lower_pos_limit, |
| 617 |
|
|
const Eigen::MatrixBase<ConfigR_t> & upper_pos_limit) const; |
| 618 |
|
|
|
| 619 |
|
|
template<class ConfigL_t, class ConfigR_t> |
| 620 |
|
|
TangentVector_t difference( |
| 621 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, const Eigen::MatrixBase<ConfigR_t> & q1) const; |
| 622 |
|
|
/// \} |
| 623 |
|
|
|
| 624 |
|
|
/// \name Default implementations |
| 625 |
|
|
/// \{ |
| 626 |
|
|
|
| 627 |
|
|
template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t> |
| 628 |
|
|
void dIntegrate_product_impl( |
| 629 |
|
|
const Config_t & q, |
| 630 |
|
|
const Tangent_t & v, |
| 631 |
|
|
const JacobianIn_t & Jin, |
| 632 |
|
|
JacobianOut_t & Jout, |
| 633 |
|
|
bool dIntegrateOnTheLeft, |
| 634 |
|
|
const ArgumentPosition arg, |
| 635 |
|
|
const AssignmentOperatorType op) const; |
| 636 |
|
|
|
| 637 |
|
|
template< |
| 638 |
|
|
ArgumentPosition arg, |
| 639 |
|
|
class ConfigL_t, |
| 640 |
|
|
class ConfigR_t, |
| 641 |
|
|
class JacobianIn_t, |
| 642 |
|
|
class JacobianOut_t> |
| 643 |
|
|
void dDifference_product_impl( |
| 644 |
|
|
const ConfigL_t & q0, |
| 645 |
|
|
const ConfigR_t & q1, |
| 646 |
|
|
const JacobianIn_t & Jin, |
| 647 |
|
|
JacobianOut_t & Jout, |
| 648 |
|
|
bool dDifferenceOnTheLeft, |
| 649 |
|
|
const AssignmentOperatorType op) const; |
| 650 |
|
|
|
| 651 |
|
|
template<class ConfigL_t, class ConfigR_t, class ConfigOut_t> |
| 652 |
|
|
void interpolate_impl( |
| 653 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 654 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 655 |
|
|
const Scalar & u, |
| 656 |
|
|
const Eigen::MatrixBase<ConfigOut_t> & qout) const; |
| 657 |
|
|
|
| 658 |
|
|
template<class Config_t> |
| 659 |
|
|
void normalize_impl(const Eigen::MatrixBase<Config_t> & qout) const; |
| 660 |
|
|
|
| 661 |
|
|
template<class Config_t> |
| 662 |
|
|
bool isNormalized_impl( |
| 663 |
|
|
const Eigen::MatrixBase<Config_t> & qin, |
| 664 |
|
|
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const; |
| 665 |
|
|
|
| 666 |
|
|
template<class ConfigL_t, class ConfigR_t> |
| 667 |
|
|
Scalar squaredDistance_impl( |
| 668 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, const Eigen::MatrixBase<ConfigR_t> & q1) const; |
| 669 |
|
|
|
| 670 |
|
|
template<class ConfigL_t, class ConfigR_t> |
| 671 |
|
|
bool isSameConfiguration_impl( |
| 672 |
|
|
const Eigen::MatrixBase<ConfigL_t> & q0, |
| 673 |
|
|
const Eigen::MatrixBase<ConfigR_t> & q1, |
| 674 |
|
|
const Scalar & prec) const; |
| 675 |
|
|
|
| 676 |
|
|
/// \brief Default equality check. |
| 677 |
|
|
/// By default, two LieGroupBase of same type are considered equal. |
| 678 |
|
10 |
bool isEqual_impl(const LieGroupBase & /*other*/) const |
| 679 |
|
|
{ |
| 680 |
|
10 |
return true; |
| 681 |
|
|
} |
| 682 |
|
11 |
bool isDifferent_impl(const LieGroupBase & other) const |
| 683 |
|
|
{ |
| 684 |
|
11 |
return !derived().isEqual_impl(other.derived()); |
| 685 |
|
|
} |
| 686 |
|
|
|
| 687 |
|
|
/// Get dimension of Lie Group vector representation |
| 688 |
|
|
/// |
| 689 |
|
|
/// For instance, for SO(3), the dimension of the vector representation is |
| 690 |
|
|
/// 4 (quaternion) while the dimension of the tangent space is 3. |
| 691 |
|
|
Index nq() const; |
| 692 |
|
|
/// Get dimension of Lie Group tangent space |
| 693 |
|
|
Index nv() const; |
| 694 |
|
|
/// Get neutral element as a vector |
| 695 |
|
|
ConfigVector_t neutral() const; |
| 696 |
|
|
|
| 697 |
|
|
/// Get name of instance |
| 698 |
|
|
std::string name() const; |
| 699 |
|
|
|
| 700 |
|
|
Derived & derived() |
| 701 |
|
|
{ |
| 702 |
|
|
return static_cast<Derived &>(*this); |
| 703 |
|
|
} |
| 704 |
|
|
|
| 705 |
|
1698550 |
const Derived & derived() const |
| 706 |
|
|
{ |
| 707 |
|
1698550 |
return static_cast<const Derived &>(*this); |
| 708 |
|
|
} |
| 709 |
|
|
/// \} |
| 710 |
|
|
|
| 711 |
|
|
protected: |
| 712 |
|
|
/// Default constructor. |
| 713 |
|
|
/// |
| 714 |
|
|
/// Prevent the construction of derived class. |
| 715 |
|
1002153 |
LieGroupBase() |
| 716 |
|
|
{ |
| 717 |
|
1002153 |
} |
| 718 |
|
|
|
| 719 |
|
|
/// Copy constructor |
| 720 |
|
|
/// |
| 721 |
|
|
/// Prevent the copy of derived class. |
| 722 |
|
2412 |
LieGroupBase(const LieGroupBase & /*clone*/) |
| 723 |
|
|
{ |
| 724 |
|
2412 |
} |
| 725 |
|
|
|
| 726 |
|
|
/// Copy assignment operator |
| 727 |
|
|
/// |
| 728 |
|
|
/// Prevent the copy of derived class. |
| 729 |
|
✗ |
LieGroupBase & operator=(const LieGroupBase & /*other*/) |
| 730 |
|
|
{ |
| 731 |
|
✗ |
return *this; |
| 732 |
|
|
} |
| 733 |
|
|
|
| 734 |
|
|
// C++11 |
| 735 |
|
|
// LieGroupBase(const LieGroupBase &) = delete; |
| 736 |
|
|
// LieGroupBase& operator=(const LieGroupBase & /*x*/) = delete; |
| 737 |
|
|
}; // struct LieGroupBase |
| 738 |
|
|
|
| 739 |
|
|
} // namespace pinocchio |
| 740 |
|
|
|
| 741 |
|
|
#include "pinocchio/multibody/liegroup/liegroup-base.hxx" |
| 742 |
|
|
|
| 743 |
|
|
#endif // ifndef __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__ |
| 744 |
|
|
|