Franky  0.9.1
A High-Level Motion API for Franka
Namespaces | Macros | Functions
measure.cpp File Reference
#include "franky/motion/measure.hpp"
#include <sstream>
#include <utility>
#include <franka/robot_state.h>

Namespaces

 franky
 

Macros

#define MEASURE_CMP_DEF(OP)
 
#define MEASURE_OP_DEF(OP)
 

Functions

Measure franky::measure_pow (const Measure &base, const Measure &exponent)
 
Measure franky::operator- (const Measure &m)
 

Macro Definition Documentation

◆ MEASURE_CMP_DEF

#define MEASURE_CMP_DEF (   OP)
Value:
Condition operator OP(const Measure &m1, const Measure &m2) { \
std::stringstream ss; \
ss << m1.repr() << " " << #OP << " " << m2.repr(); \
return Condition([m1, m2](const franka::RobotState &robot_state, double rel_time, double abs_time) { \
return m1(robot_state, rel_time, abs_time) OP m2(robot_state, rel_time, abs_time); \
}, ss.str()); \
}

◆ MEASURE_OP_DEF

#define MEASURE_OP_DEF (   OP)
Value:
Measure operator OP(const Measure &m1, const Measure &m2) { \
std::stringstream ss; \
ss << "(" << m1.repr() << ") " << #OP << " (" << m2.repr() << ")"; \
return Measure([m1, m2](const franka::RobotState &robot_state, double rel_time, double abs_time) { \
return m1(robot_state, rel_time, abs_time) OP m2(robot_state, rel_time, abs_time); \
}, ss.str()); \
}