Franky
0.9.1
A High-Level Motion API for Franka
|
A condition on the robot state. More...
#include <condition.hpp>
Public Types | |
using | CheckFunc = std::function< bool(const franka::RobotState &, double, double)> |
Public Member Functions | |
Condition (CheckFunc check_func, std::string repr="NULL") | |
Condition (bool constant_value) | |
Implicit constructor for constant conditions. More... | |
bool | operator() (const franka::RobotState &robot_state, double rel_time, double abs_time) const |
Check if the condition is met. More... | |
std::string | repr () const |
The string representation of the condition. More... | |
A condition on the robot state.
This class defines a condition on the robot state, which can be used to define a condition for a reaction in a motion. Conditions support logical operations (&&, ||, ==, !=, !) and can be combined to form more complex conditions.
using franky::Condition::CheckFunc = std::function<bool(const franka::RobotState &, double, double)> |
|
explicit |
check_func | A function that returns true if the condition is met. |
repr | A string representation of the condition. |
franky::Condition::Condition | ( | bool | constant_value | ) |
Implicit constructor for constant conditions.
constant_value | The constant value of the condition. |
|
inline |
Check if the condition is met.
robot_state | The current robot state. |
rel_time | The time since the start of the current motion. |
abs_time | The time since the start of the current chain of motions. This value measures the time since the robot started moving, and is only reset if a motion expires without being replaced by a new motion. |
|
inline |
The string representation of the condition.