Franky  0.9.1
A High-Level Motion API for Franka
Public Member Functions | Static Public Member Functions | List of all members
franky::Measure Class Reference

A measure on the robot state. More...

#include <measure.hpp>

Public Member Functions

 Measure (MeasureFunc measure_func, std::string repr="NULL")
 
 Measure (double constant)
 Implicit constructor for constant measures. More...
 
double operator() (const franka::RobotState &robot_state, double rel_time, double abs_time) const
 Get the value of the measure. More...
 
std::string repr () const
 The string representation of the measure. More...
 

Static Public Member Functions

static Measure ForceX ()
 A measure that returns the linear force on the end-effector in X direction as by the O_F_ext_hat_K component of the robot state. More...
 
static Measure ForceY ()
 A measure that returns the linear force on the end-effector in Y direction as by the O_F_ext_hat_K component of the robot state. More...
 
static Measure ForceZ ()
 A measure that returns the linear force on the end-effector in Z direction as by the O_F_ext_hat_K component of the robot state. More...
 
static Measure RelTime ()
 A measure that returns the relative time since the start of the current motion. More...
 
static Measure AbsTime ()
 A measure that returns the absolute time since the start of the current chain of motions. The absolute time measures the time since the robot started moving, and is only reset if a motion expires without being replaced by a new motion. More...
 

Detailed Description

A measure on the robot state.

This class defines a measure on the robot state, which can be used to define a condition for a reaction in a motion. Measures support arithmetic operations (+, -, *, /, ^) and comparisons (==, !=, <, >, <=, >=) and can be combined to form more complex measures.

Constructor & Destructor Documentation

◆ Measure() [1/2]

franky::Measure::Measure ( Measure::MeasureFunc  measure_func,
std::string  repr = "NULL" 
)
explicit
Parameters
measure_funcA function that returns the value of the measure.
reprA string representation of the measure.

◆ Measure() [2/2]

franky::Measure::Measure ( double  constant)

Implicit constructor for constant measures.

Parameters
constantThe constant value of the measure.

Member Function Documentation

◆ AbsTime()

Measure franky::Measure::AbsTime ( )
static

A measure that returns the absolute time since the start of the current chain of motions. The absolute time measures the time since the robot started moving, and is only reset if a motion expires without being replaced by a new motion.

◆ ForceX()

Measure franky::Measure::ForceX ( )
static

A measure that returns the linear force on the end-effector in X direction as by the O_F_ext_hat_K component of the robot state.

◆ ForceY()

Measure franky::Measure::ForceY ( )
static

A measure that returns the linear force on the end-effector in Y direction as by the O_F_ext_hat_K component of the robot state.

◆ ForceZ()

Measure franky::Measure::ForceZ ( )
static

A measure that returns the linear force on the end-effector in Z direction as by the O_F_ext_hat_K component of the robot state.

◆ operator()()

double franky::Measure::operator() ( const franka::RobotState &  robot_state,
double  rel_time,
double  abs_time 
) const
inline

Get the value of the measure.

Parameters
robot_stateThe current robot state.
rel_timeThe time since the start of the current motion.
abs_timeThe 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.
Returns
The value of the measure.

◆ RelTime()

Measure franky::Measure::RelTime ( )
static

A measure that returns the relative time since the start of the current motion.

◆ repr()

std::string franky::Measure::repr ( ) const
inline

The string representation of the measure.


The documentation for this class was generated from the following files: