42 inline bool operator()(
const RobotState &robot_state, franka::Duration rel_time, franka::Duration abs_time)
const {
43 return check_func_(robot_state, rel_time, abs_time);
49 [[nodiscard]]
inline std::string
repr()
const {
return repr_; }
56Condition
operator&&(
const Condition &c1,
const Condition &c2);
58Condition
operator||(
const Condition &c1,
const Condition &c2);
60Condition
operator==(
const Condition &c1,
const Condition &c2);
62Condition
operator!=(
const Condition &c1,
const Condition &c2);
A condition on the robot state.
Definition condition.hpp:16
bool operator()(const RobotState &robot_state, franka::Duration rel_time, franka::Duration abs_time) const
Check if the condition is met.
Definition condition.hpp:42
std::function< bool(const RobotState &, franka::Duration, franka::Duration)> CheckFunc
Definition condition.hpp:18
std::string repr() const
The string representation of the condition.
Definition condition.hpp:49
Definition dynamics_limit.cpp:8
Condition operator==(const Condition &c1, const Condition &c2)
Definition condition.cpp:33
Condition operator!=(const Condition &c1, const Condition &c2)
Definition condition.cpp:41
Condition operator&&(const Condition &c1, const Condition &c2)
Definition condition.cpp:17
Condition operator||(const Condition &c1, const Condition &c2)
Definition condition.cpp:25
Condition operator!(const Condition &c)
Definition condition.cpp:49
Full state of the robot.
Definition robot_state.hpp:23