Franky  0.9.1
A High-Level Motion API for Franka
condition.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <functional>
4 #include <cmath>
5 #include <memory>
6 #include <iostream>
7 #include <franka/robot_state.h>
8 
9 namespace franky {
10 
18 class Condition {
19  public:
20  using CheckFunc = std::function<bool(const franka::RobotState &, double, double)>;
21 
26  explicit Condition(CheckFunc check_func, std::string repr = "NULL");
27 
32  Condition(bool constant_value);
33 
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);
45  }
46 
50  [[nodiscard]] inline std::string repr() const {
51  return repr_;
52  }
53 
54  private:
55  CheckFunc check_func_;
56  std::string repr_;
57 };
58 
59 Condition operator&&(const Condition &c1, const Condition &c2);
60 
61 Condition operator||(const Condition &c1, const Condition &c2);
62 
63 Condition operator==(const Condition &c1, const Condition &c2);
64 
65 Condition operator!=(const Condition &c1, const Condition &c2);
66 
67 Condition operator!(const Condition &c);
68 
69 } // namespace franky
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