Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
measure.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <functional>
4#include <iostream>
5#include <franka/robot_state.h>
6
8
9namespace franky {
10
18class Measure {
19 using MeasureFunc = std::function<double(
20 const RobotState &, franka::Duration, franka::Duration)>;
21
22 public:
27 explicit Measure(MeasureFunc measure_func, std::string repr = "NULL");
28
33 Measure(double constant);
34
44 inline double operator()(
45 const RobotState &robot_state,
46 franka::Duration rel_time,
47 franka::Duration abs_time) const {
48 return measure_func_(robot_state, rel_time, abs_time);
49 }
50
54 [[nodiscard]] inline std::string repr() const {
55 return repr_;
56 }
57
62 static Measure ForceX();
63
68 static Measure ForceY();
69
74 static Measure ForceZ();
75
79 static Measure RelTime();
80
86 static Measure AbsTime();
87
88 private:
89 MeasureFunc measure_func_;
90 std::string repr_;
91};
92
93Condition operator==(const Measure &m1, const Measure &m2);
94Condition operator!=(const Measure &m1, const Measure &m2);
95Condition operator<=(const Measure &m1, const Measure &m2);
96Condition operator>=(const Measure &m1, const Measure &m2);
97Condition operator<(const Measure &m1, const Measure &m2);
98Condition operator>(const Measure &m1, const Measure &m2);
99
100Measure operator+(const Measure &m1, const Measure &m2);
101Measure operator-(const Measure &m1, const Measure &m2);
102Measure operator*(const Measure &m1, const Measure &m2);
103Measure operator/(const Measure &m1, const Measure &m2);
104
105Measure operator-(const Measure &m);
106
107Measure measure_pow(const Measure &base, const Measure &exponent);
108
109} // namespace franky
A condition on the robot state.
Definition condition.hpp:15
A measure on the robot state.
Definition measure.hpp:18
double operator()(const RobotState &robot_state, franka::Duration rel_time, franka::Duration abs_time) const
Get the value of the measure.
Definition measure.hpp:44
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:45
std::string repr() const
The string representation of the measure.
Definition measure.hpp:54
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:37
static Measure AbsTime()
A measure that returns the absolute time since the start of the current chain of motions....
Definition measure.cpp:70
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:53
static Measure RelTime()
A measure that returns the relative time since the start of the current motion.
Definition measure.cpp:61
Definition dynamics_limit.cpp:8
Measure measure_pow(const Measure &base, const Measure &exponent)
Definition measure.cpp:91
Condition operator==(const Condition &c1, const Condition &c2)
Definition condition.cpp:34
Measure operator+(const Measure &m1, const Measure &m2)
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition cartesian_state.hpp:78
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:42
Condition operator>(const Measure &m1, const Measure &m2)
Condition operator>=(const Measure &m1, const Measure &m2)
Measure operator-(const Measure &m)
Definition measure.cpp:102
Measure operator/(const Measure &m1, const Measure &m2)
Full state of the robot.
Definition robot_state.hpp:20