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>
  • Loading branch information
chapulina committed Dec 28, 2021
1 parent 22d9aad commit c69f1a9
Show file tree
Hide file tree
Showing 4 changed files with 60 additions and 60 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
18 changes: 9 additions & 9 deletions src/python/Matrix3_TEST.py
Original file line number Diff line number Diff line change
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
40 changes: 20 additions & 20 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 Down Expand Up @@ -59,19 +59,19 @@ namespace ignition
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 +107,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 @@ -166,6 +166,6 @@ namespace ignition
%template(Quaternionf) Quaternion<float>;
}
}
%template(ToAxisOutputi) ToAxisOutput<int>;
%template(ToAxisOutputd) ToAxisOutput<double>;
%template(ToAxisOutputf) ToAxisOutput<float>;
%template(AxisAngleOutputi) AxisAngleOutput<int>;
%template(AxisAngleOutputd) AxisAngleOutput<double>;
%template(AxisAngleOutputf) AxisAngleOutput<float>;
52 changes: 26 additions & 26 deletions src/python/Quaternion_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ def test_mathlog(self):
Quaterniond(0, -1.02593, 0.162491, 1.02593))

q1 = Quaterniond(q)
q1.w(2.0)
q1.set_w(2.0)
self.assertAlmostEqual(q1.log(),
Quaterniond(0, -0.698401, 0.110616, 0.698401))

Expand All @@ -129,10 +129,10 @@ def test_math_exp(self):
0.093284, 0.588972))

q1 = Quaterniond(q)
q1.x(0.000000001)
q1.y(0.0)
q1.z(0.0)
q1.w(0.0)
q1.set_x(0.000000001)
q1.set_y(0.0)
q1.set_z(0.0)
q1.set_w(0.0)
self.assertAlmostEqual(q1.exp(), Quaterniond(1, 0, 0, 0))

def test_math_invert(self):
Expand All @@ -145,10 +145,10 @@ def test_math_invert(self):
def test_math_axis(self):
q = Quaterniond(math.pi*0.1, math.pi*0.5, math.pi)

q.axis(0, 1, 0, math.pi)
q.set_from_axis_angle(0, 1, 0, math.pi)
self.assertAlmostEqual(q, Quaterniond(6.12303e-17, 0, 1, 0))

q.axis(Vector3d(1, 0, 0), math.pi)
q.set_from_axis_angle(Vector3d(1, 0, 0), math.pi)
self.assertAlmostEqual(q, Quaterniond(0, 1, 0, 0))

def test_math_set(self):
Expand Down Expand Up @@ -187,7 +187,7 @@ def test_math(self):
self.assertAlmostEqual(q.pitch(), -0.339837, delta=1e-3)
self.assertAlmostEqual(q.yaw(), 2.35619, delta=1e-3)

axis, angle = q.to_axis()
axis, angle = q.axis_angle()
self.assertAlmostEqual(
axis, Vector3d(0.371391, 0.557086, 0.742781), delta=1e-3)
self.assertAlmostEqual(angle, 2.77438, delta=1e-3)
Expand Down Expand Up @@ -241,10 +241,10 @@ def test_math(self):
self.assertAlmostEqual(4.01, q.z())
self.assertAlmostEqual(7.68, q.w())

q.x(0.0)
q.y(0.0)
q.z(0.0)
q.w(0.0)
q.set_x(0.0)
q.set_y(0.0)
q.set_z(0.0)
q.set_w(0.0)
q.normalize()
self.assertTrue(q == Quaterniond())

Expand All @@ -254,12 +254,12 @@ def test_math(self):
self.assertTrue(Quaterniond.euler_to_quaternion(0.1, 0.2, 0.3) ==
Quaterniond(0.983347, 0.0342708, 0.106021, 0.143572))

# to_axis() method
q.x(0.0)
q.y(0.0)
q.z(0.0)
q.w(0.0)
axis, angle = q.to_axis()
# axis_angle() method
q.set_x(0.0)
q.set_y(0.0)
q.set_z(0.0)
q.set_w(0.0)
axis, angle = q.axis_angle()
self.assertAlmostEqual(axis, Vector3d(1., 0., 0.), delta=1e-3)
self.assertAlmostEqual(angle, 0., delta=1e-3)

Expand Down Expand Up @@ -376,10 +376,10 @@ def test_from_2_axes(self):
v2 = Vector3d(0.0, 1.0, 0.0)

q1 = Quaterniond()
q1.from_2_axes(v1, v2)
q1.set_from_2_axes(v1, v2)

q2 = Quaterniond()
q2.from_2_axes(v2, v1)
q2.set_from_2_axes(v2, v1)

q2Correct = Quaterniond(math.sqrt(2)/2, 0, 0, -math.sqrt(2)/2)
q1Correct = Quaterniond(math.sqrt(2)/2, 0, 0, math.sqrt(2)/2)
Expand All @@ -395,8 +395,8 @@ def test_from_2_axes(self):
v1.set(0.5, 0.5, 0)
v2.set(-0.5, 0.5, 0)

q1.from_2_axes(v1, v2)
q2.from_2_axes(v2, v1)
q1.set_from_2_axes(v1, v2)
q2.set_from_2_axes(v2, v1)

self.assertNotEqual(q1, q2)
self.assertAlmostEqual(q1Correct, q1)
Expand All @@ -410,7 +410,7 @@ def test_from_2_axes(self):

v1.set(1, 0, 0)
v2.set(-1, 0, 0)
q1.from_2_axes(v1, v2)
q1.set_from_2_axes(v1, v2)
q2 = q1 * q1
self.assertTrue(abs(q2.w()-1.0) <= tolerance or
abs(q2.w()-(-1.0)) <= tolerance)
Expand All @@ -420,7 +420,7 @@ def test_from_2_axes(self):

v1.set(0, 1, 0)
v2.set(0, -1, 0)
q1.from_2_axes(v1, v2)
q1.set_from_2_axes(v1, v2)
q2 = q1 * q1
self.assertTrue(abs(q2.w()-1.0) <= tolerance or
abs(q2.w()-(-1.0)) <= tolerance)
Expand All @@ -430,7 +430,7 @@ def test_from_2_axes(self):

v1.set(0, 0, 1)
v2.set(0, 0, -1)
q1.from_2_axes(v1, v2)
q1.set_from_2_axes(v1, v2)
q2 = q1 * q1
self.assertTrue(abs(q2.w()-1.0) <= tolerance or
abs(q2.w()-(-1.0)) <= tolerance)
Expand All @@ -440,7 +440,7 @@ def test_from_2_axes(self):

v1.set(0, 1, 1)
v2.set(0, -1, -1)
q1.from_2_axes(v1, v2)
q1.set_from_2_axes(v1, v2)
q2 = q1 * q1
self.assertTrue(abs(q2.w()-1.0) <= tolerance or
abs(q2.w()-(-1.0)) <= tolerance)
Expand Down

0 comments on commit c69f1a9

Please sign in to comment.