Skip to content

Commit

Permalink
Remove deprecated functions from python SWIG API (#344)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
Signed-off-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
chapulina committed Dec 29, 2021
1 parent 22d9aad commit 84837c2
Show file tree
Hide file tree
Showing 7 changed files with 118 additions and 113 deletions.
10 changes: 5 additions & 5 deletions src/python/Matrix3.i
Original file line number Diff line number Diff line change
Expand Up @@ -49,13 +49,13 @@ namespace ignition
public: void Set(T _v00, T _v01, T _v02,
T _v10, T _v11, T _v12,
T _v20, T _v21, T _v22);
public: void Axes(const Vector3<T> &_xAxis,
public: void SetAxes(const Vector3<T> &_xAxis,
const Vector3<T> &_yAxis,
const Vector3<T> &_zAxis);
public: void Axis(const Vector3<T> &_axis, T _angle);
%rename(from_2_axes) From2Axes;
public: void From2Axes(const Vector3<T> &_v1, const Vector3<T> &_v2);
public: void Col(unsigned int _c, const Vector3<T> &_v);
public: void SetFromAxisAngle(const Vector3<T> &_axis, T _angle);
%rename(set_from_2_axes) SetFrom2Axes;
public: void SetFrom2Axes(const Vector3<T> &_v1, const Vector3<T> &_v2);
public: void SetCol(unsigned int _c, const Vector3<T> &_v);
public: Matrix3<T> operator-(const Matrix3<T> &_m) const;
public: Matrix3<T> operator+(const Matrix3<T> &_m) const;
public: Matrix3<T> operator*(const T &_s) const;
Expand Down
26 changes: 13 additions & 13 deletions src/python/Matrix3_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,17 +32,17 @@ def test_matrix3d(self):
self.assertAlmostEqual(matrix1, Matrix3d(1, 2, 3, 4, 5, 6, 7, 8, 9))

matrix = Matrix3d()
matrix.axes(Vector3d(1, 1, 1), Vector3d(2, 2, 2),
matrix.set_axes(Vector3d(1, 1, 1), Vector3d(2, 2, 2),
Vector3d(3, 3, 3))
self.assertAlmostEqual(matrix, Matrix3d(1, 2, 3, 1, 2, 3, 1, 2, 3))

matrix.axis(Vector3d(1, 1, 1), math.pi)
matrix.set_from_axis_angle(Vector3d(1, 1, 1), math.pi)
self.assertAlmostEqual(matrix, Matrix3d(1, 2, 2, 2, 1, 2, 2, 2, 1))

matrix.col(0, Vector3d(3, 4, 5))
matrix.set_col(0, Vector3d(3, 4, 5))
self.assertAlmostEqual(matrix, Matrix3d(3, 2, 2, 4, 1, 2, 5, 2, 1))

matrix.col(3, Vector3d(1, 1, 1))
matrix.set_col(3, Vector3d(1, 1, 1))
self.assertAlmostEqual(matrix, Matrix3d(3, 2, 1, 4, 1, 1, 5, 2, 1))

def test_sub(self):
Expand Down Expand Up @@ -240,10 +240,10 @@ def test_from_2axes(self):
v2 = Vector3d(0.0, 1.0, 0.0)

m1 = Matrix3d()
m1.from_2_axes(v1, v2)
m1.set_from_2_axes(v1, v2)

m2 = Matrix3d()
m2.from_2_axes(v2, v1)
m2.set_from_2_axes(v2, v1)

m1Correct = Matrix3d(0, -1, 0,
1, 0, 0,
Expand All @@ -261,16 +261,16 @@ def test_from_2axes(self):
# rotation about 45 degrees
v1.set(1.0, 0.0, 0.0)
v2.set(1.0, 1.0, 0.0)
m2.from_2_axes(v1, v2)
m2.set_from_2_axes(v1, v2)
# m1 is 90 degrees rotation
self.assertAlmostEqual(m1, m2*m2)

# with non-unit vectors
v1.set(0.5, 0.5, 0)
v2.set(-0.5, 0.5, 0)

m1.from_2_axes(v1, v2)
m2.from_2_axes(v2, v1)
m1.set_from_2_axes(v1, v2)
m2.set_from_2_axes(v2, v1)

self.assertNotEqual(m1, m2)
self.assertAlmostEqual(m1Correct, m1)
Expand All @@ -282,25 +282,25 @@ def test_from_2axes(self):
# For zero-length vectors, a unit matrix is returned
v1.set(0, 0, 0)
v2.set(-0.5, 0.5, 0)
m1.from_2_axes(v1, v2)
m1.set_from_2_axes(v1, v2)
self.assertAlmostEqual(Matrix3d.IDENTITY, m1)

# For zero-length vectors, a unit matrix is returned
v1.set(-0.5, 0.5, 0)
v2.set(0, 0, 0)
m1.from_2_axes(v1, v2)
m1.set_from_2_axes(v1, v2)
self.assertAlmostEqual(Matrix3d.IDENTITY, m1)

# Parallel vectors
v1.set(1, 0, 0)
v2.set(2, 0, 0)
m1.from_2_axes(v1, v2)
m1.set_from_2_axes(v1, v2)
self.assertAlmostEqual(Matrix3d.IDENTITY, m1)

# Opposite vectors
v1.set(1, 0, 0)
v2.set(-2, 0, 0)
m1.from_2_axes(v1, v2)
m1.set_from_2_axes(v1, v2)
self.assertAlmostEqual(Matrix3d.ZERO - Matrix3d.IDENTITY, m1)

def test_to_quaternion(self):
Expand Down
13 changes: 7 additions & 6 deletions src/python/Pose3.i
Original file line number Diff line number Diff line change
Expand Up @@ -36,19 +36,18 @@ namespace ignition
{
%rename("%(undercase)s", %$isfunction, %$ismember, %$not %$isconstructor) "";
%rename("%(uppercase)s", %$isstatic, %$isvariable) "";

public: static const Pose3<T> Zero;

public: Pose3() : p(0, 0, 0), q(1, 0, 0, 0);
public: Pose3() = default;
public: Pose3(const Vector3<T> &_pos, const Quaternion<T> &_rot)
: p(_pos), q(_rot);
public: Pose3(T _x, T _y, T _z, T _roll, T _pitch, T _yaw)
: p(_x, _y, _z), q(_roll, _pitch, _yaw);
public: Pose3(T _x, T _y, T _z, T _qw, T _qx, T _qy, T _qz)
: p(_x, _y, _z), q(_qw, _qx, _qy, _qz);
public: Pose3(const Pose3<T> &_pose)
: p(_pose.p), q(_pose.q);
public: virtual ~Pose3();
public: Pose3(const Pose3<T> &_pose) = default;
public: ~Pose3() = default;
public: void Set(const Vector3<T> &_pos, const Quaternion<T> &_rot);
public: void Set(const Vector3<T> &_pos, const Vector3<T> &_rpy);
public: void Set(T _x, T _y, T _z, T _roll, T _pitch, T _yaw);
Expand All @@ -74,17 +73,20 @@ namespace ignition
public: void Reset();
public: Pose3<T> RotatePositionAboutOrigin(const Quaternion<T> &_q) const;
public: void Round(int _precision);
public: inline const Vector3<T> &Pos() const;
public: inline Vector3<T> &Pos();
public: inline const T X() const;
public: inline void SetX(T x);
public: inline const T Y() const;
public: inline void SetY(T y);
public: inline const T Z() const;
public: inline void SetZ(T z);
public: inline const Quaternion<T> &Rot() const;
public: inline Quaternion<T> &Rot();
public: inline const T Roll() const;
public: inline const T Pitch() const;
public: inline const T Yaw() const;
public: bool Equal(const Pose3 &_p, const T &_tol) const;
};

%extend Pose3 {
Expand All @@ -95,7 +97,6 @@ namespace ignition
}
}

%template(Pose3i) Pose3<int>;
%template(Pose3d) Pose3<double>;
%template(Pose3f) Pose3<float>;
}
Expand Down
56 changes: 31 additions & 25 deletions src/python/Pose3_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,44 +41,44 @@ def test_pose(self):
# A is the transform from O to P specified in frame O
# B is the transform from P to Q specified in frame P
# then, B + A is the transform from O to Q specified in frame O
self.assertAlmostEqual((B + A).pos().x(), 1.0 + 1.0/math.sqrt(2))
self.assertAlmostEqual((B + A).pos().y(), 1.0/math.sqrt(2))
self.assertAlmostEqual((B + A).pos().z(), 0.0)
self.assertAlmostEqual((B + A).rot().euler().x(), 0.0)
self.assertAlmostEqual((B + A).rot().euler().y(), 0.0)
self.assertAlmostEqual((B + A).rot().euler().z(), 3.0*math.pi/4.0)
self.assertAlmostEqual((B + A).x(), 1.0 + 1.0/math.sqrt(2))
self.assertAlmostEqual((B + A).y(), 1.0/math.sqrt(2))
self.assertAlmostEqual((B + A).z(), 0.0)
self.assertAlmostEqual((B + A).roll(), 0.0)
self.assertAlmostEqual((B + A).pitch(), 0.0)
self.assertAlmostEqual((B + A).yaw(), 3.0*math.pi/4.0)

# If:
# A is the transform from O to P in frame O
# B is the transform from O to Q in frame O
# then -A is transform from P to O specified in frame P
self.assertAlmostEqual((Pose3d() - A).pos().x(), -1.0/math.sqrt(2))
self.assertAlmostEqual((Pose3d() - A).pos().y(), 1.0/math.sqrt(2))
self.assertAlmostEqual((Pose3d() - A).pos().z(), 0.0)
self.assertAlmostEqual((Pose3d() - A).rot().euler().x(), 0.0)
self.assertAlmostEqual((Pose3d() - A).rot().euler().y(), 0.0)
self.assertAlmostEqual((Pose3d() - A).rot().euler().z(), -math.pi/4)
self.assertAlmostEqual((Pose3d() - A).x(), -1.0/math.sqrt(2))
self.assertAlmostEqual((Pose3d() - A).y(), 1.0/math.sqrt(2))
self.assertAlmostEqual((Pose3d() - A).z(), 0.0)
self.assertAlmostEqual((Pose3d() - A).roll(), 0.0)
self.assertAlmostEqual((Pose3d() - A).pitch(), 0.0)
self.assertAlmostEqual((Pose3d() - A).yaw(), -math.pi/4)

# test negation operator
self.assertAlmostEqual((-A).pos().x(), -1.0/math.sqrt(2))
self.assertAlmostEqual((-A).pos().y(), 1.0/math.sqrt(2))
self.assertAlmostEqual((-A).pos().z(), 0.0)
self.assertAlmostEqual((-A).rot().euler().x(), 0.0)
self.assertAlmostEqual((-A).rot().euler().y(), 0.0)
self.assertAlmostEqual((-A).rot().euler().z(), -math.pi/4.0)
self.assertAlmostEqual((-A).x(), -1.0/math.sqrt(2))
self.assertAlmostEqual((-A).y(), 1.0/math.sqrt(2))
self.assertAlmostEqual((-A).z(), 0.0)
self.assertAlmostEqual((-A).roll(), 0.0)
self.assertAlmostEqual((-A).pitch(), 0.0)
self.assertAlmostEqual((-A).yaw(), -math.pi/4.0)

# If:
# A is the transform from O to P in frame O
# B is the transform from O to Q in frame O
# B - A is the transform from P to Q in frame P
B = Pose3d(Vector3d(1, 1, 0),
Quaterniond(0, 0, math.pi/2.0))
self.assertAlmostEqual((B - A).pos().x(), 1.0/math.sqrt(2))
self.assertAlmostEqual((B - A).pos().y(), 1.0/math.sqrt(2))
self.assertAlmostEqual((B - A).pos().z(), 0.0)
self.assertAlmostEqual((B - A).rot().euler().x(), 0.0)
self.assertAlmostEqual((B - A).rot().euler().y(), 0.0)
self.assertAlmostEqual((B - A).rot().euler().z(), math.pi/4.0)
self.assertAlmostEqual((B - A).x(), 1.0/math.sqrt(2))
self.assertAlmostEqual((B - A).y(), 1.0/math.sqrt(2))
self.assertAlmostEqual((B - A).z(), 0.0)
self.assertAlmostEqual((B - A).roll(), 0.0)
self.assertAlmostEqual((B - A).pitch(), 0.0)
self.assertAlmostEqual((B - A).yaw(), math.pi/4.0)

pose = Pose3d()
self.assertTrue(pose.pos() == Vector3d(0, 0, 0))
Expand Down Expand Up @@ -113,7 +113,7 @@ def test_pose(self):
self.assertTrue(pose == Pose3d(0, 0, 0, 0, 0, 0))

pose.pos().set(5, 6, 7)
pose.rot().euler(Vector3d(.4, .6, 0))
pose.rot().set_from_euler(Vector3d(.4, .6, 0))

self.assertTrue(pose.coord_position_add(Vector3d(1, 2, 3)) ==
Vector3d(7.82531, 6.67387, 9.35871))
Expand Down Expand Up @@ -158,11 +158,17 @@ def test_mutable_pose(self):
def test_pose_elements(self):
pose = Pose3d(0, 1, 2, 1, 1, 2)
self.assertAlmostEqual(pose.x(), 0)
self.assertAlmostEqual(pose.x(), pose.pos().x())
self.assertAlmostEqual(pose.y(), 1)
self.assertAlmostEqual(pose.y(), pose.pos().y())
self.assertAlmostEqual(pose.z(), 2)
self.assertAlmostEqual(pose.z(), pose.pos().z())
self.assertAlmostEqual(pose.roll(), 1)
self.assertAlmostEqual(pose.roll(), pose.rot().euler().x())
self.assertAlmostEqual(pose.pitch(), 1)
self.assertAlmostEqual(pose.pitch(), pose.rot().euler().y())
self.assertAlmostEqual(pose.yaw(), 2)
self.assertAlmostEqual(pose.yaw(), pose.rot().euler().z())

def test_set_pose_element(self):
pose = Pose3d(1, 2, 3, 1.57, 1, 2)
Expand Down
50 changes: 25 additions & 25 deletions src/python/Quaternion.i
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@

%inline %{
template<typename D>
struct ToAxisOutput {
struct AxisAngleOutput {
ignition::math::Vector3<D> axis;
D angle;
};
Expand All @@ -46,32 +46,34 @@ namespace ignition
public: static const Quaternion Identity;
public: static const Quaternion Zero;

public: Quaternion();
public: Quaternion(const T &_w, const T &_x, const T &_y, const T &_z);
public: Quaternion()
: qw(1), qx(0), qy(0), qz(0);
public: Quaternion(const T &_w, const T &_x, const T &_y, const T &_z)
: qw(_w), qx(_x), qy(_y), qz(_z);
public: Quaternion(const T &_roll, const T &_pitch, const T &_yaw);
public: Quaternion(const Vector3<T> &_axis, const T &_angle);
public: explicit Quaternion(const Vector3<T> &_rpy);
public: Quaternion(const Quaternion<T> &_qt);
public: ~Quaternion();
public: Quaternion(const Quaternion<T> &_qt) = default;
public: ~Quaternion() = default;
public: void Invert();
public: inline Quaternion<T> Inverse() const;
public: Quaternion<T> Log() const;
public: Quaternion<T> Exp() const;
public: void Normalize();
public: Quaternion<T> Normalized() const;
public: void Axis(T _ax, T _ay, T _az, T _aa);
public: void Axis(const Vector3<T> &_axis, T _a);
public: void SetFromAxisAngle(T _ax, T _ay, T _az, T _aa);
public: void SetFromAxisAngle(const Vector3<T> &_axis, T _a);
public: void Set(T _w, T _x, T _y, T _z);
public: void Euler(const Vector3<T> &_vec);
public: void Euler(T _roll, T _pitch, T _yaw);
public: void SetFromEuler(const Vector3<T> &_vec);
public: void SetFromEuler(T _roll, T _pitch, T _yaw);
public: Vector3<T> Euler() const;
public: static Quaternion<T> EulerToQuaternion(const Vector3<T> &_vec);
public: static Quaternion<T> EulerToQuaternion(T _x, T _y, T _z);
public: T Roll() const;
public: T Pitch() const;
public: T Yaw() const;
%rename(from_2_axes) From2Axes;
public: void From2Axes(const Vector3<T> &_v1, const Vector3<T> &_v2);
%rename(set_from_2_axes) SetFrom2Axes;
public: void SetFrom2Axes(const Vector3<T> &_v1, const Vector3<T> &_v2);
public: void Scale(T _scale);
public: Quaternion<T> operator+(const Quaternion<T> &_qt) const;
public: Quaternion<T> operator+=(const Quaternion<T> &_qt);
Expand Down Expand Up @@ -107,24 +109,24 @@ namespace ignition
public: Quaternion<T> Integrate(const Vector3<T> &_angularVelocity,
const T _deltaT) const;

public: inline void X(T _v);
public: inline void Y(T _v);
public: inline void Z(T _v);
public: inline void W(T _v);
public: inline void SetX(T _v);
public: inline void SetY(T _v);
public: inline void SetZ(T _v);
public: inline void SetW(T _v);

%pythoncode %{
def to_axis(self):
to_axis_output = self._to_axis()
return [to_axis_output.axis, to_axis_output.angle]
def axis_angle(self):
axis_angle_output = self._axis_angle()
return [axis_angle_output.axis, axis_angle_output.angle]
%}
};

%extend Quaternion{
inline ToAxisOutput<T> _to_axis() {
inline AxisAngleOutput<T> _axis_angle() {
ignition::math::Vector3<T> axis;
T angle;
(*$self).ToAxis(axis, angle);
ToAxisOutput<T> output;
(*$self).AxisAngle(axis, angle);
AxisAngleOutput<T> output;
output.axis = axis;
output.angle = angle;
return output;
Expand Down Expand Up @@ -161,11 +163,9 @@ namespace ignition
}
}

%template(Quaternioni) Quaternion<int>;
%template(Quaterniond) Quaternion<double>;
%template(Quaternionf) Quaternion<float>;
}
}
%template(ToAxisOutputi) ToAxisOutput<int>;
%template(ToAxisOutputd) ToAxisOutput<double>;
%template(ToAxisOutputf) ToAxisOutput<float>;
%template(AxisAngleOutputd) AxisAngleOutput<double>;
%template(AxisAngleOutputf) AxisAngleOutput<float>;
Loading

0 comments on commit 84837c2

Please sign in to comment.