7 #include <franka/robot_state.h>
20 using CheckFunc = std::function<bool(
const franka::RobotState &,
double,
double)>;
43 inline bool operator()(
const franka::RobotState &robot_state,
double rel_time,
double abs_time)
const {
44 return check_func_(robot_state, rel_time, abs_time);
50 [[nodiscard]]
inline std::string
repr()
const {
59 Condition
operator&&(
const Condition &c1,
const Condition &c2);
61 Condition
operator||(
const Condition &c1,
const Condition &c2);
63 Condition
operator==(
const Condition &c1,
const Condition &c2);
65 Condition
operator!=(
const Condition &c1,
const Condition &c2);
A condition on the robot state.
Definition: condition.hpp:18
bool operator()(const franka::RobotState &robot_state, double rel_time, double abs_time) const
Check if the condition is met.
Definition: condition.hpp:43
std::function< bool(const franka::RobotState &, double, double)> CheckFunc
Definition: condition.hpp:20
Condition(CheckFunc check_func, std::string repr="NULL")
Definition: condition.cpp:9
std::string repr() const
The string representation of the condition.
Definition: condition.hpp:50
Definition: gripper.cpp:3
Condition operator==(const Condition &c1, const Condition &c2)
Definition: condition.cpp:30
Condition operator!=(const Condition &c1, const Condition &c2)
Definition: condition.cpp:36
Condition operator&&(const Condition &c1, const Condition &c2)
Definition: condition.cpp:18
Condition operator||(const Condition &c1, const Condition &c2)
Definition: condition.cpp:24
Condition operator!(const Condition &c)
Definition: condition.cpp:42