3#include <franka/robot_state.h>
21 using MeasureFunc = std::function<double(
const RobotState &, franka::Duration, franka::Duration)>;
28 explicit Measure(MeasureFunc measure_func, std::string
repr =
"NULL");
46 inline double operator()(
const RobotState &robot_state, franka::Duration rel_time, franka::Duration abs_time)
const {
47 return measure_func_(robot_state, rel_time, abs_time);
53 [[nodiscard]]
inline std::string
repr()
const {
return repr_; }
88 MeasureFunc measure_func_;
A condition on the robot state.
Definition condition.hpp:16
A measure on the robot state.
Definition measure.hpp:20
double operator()(const RobotState &robot_state, franka::Duration rel_time, franka::Duration abs_time) const
Get the value of the measure.
Definition measure.hpp:46
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:49
std::string repr() const
The string representation of the measure.
Definition measure.hpp:53
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:41
static Measure AbsTime()
A measure that returns the absolute time since the start of the current chain of motions....
Definition measure.cpp:73
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:57
static Measure RelTime()
A measure that returns the relative time since the start of the current motion.
Definition measure.cpp:65
Definition dynamics_limit.cpp:8
Measure measure_pow(const Measure &base, const Measure &exponent)
Definition measure.cpp:93
Condition operator==(const Condition &c1, const Condition &c2)
Definition condition.cpp:33
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:41
Condition operator>(const Measure &m1, const Measure &m2)
Condition operator>=(const Measure &m1, const Measure &m2)
Measure operator-(const Measure &m)
Definition measure.cpp:103
Measure operator/(const Measure &m1, const Measure &m2)
Full state of the robot.
Definition robot_state.hpp:23