From e8c375efafc0846d69ec1f85311389f8cb623671 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Thu, 22 Jun 2023 13:45:21 +0200 Subject: [PATCH] Update python wrapper and examples --- python-examples/ros-poses-convert.out | 32 +++++++++++++++++ python/ros_bridge.py | 17 +++++++++ python/src/mrpt/math/CMatrixDynamic.cpp | 14 +++++++- python/src/mrpt/math/CMatrixDynamic_1.cpp | 14 +++++++- python/src/mrpt/math/CMatrixFixed.cpp | 43 +++++++++++++++++++++-- python/src/mrpt/math/CMatrixFixed_1.cpp | 13 ++++++- python/src/mrpt/math/CMatrixFixed_2.cpp | 13 ++++++- python/src/mrpt/math/CMatrixFixed_3.cpp | 41 +++++++++++++++++++-- python/src/mrpt/math/CMatrixFixed_4.cpp | 13 ++++++- 9 files changed, 190 insertions(+), 10 deletions(-) create mode 100644 python-examples/ros-poses-convert.out diff --git a/python-examples/ros-poses-convert.out b/python-examples/ros-poses-convert.out new file mode 100644 index 0000000000..68abfb1aa5 --- /dev/null +++ b/python-examples/ros-poses-convert.out @@ -0,0 +1,32 @@ +mrpt p1 : (1.000,2.000,90.00deg) +ros p1 : geometry_msgs.msg.Pose(position=geometry_msgs.msg.Point(x=1.0, y=2.0, z=0.0), orientation=geometry_msgs.msg.Quaternion(x=0.0, y=0.0, z=0.7071067811865475, w=0.7071067811865476)) +mrpt p2 : (x,y,z,yaw,pitch,roll)=(1.0000,2.0000,0.0000,90.00deg,-0.00deg,0.00deg) + +ros r2 : geometry_msgs.msg.Pose(position=geometry_msgs.msg.Point(x=10.0, y=5.0, z=0.0), orientation=geometry_msgs.msg.Quaternion(x=0.0, y=0.0, z=0.0, w=1.0)) +mrpt mr2 : (x,y,z,yaw,pitch,roll)=(10.0000,5.0000,0.0000,0.00deg,-0.00deg,0.00deg) +mrpt mr2b : (x,y,z,qr,qx,qy,qz)=(10.0000,5.0000,0.0000,1.0000,0.0000,0.0000,0.0000) + +ros PDF r3 : geometry_msgs.msg.PoseWithCovariance(pose=geometry_msgs.msg.Pose(position=geometry_msgs.msg.Point(x=10.0, y=5.0, z=0.0), orientation=geometry_msgs.msg.Quaternion(x=0.0, y=0.0, z=0.0, w=1.0)), covariance=array([1., 0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0., 1., 0., 0., + 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., + 0., 1.])) +mrpt PDF mr3 : Mean: (x,y,z,yaw,pitch,roll)=(11.0000,5.0000,0.0000,0.00deg,-0.00deg,0.00deg) +Covariance: +1 0 0 0 0 0 +0 1 0 0 0 0 +0 0 1 0 0 0 +0 0 0 1 0 0 +0 0 0 0 1 0 +0 0 0 0 0 1 + +mrpt PDF mr3b : Mean: (x,y,z,yaw,pitch,roll)=(11.0000,5.0000,0.0000,0.00deg,-0.00deg,0.00deg) +Covariance: +1 0 0 0 0 0 +0 1 0 0 0 0 +0 0 1 0 0 0 +0 0 0 1 0 0 +0 0 0 0 1 0 +0 0 0 0 0 1 + +ros PDF r3b : geometry_msgs.msg.PoseWithCovariance(pose=geometry_msgs.msg.Pose(position=geometry_msgs.msg.Point(x=11.0, y=5.0, z=0.0), orientation=geometry_msgs.msg.Quaternion(x=0.0, y=0.0, z=0.0, w=1.0)), covariance=array([1., 0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0., 1., 0., 0., + 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., + 0., 1.])) diff --git a/python/ros_bridge.py b/python/ros_bridge.py index 9097d24c4b..644c1d5f10 100644 --- a/python/ros_bridge.py +++ b/python/ros_bridge.py @@ -97,3 +97,20 @@ def ROS_PoseWithCovariance_msg_to_CPose3DPDFGaussian(p: PoseWithCovariance) -> _ ret.cov[i, j] = p.covariance[ind_map[i] * 6 + ind_map[j]] return ret + + +def CPose3DPDFGaussian_to_ROS_PoseWithCovariance_msg(p: _mrpt.poses.CPose3DPDFGaussian) -> PoseWithCovariance: + """ + Converts from mrpt::poses::CPose3DPDFGaussian to ROS geometry_msgs.PoseWithCovariance + """ + # rearrange covariance (see notes above) + ind_map = [0, 1, 2, 5, 4, 3] # X,Y,Z,YAW,PITCH,ROLL + + ret = PoseWithCovariance() + ret.pose = CPose3D_to_ROS_Pose_msg(p.mean) + + for i in range(0, 6): + for j in range(0, 6): + ret.covariance[ind_map[i] * 6 + ind_map[j]] = p.cov[i, j] + + return ret diff --git a/python/src/mrpt/math/CMatrixDynamic.cpp b/python/src/mrpt/math/CMatrixDynamic.cpp index edd9586d44..1b600737aa 100644 --- a/python/src/mrpt/math/CMatrixDynamic.cpp +++ b/python/src/mrpt/math/CMatrixDynamic.cpp @@ -43,11 +43,23 @@ void bind_mrpt_math_CMatrixDynamic(std::function< pybind11::module &(std::string cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); cl.def("data", (float * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> float *", pybind11::return_value_policy::automatic); cl.def("__call__", (float & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__getitem__", (float & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("ith")); cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_float, "C++: mrpt::math::CMatrixDynamic::cast_float() const --> class mrpt::math::CMatrixDynamic"); cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_double, "C++: mrpt::math::CMatrixDynamic::cast_double() const --> class mrpt::math::CMatrixDynamic"); cl.def("llt_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::llt_solve, "C++: mrpt::math::CMatrixDynamic::llt_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); cl.def("lu_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::lu_solve, "C++: mrpt::math::CMatrixDynamic::lu_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); + + // Manually-added matrix methods: + using dat_t = float; + using mat_t = mrpt::math::CMatrixDynamic; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Identity", [](const size_t N) -> mat_t { return mat_t::Identity(N); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", [](const size_t nRows, const size_t nCols) -> mat_t { return mat_t::Zero(nRows,nCols); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixDynamic_unsigned_char_t", ""); diff --git a/python/src/mrpt/math/CMatrixDynamic_1.cpp b/python/src/mrpt/math/CMatrixDynamic_1.cpp index 7eae41c0ae..70f933be5c 100644 --- a/python/src/mrpt/math/CMatrixDynamic_1.cpp +++ b/python/src/mrpt/math/CMatrixDynamic_1.cpp @@ -128,11 +128,23 @@ void bind_mrpt_math_CMatrixDynamic_1(std::function< pybind11::module &(std::stri cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); cl.def("data", (double * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> double *", pybind11::return_value_policy::automatic); cl.def("__call__", (double & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("ith")); cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_float, "C++: mrpt::math::CMatrixDynamic::cast_float() const --> class mrpt::math::CMatrixDynamic"); cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_double, "C++: mrpt::math::CMatrixDynamic::cast_double() const --> class mrpt::math::CMatrixDynamic"); cl.def("llt_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::llt_solve, "C++: mrpt::math::CMatrixDynamic::llt_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); cl.def("lu_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::lu_solve, "C++: mrpt::math::CMatrixDynamic::lu_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); + + // Manually-added matrix methods: + using dat_t = double; + using mat_t = mrpt::math::CMatrixDynamic; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Identity", [](const size_t N) -> mat_t { return mat_t::Identity(N); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", [](const size_t nRows, const size_t nCols) -> mat_t { return mat_t::Zero(nRows,nCols); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, PyCallBack_mrpt_math_CMatrixD, mrpt::serialization::CSerializable, mrpt::math::CMatrixDynamic> cl(M("mrpt::math"), "CMatrixD", "This class is a \"CSerializable\" wrapper for\n \"CMatrixDynamic\".\n \n\n For a complete introduction to Matrices and vectors in MRPT, see:\n https://www.mrpt.org/Matrices_vectors_arrays_and_Linear_Algebra_MRPT_and_Eigen_classes\n \n\n\n "); diff --git a/python/src/mrpt/math/CMatrixFixed.cpp b/python/src/mrpt/math/CMatrixFixed.cpp index 342ed05695..877ac0cb49 100644 --- a/python/src/mrpt/math/CMatrixFixed.cpp +++ b/python/src/mrpt/math/CMatrixFixed.cpp @@ -66,10 +66,22 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = double; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_4UL_4UL_t", ""); @@ -93,10 +105,22 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = double; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_6UL_6UL_t", ""); @@ -120,8 +144,21 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = double; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = double; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_3UL_4UL_t", ""); diff --git a/python/src/mrpt/math/CMatrixFixed_2.cpp b/python/src/mrpt/math/CMatrixFixed_2.cpp index f8bc51568e..88d8935ca9 100644 --- a/python/src/mrpt/math/CMatrixFixed_2.cpp +++ b/python/src/mrpt/math/CMatrixFixed_2.cpp @@ -116,9 +116,20 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = double; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + + // Manually-added matrix methods: + using dat_t = float; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_float_4UL_4UL_t", ""); @@ -90,10 +102,22 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = float; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_float_3UL_1UL_t", ""); @@ -121,5 +145,18 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = float; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = float; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r(M("mrpt::math"), "TMatrixTextFileFormat", pybind11::arithmetic(), "Selection of the number format in MatrixVectorBase::saveToTextFile()\n \n")