Skip to content

Commit e6a1c65

Browse files
author
Maximilien Naveau
committed
[operators][fir_filter] fix some bug on the python bindings side
1 parent 7f5a93e commit e6a1c65

File tree

4 files changed

+34
-30
lines changed

4 files changed

+34
-30
lines changed

src/matrix/fir-filter.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ using dynamicgraph::Vector;
2323
\
2424
template <> \
2525
const std::string sotClassType<sotSigType, sotCoefType>::CLASS_NAME = \
26-
std::string(className) + "_" + #sotSigType + "," + #sotCoefType + "_"; \
26+
std::string(className) + "_" + #sotSigType + "_" + #sotCoefType; \
2727
\
2828
template <> \
2929
const std::string &sotClassType<sotSigType, sotCoefType>::getClassName(void) \

src/matrix/operator-python-module-py.cc

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -102,6 +102,10 @@ BOOST_PYTHON_MODULE(wrap)
102102
exposeUnaryOp < HomogeneousMatrixToVector> ();
103103
exposeUnaryOp < SkewSymToVector> ();
104104
exposeUnaryOp < PoseUThetaToMatrixHomo> ();
105+
exposeUnaryOp < HomogeneousMatrixToVector> ();
106+
exposeUnaryOp < HomogeneousMatrixToSE3Vector> ();
107+
exposeUnaryOp < SE3VectorToHomogeneousMatrix> ();
108+
exposeUnaryOp < PoseQuaternionToMatrixHomo> ();
105109
exposeUnaryOp < MatrixHomoToPoseQuaternion> ();
106110
exposeUnaryOp < MatrixHomoToPoseRollPitchYaw> ();
107111
exposeUnaryOp < PoseRollPitchYawToMatrixHomo> ();

src/matrix/operator.cpp

Lines changed: 0 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -58,40 +58,11 @@ REGISTER_UNARY_OP(InverserQuaternion, Inverse_of_unitquat);
5858
/* ----------------------------------------------------------------------- */
5959

6060
REGISTER_UNARY_OP(HomogeneousMatrixToVector, MatrixHomoToPoseUTheta);
61-
62-
struct HomogeneousMatrixToSE3Vector
63-
: public UnaryOpHeader<MatrixHomogeneous, dg::Vector> {
64-
void operator()(const MatrixHomogeneous &M, dg::Vector &res) {
65-
res.resize(12);
66-
res.head<3>() = M.translation();
67-
res.segment(3, 3) = M.linear().row(0);
68-
res.segment(6, 3) = M.linear().row(1);
69-
res.segment(9, 3) = M.linear().row(2);
70-
}
71-
};
7261
REGISTER_UNARY_OP(HomogeneousMatrixToSE3Vector, MatrixHomoToSE3Vector);
73-
74-
struct SE3VectorToHomogeneousMatrix
75-
: public UnaryOpHeader<dg::Vector, MatrixHomogeneous> {
76-
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres) {
77-
Mres.translation() = vect.head<3>();
78-
Mres.linear().row(0) = vect.segment(3, 3);
79-
Mres.linear().row(1) = vect.segment(6, 3);
80-
Mres.linear().row(2) = vect.segment(9, 3);
81-
}
82-
};
8362
REGISTER_UNARY_OP(SE3VectorToHomogeneousMatrix, SE3VectorToMatrixHomo);
8463
REGISTER_UNARY_OP(SkewSymToVector, SkewSymToVector);
8564
REGISTER_UNARY_OP(PoseUThetaToMatrixHomo, PoseUThetaToMatrixHomo);
8665
REGISTER_UNARY_OP(MatrixHomoToPoseQuaternion, MatrixHomoToPoseQuaternion);
87-
88-
struct PoseQuaternionToMatrixHomo
89-
: public UnaryOpHeader<Vector, MatrixHomogeneous> {
90-
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres) {
91-
Mres.translation() = vect.head<3>();
92-
Mres.linear() = VectorQuaternion(vect.tail<4>()).toRotationMatrix();
93-
}
94-
};
9566
REGISTER_UNARY_OP(PoseQuaternionToMatrixHomo, PoseQuatToMatrixHomo);
9667
REGISTER_UNARY_OP(MatrixHomoToPoseRollPitchYaw, MatrixHomoToPoseRollPitchYaw);
9768
REGISTER_UNARY_OP(PoseRollPitchYawToMatrixHomo, PoseRollPitchYawToMatrixHomo);

src/matrix/operator.hh

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -310,6 +310,35 @@ struct PoseUThetaToMatrixHomo
310310
}
311311
};
312312

313+
struct SE3VectorToHomogeneousMatrix
314+
: public UnaryOpHeader<dg::Vector, MatrixHomogeneous> {
315+
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres) {
316+
Mres.translation() = vect.head<3>();
317+
Mres.linear().row(0) = vect.segment(3, 3);
318+
Mres.linear().row(1) = vect.segment(6, 3);
319+
Mres.linear().row(2) = vect.segment(9, 3);
320+
}
321+
};
322+
323+
struct HomogeneousMatrixToSE3Vector
324+
: public UnaryOpHeader<MatrixHomogeneous, dg::Vector> {
325+
void operator()(const MatrixHomogeneous &M, dg::Vector &res) {
326+
res.resize(12);
327+
res.head<3>() = M.translation();
328+
res.segment(3, 3) = M.linear().row(0);
329+
res.segment(6, 3) = M.linear().row(1);
330+
res.segment(9, 3) = M.linear().row(2);
331+
}
332+
};
333+
334+
struct PoseQuaternionToMatrixHomo
335+
: public UnaryOpHeader<Vector, MatrixHomogeneous> {
336+
void operator()(const dg::Vector &vect, MatrixHomogeneous &Mres) {
337+
Mres.translation() = vect.head<3>();
338+
Mres.linear() = VectorQuaternion(vect.tail<4>()).toRotationMatrix();
339+
}
340+
};
341+
313342
struct MatrixHomoToPoseQuaternion
314343
: public UnaryOpHeader<MatrixHomogeneous, Vector> {
315344
inline void operator()(const MatrixHomogeneous &M, Vector &res) {

0 commit comments

Comments
 (0)