18 #include <Eigen/Cholesky>
26 for (
int i = 0;
i <
x.rows();
i++) {
27 for (
int j = 0;
j <
x.cols();
j++) {
28 x(
i,
j) = 11 + 10 *
i +
j;
35 static Eigen::MatrixXd *
x;
37 x =
new Eigen::MatrixXd(3, 3);
62 template <
typename MatrixArgType>
64 Eigen::MatrixXd
ret(
m);
65 for (
int c = 0;
c <
m.cols();
c++) {
66 for (
int r = 0; r <
m.rows(); r++) {
67 ret(r,
c) += 10 * r + 100 *
c;
76 Eigen::Matrix4d
a = Eigen::Matrix4d::Zero();
77 Eigen::Matrix4d
b = Eigen::Matrix4d::Identity();
95 m.def(
"double_col", [](
const Eigen::VectorXf &
x) -> Eigen::VectorXf {
return 2.0f *
x; });
97 [](
const Eigen::RowVectorXf &
x) -> Eigen::RowVectorXf {
return 2.0f *
x; });
98 m.def(
"double_complex",
99 [](
const Eigen::VectorXcf &
x) -> Eigen::VectorXcf {
return 2.0f *
x; });
100 m.def(
"double_threec", [](py::EigenDRef<Eigen::Vector3f>
x) {
x *= 2; });
101 m.def(
"double_threer", [](py::EigenDRef<Eigen::RowVector3f>
x) {
x *= 2; });
102 m.def(
"double_mat_cm", [](
const Eigen::MatrixXf &
x) -> Eigen::MatrixXf {
return 2.0f *
x; });
103 m.def(
"double_mat_rm", [](
const DenseMatrixR &
x) -> DenseMatrixR {
return 2.0f *
x; });
110 return x.llt().matrixL();
115 return x.llt().matrixL();
127 m.def(
"add_rm", add_rm);
128 m.def(
"add_cm", add_cm);
130 m.def(
"add1", add_rm);
131 m.def(
"add1", add_cm);
132 m.def(
"add2", add_cm);
133 m.def(
"add2", add_rm);
136 [](py::EigenDRef<Eigen::MatrixXd>
x,
int r,
int c,
double v) {
x(r,
c) +=
v; });
151 m += Eigen::MatrixXd::Constant(
m.rows(),
m.cols(),
v);
154 py::return_value_policy::reference);
159 [](py::EigenDRef<Eigen::MatrixXd>
m,
double v) {
160 m += Eigen::MatrixXd::Constant(
m.rows(),
m.cols(),
v);
163 py::return_value_policy::reference);
168 [](py::EigenDRef<Eigen::MatrixXd>
m) {
169 return py::EigenDMap<Eigen::MatrixXd>(
173 py::EigenDStride(
m.outerStride(), 2 *
m.innerStride()));
175 py::return_value_policy::reference);
180 [](py::EigenDRef<Eigen::MatrixXd>
m) {
181 return py::EigenDMap<Eigen::MatrixXd>(
185 py::EigenDStride(2 *
m.outerStride(),
m.innerStride()));
187 py::return_value_policy::reference);
198 [
m](
const py::object &x_obj,
203 return m.attr(
"_block")(x_obj, x_obj, start_row, start_col, block_rows, block_cols);
208 [](
const py::object &x_obj,
217 auto x0_orig = x_obj[*
i0].cast<
double>();
218 if (
x(0, 0) != x0_orig) {
219 throw std::runtime_error(
220 "Something in the type_caster for Eigen::Ref is terribly wrong.");
222 double x0_mod = x0_orig + 1;
224 auto copy_detected = (
x(0, 0) != x0_mod);
225 x_obj[*
i0] = x0_orig;
227 throw std::runtime_error(
"type_caster for Eigen::Ref made a copy.");
229 return x.block(start_row, start_col, block_rows, block_cols);
231 py::keep_alive<0, 1>());
241 static Eigen::MatrixXd
create() {
return Eigen::MatrixXd::Ones(10, 10); }
243 static const Eigen::MatrixXd createConst() {
return Eigen::MatrixXd::Ones(10, 10); }
244 Eigen::MatrixXd &
get() {
return mat; }
245 Eigen::MatrixXd *getPtr() {
return &
mat; }
246 const Eigen::MatrixXd &
view() {
return mat; }
247 const Eigen::MatrixXd *viewPtr() {
return &
mat; }
251 return mat.block(r,
c, nrow, ncol);
254 return mat.block(r,
c, nrow, ncol);
256 py::EigenDMap<Eigen::Matrix2d>
corners() {
257 return py::EigenDMap<Eigen::Matrix2d>(
259 py::EigenDStride(
mat.outerStride() * (
mat.outerSize() - 1),
260 mat.innerStride() * (
mat.innerSize() - 1)));
262 py::EigenDMap<const Eigen::Matrix2d> cornersConst()
const {
263 return py::EigenDMap<const Eigen::Matrix2d>(
265 py::EigenDStride(
mat.outerStride() * (
mat.outerSize() - 1),
266 mat.innerStride() * (
mat.innerSize() - 1)));
270 py::class_<ReturnTester>(
m,
"ReturnTester")
273 .def_static(
"create_const", &ReturnTester::createConst)
275 .def(
"get_ptr", &ReturnTester::getPtr, rvp::reference_internal)
281 .def(
"ref_const", &ReturnTester::refConst)
283 .def(
"ref_const_safe", &ReturnTester::refConst, rvp::reference_internal)
285 .def(
"copy_ref_const", &ReturnTester::refConst,
rvp::copy)
288 .def(
"block_const", &ReturnTester::blockConst, rvp::reference_internal)
291 .def(
"corners_const", &ReturnTester::cornersConst, rvp::reference_internal);
295 m.def(
"incr_diag", [](
int k) {
297 for (
int i = 0;
i < k;
i++) {
298 m.diagonal()[
i] =
i + 1;
304 m.def(
"symmetric_lower",
305 [](
const Eigen::MatrixXi &
m) {
return m.selfadjointView<
Eigen::Lower>(); });
307 m.def(
"symmetric_upper",
308 [](
const Eigen::MatrixXi &
m) {
return m.selfadjointView<
Eigen::Upper>(); });
311 Eigen::MatrixXf
mat(5, 6);
312 mat << 0, 3, 0, 0, 0, 11, 22, 0, 0, 0, 17, 11, 7, 5, 0, 1, 0, 11, 0, 0, 0, 0, 0, 11, 0, 0, 14,
316 m.def(
"fixed_r", [
mat]() -> FixedMatrixR {
return FixedMatrixR(
mat); });
320 m.def(
"fixed_r_const", [
mat]() ->
const FixedMatrixR {
return FixedMatrixR(
mat); });
321 m.def(
"fixed_c", [
mat]() -> FixedMatrixC {
return FixedMatrixC(
mat); });
322 m.def(
"fixed_copy_r", [](
const FixedMatrixR &
m) -> FixedMatrixR {
return m; });
323 m.def(
"fixed_copy_c", [](
const FixedMatrixC &
m) -> FixedMatrixC {
return m; });
327 m.def(
"fixed_mutator_a", [](
const py::EigenDRef<FixedMatrixC> &) {});
329 m.def(
"dense_r", [
mat]() -> DenseMatrixR {
return DenseMatrixR(
mat); });
330 m.def(
"dense_c", [
mat]() -> DenseMatrixC {
return DenseMatrixC(
mat); });
331 m.def(
"dense_copy_r", [](
const DenseMatrixR &
m) -> DenseMatrixR {
return m; });
332 m.def(
"dense_copy_c", [](
const DenseMatrixC &
m) -> DenseMatrixC {
return m; });
334 bool have_numpy =
true;
336 py::module_::import(
"numpy");
337 }
catch (
const py::error_already_set &) {
341 py::module_::import(
"numpy");
343 m.def(
"defaults_mat", [](
const Eigen::Matrix3d &) {},
py::arg(
"mat") = defaultMatrix);
345 Eigen::VectorXd defaultVector = Eigen::VectorXd::Ones(32);
346 m.def(
"defaults_vec", [](
const Eigen::VectorXd &) {},
py::arg(
"vec") = defaultMatrix);
349 m.def(
"sparse_r", [
mat]() -> SparseMatrixR {
355 m.def(
"sparse_copy_r", [](
const SparseMatrixR &
m) -> SparseMatrixR {
return m; });
356 m.def(
"sparse_copy_c", [](
const SparseMatrixC &
m) -> SparseMatrixC {
return m; });
358 m.def(
"partial_copy_four_rm_r", [](
const FourRowMatrixR &
m) -> FourRowMatrixR {
return m; });
359 m.def(
"partial_copy_four_rm_c", [](
const FourColMatrixR &
m) -> FourColMatrixR {
return m; });
360 m.def(
"partial_copy_four_cm_r", [](
const FourRowMatrixC &
m) -> FourRowMatrixC {
return m; });
361 m.def(
"partial_copy_four_cm_c", [](
const FourColMatrixC &
m) -> FourColMatrixC {
return m; });
365 m.def(
"cpp_copy", [](py::handle
m) {
return m.cast<Eigen::MatrixXd>()(1, 0); });
369 [](py::handle
m) {
return m.cast<py::EigenDRef<Eigen::MatrixXd>>()(1, 0); });
384 "get_elem_rm_nocopy",
408 m.def(
"iss1105_col", [](
const Eigen::VectorXd &) {
return true; });
409 m.def(
"iss1105_row", [](
const Eigen::RowVectorXd &) {
return true; });
415 [](
const py::EigenDRef<const Eigen::MatrixXd> &
A,
416 const py::EigenDRef<const Eigen::MatrixXd> &
B) -> Eigen::MatrixXd {
417 if (
A.cols() !=
B.rows()) {
418 throw std::domain_error(
"Nonconformable matrices!");
426 py::class_<CustomOperatorNew>(
m,
"CustomOperatorNew")
436 py::module_::import(
"numpy").attr(
"ones")(10);
440 py::module_::import(
"numpy").attr(
"ones")(10);