7 #include <franka/robot_state.h>
21 using MeasureFunc = std::function<double(
const franka::RobotState &,
double,
double)>;
28 explicit Measure(MeasureFunc measure_func, std::string
repr =
"NULL");
45 inline double operator()(
const franka::RobotState &robot_state,
double rel_time,
double abs_time)
const {
46 return measure_func_(robot_state, rel_time, abs_time);
52 [[nodiscard]]
inline std::string
repr()
const {
87 MeasureFunc measure_func_;
A condition on the robot state.
Definition: condition.hpp:18
A measure on the robot state.
Definition: measure.hpp:20
static Measure ForceY()
A measure that returns the linear force on the end-effector in Y direction as by the O_F_ext_hat_K co...
Definition: measure.cpp:41
std::string repr() const
The string representation of the measure.
Definition: measure.hpp:52
static Measure ForceX()
A measure that returns the linear force on the end-effector in X direction as by the O_F_ext_hat_K co...
Definition: measure.cpp:35
Measure(MeasureFunc measure_func, std::string repr="NULL")
Definition: measure.cpp:27
static Measure AbsTime()
A measure that returns the absolute time since the start of the current chain of motions....
Definition: measure.cpp:59
static Measure ForceZ()
A measure that returns the linear force on the end-effector in Z direction as by the O_F_ext_hat_K co...
Definition: measure.cpp:47
static Measure RelTime()
A measure that returns the relative time since the start of the current motion.
Definition: measure.cpp:53
double operator()(const franka::RobotState &robot_state, double rel_time, double abs_time) const
Get the value of the measure.
Definition: measure.hpp:45
Definition: gripper.cpp:3
Measure measure_pow(const Measure &base, const Measure &exponent)
Definition: measure.cpp:77
Condition operator==(const Condition &c1, const Condition &c2)
Definition: condition.cpp:30
Measure operator+(const Measure &m1, const Measure &m2)
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition: cartesian_state.hpp:76
Condition operator<=(const Measure &m1, const Measure &m2)
Condition operator<(const Measure &m1, const Measure &m2)
Condition operator!=(const Condition &c1, const Condition &c2)
Definition: condition.cpp:36
Condition operator>(const Measure &m1, const Measure &m2)
Condition operator>=(const Measure &m1, const Measure &m2)
Measure operator-(const Measure &m)
Definition: measure.cpp:85
Measure operator/(const Measure &m1, const Measure &m2)