Skip to content

Commit 3ef8a50

Browse files
Simplified Measure class by making the double constructor non-explicit
1 parent 1593406 commit 3ef8a50

File tree

2 files changed

+25
-46
lines changed

2 files changed

+25
-46
lines changed

include/franky/motion/measure.hpp

+11-35
Original file line numberDiff line numberDiff line change
@@ -8,24 +8,6 @@
88

99
#include "franky/motion/condition.hpp"
1010

11-
#define MEASURE_CMP_DECL(OP) \
12-
Condition operator OP(const Measure &m1, const Measure &m2); \
13-
inline Condition operator OP(const Measure &m1, double m2) { \
14-
return m1 OP Measure(m2); \
15-
} \
16-
inline Condition operator OP(double m1, const Measure &m2) { \
17-
return Measure(m1) OP m2; \
18-
}
19-
20-
#define MEASURE_OP_DECL(OP) \
21-
Measure operator OP(const Measure &m1, const Measure &m2); \
22-
inline Measure operator OP(const Measure &m1, double m2){ \
23-
return m1 OP Measure(m2); \
24-
} \
25-
inline Measure operator OP(double m1, const Measure &m2){ \
26-
return Measure(m1) OP m2; \
27-
}
28-
2911
namespace franky {
3012

3113
class Measure {
@@ -34,7 +16,7 @@ class Measure {
3416
public:
3517
explicit Measure(MeasureFunc measure_func, std::string repr = "NULL");
3618

37-
explicit Measure(double constant);
19+
Measure(double constant);
3820

3921
inline double operator()(const franka::RobotState &robot_state, double rel_time, double abs_time) const {
4022
return measure_func_(robot_state, rel_time, abs_time);
@@ -59,26 +41,20 @@ class Measure {
5941
std::string repr_;
6042
};
6143

62-
MEASURE_CMP_DECL(==)
63-
MEASURE_CMP_DECL(!=)
64-
MEASURE_CMP_DECL(<=)
65-
MEASURE_CMP_DECL(>=)
66-
MEASURE_CMP_DECL(<)
67-
MEASURE_CMP_DECL(>)
44+
Condition operator==(const Measure &m1, const Measure &m2);
45+
Condition operator!=(const Measure &m1, const Measure &m2);
46+
Condition operator<=(const Measure &m1, const Measure &m2);
47+
Condition operator>=(const Measure &m1, const Measure &m2);
48+
Condition operator<(const Measure &m1, const Measure &m2);
49+
Condition operator>(const Measure &m1, const Measure &m2);
6850

69-
MEASURE_OP_DECL(+)
70-
MEASURE_OP_DECL(-)
71-
MEASURE_OP_DECL(*)
72-
MEASURE_OP_DECL(/)
51+
Measure operator+(const Measure &m1, const Measure &m2);
52+
Measure operator-(const Measure &m1, const Measure &m2);
53+
Measure operator*(const Measure &m1, const Measure &m2);
54+
Measure operator/(const Measure &m1, const Measure &m2);
7355

7456
Measure operator-(const Measure &m);
7557

7658
Measure measure_pow(const Measure &base, const Measure &exponent);
77-
inline Measure measure_pow(double base, const Measure &exponent) {
78-
return measure_pow(Measure(base), exponent);
79-
}
80-
inline Measure measure_pow(const Measure &base, double exponent) {
81-
return measure_pow(base, Measure(exponent));
82-
}
8359

8460
} // namespace franky

python/python.cpp

+14-11
Original file line numberDiff line numberDiff line change
@@ -235,31 +235,34 @@ PYBIND11_MODULE(_franky, m) {
235235
.def_property_readonly_static("REL_TIME", [](py::object) { return Measure::RelTime(); })
236236
.def_property_readonly_static("ABS_TIME", [](py::object) { return Measure::AbsTime(); })
237237
.def("__eq__", py::overload_cast<const Measure &, const Measure &>(&operator==), py::is_operator())
238-
.def("__eq__", py::overload_cast<const Measure &, double>(&operator==), py::is_operator())
238+
.def("__eq__", [](const Measure &measure, double constant) { return measure == constant; }, py::is_operator())
239239
.def("__ne__", py::overload_cast<const Measure &, const Measure &>(&operator!=), py::is_operator())
240-
.def("__ne__", py::overload_cast<const Measure &, double>(&operator!=), py::is_operator())
240+
.def("__ne__", [](const Measure &measure, double constant) { return measure != constant; }, py::is_operator())
241241
.def("__gt__", py::overload_cast<const Measure &, const Measure &>(&operator>), py::is_operator())
242-
.def("__gt__", py::overload_cast<const Measure &, double>(&operator>), py::is_operator())
242+
.def("__gt__", [](const Measure &measure, double constant) { return measure > constant; }, py::is_operator())
243243
.def("__ge__", py::overload_cast<const Measure &, const Measure &>(&operator>=), py::is_operator())
244-
.def("__ge__", py::overload_cast<const Measure &, double>(&operator>=), py::is_operator())
244+
.def("__ge__", [](const Measure &measure, double constant) { return measure >= constant; }, py::is_operator())
245245
.def("__lt__", py::overload_cast<const Measure &, const Measure &>(&operator<), py::is_operator())
246-
.def("__lt__", py::overload_cast<const Measure &, double>(&operator<), py::is_operator())
246+
.def("__lt__", [](const Measure &measure, double constant) { return measure < constant; }, py::is_operator())
247247
.def("__le__", py::overload_cast<const Measure &, const Measure &>(&operator<=), py::is_operator())
248-
.def("__le__", py::overload_cast<const Measure &, double>(&operator<=), py::is_operator())
248+
.def("__le__", [](const Measure &measure, double constant) { return measure <= constant; }, py::is_operator())
249+
.def("__neg__", py::overload_cast<const Measure &>(&operator-), py::is_operator())
249250
.def("__add__", py::overload_cast<const Measure &, const Measure &>(&operator+), py::is_operator())
250-
.def("__add__", py::overload_cast<const Measure &, double>(&operator+), py::is_operator())
251+
.def("__add__", [](const Measure &measure, double constant) { return measure + constant; }, py::is_operator())
251252
.def("__radd__", [](const Measure &measure, double constant) { return constant + measure; }, py::is_operator())
252253
.def("__sub__", py::overload_cast<const Measure &, const Measure &>(&operator-), py::is_operator())
253-
.def("__sub__", py::overload_cast<const Measure &, double>(&operator-), py::is_operator())
254+
.def("__sub__", [](const Measure &measure, double constant) { return constant - measure; }, py::is_operator())
254255
.def("__rsub__", [](const Measure &measure, double constant) { return constant - measure; }, py::is_operator())
255256
.def("__mul__", py::overload_cast<const Measure &, const Measure &>(&operator*), py::is_operator())
256-
.def("__mul__", py::overload_cast<const Measure &, double>(&operator*), py::is_operator())
257+
.def("__mul__", [](const Measure &measure, double constant) { return constant * measure; }, py::is_operator())
257258
.def("__rmul__", [](const Measure &measure, double constant) { return constant * measure; }, py::is_operator())
258259
.def("__div__", py::overload_cast<const Measure &, const Measure &>(&operator/), py::is_operator())
259-
.def("__div__", py::overload_cast<const Measure &, double>(&operator/), py::is_operator())
260+
.def("__div__", [](const Measure &measure, double constant) { return constant / measure; }, py::is_operator())
260261
.def("__rdiv__", [](const Measure &measure, double constant) { return constant / measure; }, py::is_operator())
261262
.def("__pow__", py::overload_cast<const Measure &, const Measure &>(&measure_pow), py::is_operator())
262-
.def("__pow__", py::overload_cast<const Measure &, double>(&measure_pow), py::is_operator())
263+
.def("__pow__",
264+
[](const Measure &measure, double constant) { return measure_pow(measure, constant); },
265+
py::is_operator())
263266
.def("__rpow__",
264267
[](const Measure &measure, double constant) { return measure_pow(constant, measure); },
265268
py::is_operator())

0 commit comments

Comments
 (0)