18 const RobotState &, franka::Duration, franka::Duration)>;
43 franka::Duration rel_time,
44 franka::Duration abs_time)
const {
45 return check_func_(robot_state, rel_time, abs_time);
51 [[nodiscard]]
inline std::string
repr()
const {
60Condition
operator&&(
const Condition &c1,
const Condition &c2);
62Condition
operator||(
const Condition &c1,
const Condition &c2);
64Condition
operator==(
const Condition &c1,
const Condition &c2);
66Condition
operator!=(
const Condition &c1,
const Condition &c2);
A condition on the robot state.
Definition condition.hpp:15
std::function< bool(const RobotState &, franka::Duration, franka::Duration)> CheckFunc
Definition condition.hpp:18
bool operator()(const RobotState &robot_state, franka::Duration rel_time, franka::Duration abs_time) const
Check if the condition is met.
Definition condition.hpp:41
std::string repr() const
The string representation of the condition.
Definition condition.hpp:51
Definition dynamics_limit.cpp:8
Condition operator==(const Condition &c1, const Condition &c2)
Definition condition.cpp:34
Condition operator!=(const Condition &c1, const Condition &c2)
Definition condition.cpp:42
Condition operator&&(const Condition &c1, const Condition &c2)
Definition condition.cpp:18
Condition operator||(const Condition &c1, const Condition &c2)
Definition condition.cpp:26
Condition operator!(const Condition &c)
Definition condition.cpp:50
Full state of the robot.
Definition robot_state.hpp:20