1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351
|
#ifndef _MANIF_PYTHON_BINDINGS_LIE_GROUP_BASE_H_
#define _MANIF_PYTHON_BINDINGS_LIE_GROUP_BASE_H_
template <typename _LieGroup, typename... _Args>
void wrap_lie_group_base(pybind11::class_<_LieGroup, _Args...>& py_class) {
using Scalar = typename _LieGroup::Scalar;
using Tangent = typename _LieGroup::Tangent;
using Vector = typename _LieGroup::Vector;
using DataType = typename _LieGroup::DataType;
using OptJacobianRef = typename _LieGroup::OptJacobianRef;
py_class.attr("Dim") = _LieGroup::Dim;
py_class.attr("DoF") = _LieGroup::DoF;
py_class.attr("RepSize") = _LieGroup::RepSize;
py_class.def(
pybind11::init<>(),
"Default constructor, uninitialized data."
);
py_class.def(
pybind11::init<const DataType&>(),
"Constructor given data vector."
);
py_class.def(
"coeffs_copy",
static_cast<DataType& (_LieGroup::*)(void)>(&_LieGroup::coeffs),
"Return a copy of underlying data."
); // Makes a copy!
py_class.def(
"coeffs",
static_cast<DataType& (_LieGroup::*)(void)>(&_LieGroup::coeffs),
pybind11::return_value_policy::reference_internal,
"Get a reference to underlying data."
);
py_class.def(
"inverse",
&_LieGroup::inverse,
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
R"(
Return the inverse of the Lie group object.
See Eq. (3).
Parameters
----------
J_out_self [out] : numpy.ndarray
Jacobian of the inverse wrt self.
)"
);
py_class.def(
"log",
&_LieGroup::log,
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
R"(
Return the corresponding Lie algebra element in vector form.
Eq. (24).
Parameters
----------
J_out_self [out] : numpy.ndarray
Jacobian of the log wrt self.
)"
);
py_class.def(
"adj",
&_LieGroup::adj,
R"(
Return the Adjoint of the Lie group object self.
See Eq. (29).
)"
);
py_class.def(
"compose",
&_LieGroup::template compose<_LieGroup>,
pybind11::arg("other"),
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
pybind11::arg_v("J_out_other", OptJacobianRef(), "None"),
R"(
Return the composition of self and another object of the same Lie group.
See Eqs. (1,2,3,4).
Parameters
----------
other : Lie group
Another object of the same Lie group.
J_out_self [out] : numpy.ndarray
Jacobian of the composition wrt self.
J_out_other [out] : numpy.ndarray
Jacobian of the composition wrt other.
)"
);
py_class.def(
"between",
&_LieGroup::template between<_LieGroup>,
pybind11::arg("other"),
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
pybind11::arg_v("J_out_other", OptJacobianRef(), "None"),
R"(
Return the between of self and another object of the same Lie group.
Parameters
----------
other : Lie group
Another object of the same Lie group.
J_out_self [out] : numpy.ndarray
Jacobian of the composition wrt self.
J_out_other [out] : numpy.ndarray
Jacobian of the composition wrt other.
)"
);
// That pops some nasty compilation errors.
// py_class.def(
// "act",
// &_LieGroup::template act<Vector>,
// pybind11::arg("v"),
// pybind11::arg_v(
// "J_vout_m",
// tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, _LieGroup::Dim, _LieGroup::DoF>>>(),
// "None"
// ),
// pybind11::arg_v(
// "J_vout_v",
// tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, _LieGroup::Dim, _LieGroup::Dim>>>(),
// "None"
// )
// );
py_class.def(
"act",
[](
const _LieGroup& self,
const Vector& v,
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, _LieGroup::Dim, _LieGroup::DoF>>> Ja,
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, _LieGroup::Dim, _LieGroup::Dim>>> Jb) {
return self.act(v, Ja, Jb);
},
pybind11::arg("p"),
pybind11::arg_v(
"J_out_self",
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, _LieGroup::Dim, _LieGroup::DoF>>>(),
"None"
),
pybind11::arg_v(
"J_out_p",
tl::optional<Eigen::Ref<Eigen::Matrix<Scalar, _LieGroup::Dim, _LieGroup::Dim>>>(),
"None"
),
R"(
Get the action of the Lie group object on a point.
Parameters
----------
p : numpy.array
A point.
J_out_self [out] : numpy.ndarray
Jacobian of the new object wrt self.
J_out_p [out] : numpy.ndarray
Jacobian of the new object wrt input point.
)"
);
py_class.def(
"isApprox",
&_LieGroup::template isApprox<_LieGroup>,
pybind11::arg("other"),
pybind11::arg_v("eps", Scalar(manif::Constants<Scalar>::eps), "1e-10"),
R"(
Evaluate whether self and other are 'close'.
Parameters
----------
other : Lie group
Another object of the same Lie group.
eps : double
Threshold for equality comparison. Default: 1e-10.
)"
);
py_class.def(
"rplus",
&_LieGroup::template rplus<Tangent>,
pybind11::arg("tau"),
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
pybind11::arg_v("J_out_tau", OptJacobianRef(), "None" ),
R"(
Right oplus operation of the Lie group.
See Eq. (25).
Parameters
----------
tau : Lie group tangent
An element of the tangent of the Lie group.
J_out_self [out] : numpy.ndarray
Jacobian of the oplus operation wrt self.
J_out_tau [out] : numpy.ndarray
Jacobian of the oplus operation wrt tau.
)"
);
py_class.def(
"lplus",
&_LieGroup::template lplus<Tangent>,
pybind11::arg("tau"),
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
pybind11::arg_v("J_mout_tau", OptJacobianRef(), "None"),
R"(
Left oplus operation of the Lie group.
See Eq. (27).
Parameters
----------
tau : Lie group tangent
An element of the tangent of the Lie group.
J_out_self [out] : numpy.ndarray
Jacobian of the oplus operation wrt self.
J_out_tau [out] : numpy.ndarray
Jacobian of the oplus operation wrt tau.
)"
);
py_class.def(
"plus",
&_LieGroup::template plus<Tangent>,
pybind11::arg("tau"),
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
pybind11::arg_v("J_mout_tau", OptJacobianRef(), "None"),
"An alias for the 'rplus' function."
);
py_class.def(
"rminus",
&_LieGroup::template rminus<_LieGroup>,
pybind11::arg("other"),
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
pybind11::arg_v("J_out_other", OptJacobianRef(), "None"),
R"(
Right ominus operation of the Lie group.
See Eq. (26).
Parameters
----------
other : Lie group
Another element of the same Lie group.
J_out_self [out] : numpy.ndarray
Jacobian of the ominus operation wrt self.
J_out_other [out] : numpy.ndarray
Jacobian of the ominus operation wrt other.
)"
);
py_class.def(
"lminus",
&_LieGroup::template lminus<_LieGroup>,
pybind11::arg("other"),
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
pybind11::arg_v("J_out_other", OptJacobianRef(), "None"),
R"(
Left ominus operation of the Lie group.
See Eq. (28).
Parameters
----------
other : Lie group
Another element of the same Lie group.
J_out_self [out] : numpy.ndarray
Jacobian of the ominus operation wrt self.
J_out_other [out] : numpy.ndarray
Jacobian of the ominus operation wrt other.
)"
);
py_class.def(
"minus",
&_LieGroup::template minus<_LieGroup>,
pybind11::arg("other"),
pybind11::arg_v("J_out_self", OptJacobianRef(), "None"),
pybind11::arg_v("J_out_other", OptJacobianRef(), "None"),
"An alias for the 'rminus' function."
);
py_class.def(
"setIdentity",
&_LieGroup::setIdentity,
"Set self to the Lie group Identity."
);
py_class.def(
"setRandom",
&_LieGroup::setRandom,
"Set self to a random value."
);
py_class.def_static(
"Identity",
&_LieGroup::Identity,
"Static helper to create an object set at the Lie group Identity."
);
py_class.def_static(
"Random",
&_LieGroup::Random,
"Static helper to create a random object of the Lie group."
);
py_class.def(
pybind11::self + Tangent(),
"Operator overload for the 'plus' function."
)
// .def(pybind11::self += Tangent())
.def(
pybind11::self - pybind11::self,
"Operator overload for the 'minus' function."
)
.def(
pybind11::self * pybind11::self,
"Operator overload for the 'compose' function."
)
// .def(pybind11::self *= pybind11::self)
.def(
pybind11::self == pybind11::self,
"Operator overload for the 'isApprox' function."
)
;
py_class.def(
"__str__",
[](const _LieGroup &o) {
std::ostringstream ss; ss << o;
return ss.str();
}
);
}
#endif // _MANIF_PYTHON_BINDINGS_LIE_GROUP_BASE_H_
|