Frankx  0.2.0
A High-Level Motion API for Franka
Public Member Functions | Public Attributes | Static Public Attributes | List of all members
frankx::Robot Class Reference

#include <robot.hpp>

Inheritance diagram for frankx::Robot:

Public Member Functions

 Robot (std::string fci_ip, double dynamic_rel=1.0, bool repeat_on_error=true, bool stop_at_python_signal=true)
 Connects to a robot at the given FCI IP address. More...
 
void setDefaultBehavior ()
 
void setDynamicRel (double dynamic_rel)
 
bool hasErrors ()
 
bool recoverFromErrors ()
 
Affine currentPose (const Affine &frame=Affine())
 
std::array< double, 7 > currentJointPositions ()
 
Affine forwardKinematics (const std::array< double, 7 > &q)
 
std::array< double, 7 > inverseKinematics (const Affine &target, const std::array< double, 7 > &q0)
 
::franka::RobotState get_state ()
 
bool move (ImpedanceMotion &motion)
 
bool move (ImpedanceMotion &motion, MotionData &data)
 
bool move (const Affine &frame, ImpedanceMotion &motion)
 
bool move (const Affine &frame, ImpedanceMotion &motion, MotionData &data)
 
bool move (JointMotion motion)
 
bool move (JointMotion motion, MotionData &data)
 
bool move (PathMotion motion)
 
bool move (PathMotion motion, MotionData &data)
 
bool move (const Affine &frame, PathMotion motion)
 
bool move (const Affine &frame, PathMotion motion, MotionData &data)
 
bool move (WaypointMotion &motion)
 
bool move (WaypointMotion &motion, MotionData &data)
 
bool move (const Affine &frame, WaypointMotion &motion)
 
bool move (const Affine &frame, WaypointMotion &motion, MotionData &data)
 

Public Attributes

std::string fci_ip
 The robot's hostname / IP address. More...
 
double velocity_rel {1.0}
 
double acceleration_rel {1.0}
 
double jerk_rel {1.0}
 
franka::ControllerMode controller_mode {franka::ControllerMode::kJointImpedance}
 
bool repeat_on_error {true}
 Whether the robots try to continue an interrupted motion due to a libfranka position/velocity/acceleration discontinuity with reduced dynamics. More...
 
bool stop_at_python_signal {true}
 Whether the robot stops if a python error signal is detected. More...
 

Static Public Attributes

static constexpr double max_translation_velocity {1.7}
 
static constexpr double max_rotation_velocity {2.5}
 
static constexpr double max_elbow_velocity {2.175}
 
static constexpr double max_translation_acceleration {13.0}
 
static constexpr double max_rotation_acceleration {25.0}
 
static constexpr double max_elbow_acceleration {10.0}
 
static constexpr double max_translation_jerk {6500.0}
 
static constexpr double max_rotation_jerk {12500.0}
 
static constexpr double max_elbow_jerk {5000.0}
 
static constexpr std::array< double, 7 > max_joint_velocity {{2.175, 2.175, 2.175, 2.175, 2.610, 2.610, 2.610}}
 
static constexpr std::array< double, 7 > max_joint_acceleration {{15.0, 7.5, 10.0, 12.5, 15.0, 20.0, 20.0}}
 
static constexpr std::array< double, 7 > max_joint_jerk {{7500.0, 3750.0, 5000.0, 6250.0, 7500.0, 10000.0, 10000.0}}
 
static constexpr size_t degrees_of_freedoms {7}
 
static constexpr double control_rate {0.001}
 

Constructor & Destructor Documentation

◆ Robot()

frankx::Robot::Robot ( std::string  fci_ip,
double  dynamic_rel = 1.0,
bool  repeat_on_error = true,
bool  stop_at_python_signal = true 
)
explicit

Connects to a robot at the given FCI IP address.

Member Function Documentation

◆ currentJointPositions()

std::array< double, 7 > frankx::Robot::currentJointPositions ( )

◆ currentPose()

Affine frankx::Robot::currentPose ( const Affine frame = Affine())

◆ forwardKinematics()

Affine frankx::Robot::forwardKinematics ( const std::array< double, 7 > &  q)

◆ get_state()

franka::RobotState frankx::Robot::get_state ( )

◆ hasErrors()

bool frankx::Robot::hasErrors ( )

◆ inverseKinematics()

std::array< double, 7 > frankx::Robot::inverseKinematics ( const Affine target,
const std::array< double, 7 > &  q0 
)

◆ move() [1/14]

bool frankx::Robot::move ( const Affine frame,
ImpedanceMotion motion 
)

◆ move() [2/14]

bool frankx::Robot::move ( const Affine frame,
ImpedanceMotion motion,
MotionData data 
)

◆ move() [3/14]

bool frankx::Robot::move ( const Affine frame,
PathMotion  motion 
)

◆ move() [4/14]

bool frankx::Robot::move ( const Affine frame,
PathMotion  motion,
MotionData data 
)

◆ move() [5/14]

bool frankx::Robot::move ( const Affine frame,
WaypointMotion motion 
)

◆ move() [6/14]

bool frankx::Robot::move ( const Affine frame,
WaypointMotion motion,
MotionData data 
)

◆ move() [7/14]

bool frankx::Robot::move ( ImpedanceMotion motion)

◆ move() [8/14]

bool frankx::Robot::move ( ImpedanceMotion motion,
MotionData data 
)

◆ move() [9/14]

bool frankx::Robot::move ( JointMotion  motion)

◆ move() [10/14]

bool frankx::Robot::move ( JointMotion  motion,
MotionData data 
)

◆ move() [11/14]

bool frankx::Robot::move ( PathMotion  motion)

◆ move() [12/14]

bool frankx::Robot::move ( PathMotion  motion,
MotionData data 
)

◆ move() [13/14]

bool frankx::Robot::move ( WaypointMotion motion)

◆ move() [14/14]

bool frankx::Robot::move ( WaypointMotion motion,
MotionData data 
)

◆ recoverFromErrors()

bool frankx::Robot::recoverFromErrors ( )

◆ setDefaultBehavior()

void frankx::Robot::setDefaultBehavior ( )

◆ setDynamicRel()

void frankx::Robot::setDynamicRel ( double  dynamic_rel)

Member Data Documentation

◆ acceleration_rel

double frankx::Robot::acceleration_rel {1.0}

◆ control_rate

constexpr double frankx::Robot::control_rate {0.001}
staticconstexpr

◆ controller_mode

franka::ControllerMode frankx::Robot::controller_mode {franka::ControllerMode::kJointImpedance}

◆ degrees_of_freedoms

constexpr size_t frankx::Robot::degrees_of_freedoms {7}
staticconstexpr

◆ fci_ip

std::string frankx::Robot::fci_ip

The robot's hostname / IP address.

◆ jerk_rel

double frankx::Robot::jerk_rel {1.0}

◆ max_elbow_acceleration

constexpr double frankx::Robot::max_elbow_acceleration {10.0}
staticconstexpr

◆ max_elbow_jerk

constexpr double frankx::Robot::max_elbow_jerk {5000.0}
staticconstexpr

◆ max_elbow_velocity

constexpr double frankx::Robot::max_elbow_velocity {2.175}
staticconstexpr

◆ max_joint_acceleration

constexpr std::array<double, 7> frankx::Robot::max_joint_acceleration {{15.0, 7.5, 10.0, 12.5, 15.0, 20.0, 20.0}}
staticconstexpr

◆ max_joint_jerk

constexpr std::array<double, 7> frankx::Robot::max_joint_jerk {{7500.0, 3750.0, 5000.0, 6250.0, 7500.0, 10000.0, 10000.0}}
staticconstexpr

◆ max_joint_velocity

constexpr std::array<double, 7> frankx::Robot::max_joint_velocity {{2.175, 2.175, 2.175, 2.175, 2.610, 2.610, 2.610}}
staticconstexpr

◆ max_rotation_acceleration

constexpr double frankx::Robot::max_rotation_acceleration {25.0}
staticconstexpr

◆ max_rotation_jerk

constexpr double frankx::Robot::max_rotation_jerk {12500.0}
staticconstexpr

◆ max_rotation_velocity

constexpr double frankx::Robot::max_rotation_velocity {2.5}
staticconstexpr

◆ max_translation_acceleration

constexpr double frankx::Robot::max_translation_acceleration {13.0}
staticconstexpr

◆ max_translation_jerk

constexpr double frankx::Robot::max_translation_jerk {6500.0}
staticconstexpr

◆ max_translation_velocity

constexpr double frankx::Robot::max_translation_velocity {1.7}
staticconstexpr

◆ repeat_on_error

bool frankx::Robot::repeat_on_error {true}

Whether the robots try to continue an interrupted motion due to a libfranka position/velocity/acceleration discontinuity with reduced dynamics.

◆ stop_at_python_signal

bool frankx::Robot::stop_at_python_signal {true}

Whether the robot stops if a python error signal is detected.

◆ velocity_rel

double frankx::Robot::velocity_rel {1.0}

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