diff --git a/Logo_FRANKA_ROBOTICS_dark.png b/Logo_FRANKA_ROBOTICS_dark.png new file mode 100644 index 00000000..b38bb6b4 Binary files /dev/null and b/Logo_FRANKA_ROBOTICS_dark.png differ diff --git a/active__control_8h.html b/active__control_8h.html new file mode 100644 index 00000000..a20f74a0 --- /dev/null +++ b/active__control_8h.html @@ -0,0 +1,153 @@ + + +
+ + + + ++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Implements the ActiveControlBase abstract class. +More...
+Go to the source code of this file.
++Classes | |
class | franka::ActiveControl |
Documented in ActiveControlBase. More... | |
Implements the ActiveControlBase abstract class.
+Contains the franka::ActiveControl
, franka::ActiveTorqueControl
and franka::ActiveMotionGenerator
type.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Abstract interface class as the base of the active controllers. +More...
+#include <franka/control_types.h>
#include <franka/exception.h>
#include <franka/robot_state.h>
#include <memory>
#include <optional>
#include <utility>
Go to the source code of this file.
++Classes | |
class | franka::ActiveControlBase |
Allows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot. More... | |
Abstract interface class as the base of the active controllers.
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains the franka::ActiveMotionGenerator
type.
+More...
#include "active_control.h"
Go to the source code of this file.
++Classes | |
class | franka::ActiveMotionGenerator< MotionGeneratorType > |
Allows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot. More... | |
Contains the franka::ActiveMotionGenerator
type.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains the franka::ActiveTorqueControl
type.
+More...
#include "active_control.h"
Go to the source code of this file.
++Classes | |
class | franka::ActiveTorqueControl |
Allows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot. More... | |
Contains the franka::ActiveTorqueControl
type.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
▼Nfranka | |
CActiveControl | Documented in ActiveControlBase |
CActiveControlBase | Allows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot |
CActiveMotionGenerator | Allows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot |
CActiveTorqueControl | Allows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot |
CFinishable | Helper type for control and motion generation loops |
CTorques | Stores joint-level torque commands without gravity and friction |
CJointPositions | Stores values for joint position motion generation |
CJointVelocities | Stores values for joint velocity motion generation |
CCartesianPose | Stores values for Cartesian pose motion generation |
CCartesianVelocities | Stores values for Cartesian velocity motion generation |
CDuration | Represents a duration with millisecond resolution |
CErrors | Enumerates errors that can occur while controlling a franka::Robot |
CException | Base class for all exceptions used by libfranka |
CModelException | ModelException is thrown if an error occurs when loading the model library |
CNetworkException | NetworkException is thrown if a connection to the robot cannot be established, or when a timeout occurs |
CProtocolException | ProtocolException is thrown if the robot returns an incorrect message |
CIncompatibleVersionException | IncompatibleVersionException is thrown if the robot does not support this version of libfranka |
CControlException | ControlException is thrown if an error occurs during motion generation or torque control |
CCommandException | CommandException is thrown if an error occurs during command execution |
CRealtimeException | RealtimeException is thrown if realtime priority cannot be set |
CInvalidOperationException | InvalidOperationException is thrown if an operation cannot be performed |
CGripper | Maintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands |
CGripperState | Describes the gripper state |
CRobotCommand | Command sent to the robot |
CRecord | One row of the log contains a robot command of timestamp n and a corresponding robot state of timestamp n+1 |
CModel | Calculates poses of joints and dynamic properties of the robot |
CRobot | Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot |
CRobotModel | Implements RobotModelBase using Pinocchio |
CRobotState | Describes the robot state |
CVacuumGripper | Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state, and allows the execution of commands |
CVacuumGripperState | Describes the vacuum gripper state |
CMotionGenerator | An example showing how to generate a joint pose motion to a goal position |
CRobotModelBase | Robot dynamic parameters computed from the URDF model with Pinocchio |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing a simple cartesian impedance controller without inertia shaping that renders a spring damper system where the equilibrium is the initial configuration.After starting the controller try to push the robot around and try different stiffness levels.
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for MotionGenerator, including all inherited members.
+MotionGenerator(double speed_factor, const std::array< double, 7 > q_goal) | MotionGenerator | |
operator()(const franka::RobotState &robot_state, franka::Duration period) | MotionGenerator |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to generate a joint pose motion to a goal position. + More...
+ +#include <examples_common.h>
+Public Member Functions | |
MotionGenerator (double speed_factor, const std::array< double, 7 > q_goal) | |
Creates a new MotionGenerator instance for a target q. More... | |
franka::JointPositions | operator() (const franka::RobotState &robot_state, franka::Duration period) |
Sends joint position calculations. More... | |
An example showing how to generate a joint pose motion to a goal position.
+Adapted from: Wisama Khalil and Etienne Dombre. 2002. Modeling, Identification and Control of Robots (Kogan Page Science Paper edition).
+MotionGenerator::MotionGenerator | +( | +double | +speed_factor, | +
+ | + | const std::array< double, 7 > | +q_goal | +
+ | ) | ++ |
Creates a new MotionGenerator instance for a target q.
+[in] | speed_factor | General speed factor in range [0, 1]. |
[in] | q_goal | Target joint positions. |
franka::JointPositions MotionGenerator::operator() | +( | +const franka::RobotState & | +robot_state, | +
+ | + | franka::Duration | +period | +
+ | ) | ++ |
Sends joint position calculations.
+[in] | robot_state | Current state of the robot. |
[in] | period | Duration of execution. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for RobotModelBase, including all inherited members.
+coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne)=0 | RobotModelBase | pure virtual |
gravity(const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne)=0 | RobotModelBase | pure virtual |
mass(const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne)=0 | RobotModelBase | pure virtual |
~RobotModelBase()=default (defined in RobotModelBase) | RobotModelBase | virtual |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Robot dynamic parameters computed from the URDF model with Pinocchio. + More...
+ +#include <robot_model_base.h>
+Public Member Functions | |
virtual void | coriolis (const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne)=0 |
Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\). More... | |
virtual void | gravity (const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne)=0 |
Calculates the gravity vector. More... | |
virtual void | mass (const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne)=0 |
Calculates the 7x7 mass matrix. More... | |
Robot dynamic parameters computed from the URDF model with Pinocchio.
+
+
|
+ +pure virtual | +
Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).
+[in] | q | Joint position. |
[in] | dq | Joint velocity. |
[in] | i_total | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\). |
[in] | m_total | Weight of the attached total load including end effector. Unit: \([kg]\). |
[in] | f_x_ctotal | Translation from flange to center of mass of the attached total load. Unit: \([m]\). |
[out] | c_ne | Coriolis force vector. Unit: \([Nm]\). |
Implemented in franka::RobotModel.
+ +
+
|
+ +pure virtual | +
Calculates the gravity vector.
+Unit: \([Nm]\).
+[in] | q | Joint position. |
[in] | gravity_earth | Earth's gravity vector. Unit: \(\frac{m}{s^2}\). |
[in] | m_total | Weight of the attached total load including end effector. Unit: \([kg]\). |
[in] | f_x_Ctotal | Translation from flange to center of mass of the attached total load. |
[out] | g_ne | Gravity vector. Unit: \([Nm]\). |
Implemented in franka::RobotModel.
+ +
+
|
+ +pure virtual | +
Calculates the 7x7 mass matrix.
+Unit: \([kg \times m^2]\).
+[in] | q | Joint position. |
[in] | i_total | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\). |
[in] | m_total | Weight of the attached total load including end effector. Unit: \([kg]\). |
[in] | f_x_ctotal | Translation from flange to center of mass of the attached total load. Unit: \([m]\). |
[out] | m_ne | Vectorized 7x7 mass matrix, column-major. |
Implemented in franka::RobotModel.
+ ++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::ActiveControl, including all inherited members.
+ActiveControl(std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock) | franka::ActiveControl | protected |
ActiveControlBase()=default (defined in franka::ActiveControlBase) | franka::ActiveControlBase | protected |
control_finished | franka::ActiveControl | protected |
control_lock | franka::ActiveControl | protected |
last_read_access | franka::ActiveControl | protected |
motion_id | franka::ActiveControl | protected |
readOnce() override | franka::ActiveControl | virtual |
robot_impl | franka::ActiveControl | protected |
writeOnce(const Torques &) override | franka::ActiveControl | inlinevirtual |
writeOnce(const JointPositions &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
writeOnce(const JointVelocities &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
writeOnce(const CartesianPose &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
writeOnce(const CartesianVelocities &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
writeOnce(const JointPositions &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
writeOnce(const JointVelocities &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
writeOnce(const CartesianPose &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
writeOnce(const CartesianVelocities &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
~ActiveControl() override (defined in franka::ActiveControl) | franka::ActiveControl | |
~ActiveControlBase()=default (defined in franka::ActiveControlBase) | franka::ActiveControlBase | virtual |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Documented in ActiveControlBase. + More...
+ +#include <active_control.h>
+Public Member Functions | |
std::pair< RobotState, Duration > | readOnce () override |
Waits for a robot state update and returns it. More... | |
void | writeOnce (const Torques &) override |
Updates torque commands of an active control. More... | |
void | writeOnce (const JointPositions &, const std::optional< const Torques > &) override |
Updates the joint position and torque commands of an active control. More... | |
void | writeOnce (const JointVelocities &, const std::optional< const Torques > &) override |
Updates the joint velocity and torque commands of an active control. More... | |
void | writeOnce (const CartesianPose &, const std::optional< const Torques > &) override |
Updates the cartesian position and torque commands of an active control. More... | |
void | writeOnce (const CartesianVelocities &, const std::optional< const Torques > &) override |
Updates the cartesian velocity and torque commands of an active control. More... | |
void | writeOnce (const JointPositions &motion_generator_input) override |
Updates the joint position commands of an active control, with internal controller. More... | |
void | writeOnce (const JointVelocities &motion_generator_input) override |
Updates the joint velocity commands of an active control, with internal controller. More... | |
void | writeOnce (const CartesianPose &motion_generator_input) override |
Updates the cartesian pose commands of an active control, with internal controller. More... | |
void | writeOnce (const CartesianVelocities &motion_generator_input) override |
Updates the cartesian velocity commands of an active control, with internal controller. More... | |
+Protected Member Functions | |
ActiveControl (std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock) | |
Construct a new ActiveControl object. More... | |
+Protected Attributes | |
+std::shared_ptr< Robot::Impl > | robot_impl |
shared pointer to Robot::Impl instance for read and write accesses | |
+uint32_t | motion_id |
motion id of running motion | |
+std::unique_lock< std::mutex > | control_lock |
control-lock preventing parallel control processes | |
+bool | control_finished |
flag indicating if control process is finished | |
+std::optional< Duration > | last_read_access |
duration to last read access | |
Documented in ActiveControlBase.
+
+
|
+ +protected | +
Construct a new ActiveControl object.
+ + +
+
|
+ +overridevirtual | +
Waits for a robot state update and returns it.
+NetworkException | if the connection is lost, e.g. after a timeout. |
ProtocolException | if robot returns an unexpected message. |
ControlException | if robot is in an error state. |
Implements franka::ActiveControlBase.
+ +
+
|
+ +inlineoverridevirtual | +
Updates the cartesian position and torque commands of an active control.
+hint: implemented in ActiveMotionGenerator<CartesianPose>
+ +Implements franka::ActiveControlBase.
+ +
+
|
+ +inlineoverridevirtual | +
Updates the cartesian pose commands of an active control, with internal controller.
+motion_generator_input | the new motion generator input |
Implements franka::ActiveControlBase.
+ +
+
|
+ +inlineoverridevirtual | +
Updates the cartesian velocity and torque commands of an active control.
+hint: implemented in ActiveMotionGenerator<CartesianVelocities>
+ +Implements franka::ActiveControlBase.
+ +
+
|
+ +inlineoverridevirtual | +
Updates the cartesian velocity commands of an active control, with internal controller.
+motion_generator_input | the new motion generator input |
Implements franka::ActiveControlBase.
+ +
+
|
+ +inlineoverridevirtual | +
Updates the joint position and torque commands of an active control.
+hint: implemented in ActiveMotionGenerator<JointPositions>
+ +Implements franka::ActiveControlBase.
+ +
+
|
+ +inlineoverridevirtual | +
Updates the joint position commands of an active control, with internal controller.
+motion_generator_input | the new motion generator input |
Implements franka::ActiveControlBase.
+ +
+
|
+ +inlineoverridevirtual | +
Updates the joint velocity and torque commands of an active control.
+hint: implemented in ActiveMotionGenerator<JointVelocities>
+ +Implements franka::ActiveControlBase.
+ +
+
|
+ +inlineoverridevirtual | +
Updates the joint velocity commands of an active control, with internal controller.
+motion_generator_input | the new motion generator input |
Implements franka::ActiveControlBase.
+ +
+
|
+ +inlineoverridevirtual | +
Updates torque commands of an active control.
+hint: implemented in ActiveTorqueControl
+ +Implements franka::ActiveControlBase.
+ +Reimplemented in franka::ActiveTorqueControl.
+ ++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::ActiveControlBase, including all inherited members.
+ActiveControlBase()=default (defined in franka::ActiveControlBase) | franka::ActiveControlBase | protected |
readOnce()=0 | franka::ActiveControlBase | pure virtual |
writeOnce(const Torques &)=0 | franka::ActiveControlBase | pure virtual |
writeOnce(const JointPositions &, const std::optional< const Torques > &)=0 | franka::ActiveControlBase | pure virtual |
writeOnce(const JointVelocities &, const std::optional< const Torques > &)=0 | franka::ActiveControlBase | pure virtual |
writeOnce(const CartesianPose &, const std::optional< const Torques > &)=0 | franka::ActiveControlBase | pure virtual |
writeOnce(const CartesianVelocities &, const std::optional< const Torques > &)=0 | franka::ActiveControlBase | pure virtual |
writeOnce(const JointPositions &motion_generator_input)=0 | franka::ActiveControlBase | pure virtual |
writeOnce(const JointVelocities &motion_generator_input)=0 | franka::ActiveControlBase | pure virtual |
writeOnce(const CartesianPose &motion_generator_input)=0 | franka::ActiveControlBase | pure virtual |
writeOnce(const CartesianVelocities &motion_generator_input)=0 | franka::ActiveControlBase | pure virtual |
~ActiveControlBase()=default (defined in franka::ActiveControlBase) | franka::ActiveControlBase | virtual |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Allows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot. + More...
+ +#include <active_control_base.h>
+Public Member Functions | |
virtual std::pair< RobotState, Duration > | readOnce ()=0 |
Waits for a robot state update and returns it. More... | |
virtual void | writeOnce (const Torques &)=0 |
Updates torque commands of an active control. More... | |
virtual void | writeOnce (const JointPositions &, const std::optional< const Torques > &)=0 |
Updates the joint position and torque commands of an active control. More... | |
virtual void | writeOnce (const JointVelocities &, const std::optional< const Torques > &)=0 |
Updates the joint velocity and torque commands of an active control. More... | |
virtual void | writeOnce (const CartesianPose &, const std::optional< const Torques > &)=0 |
Updates the cartesian position and torque commands of an active control. More... | |
virtual void | writeOnce (const CartesianVelocities &, const std::optional< const Torques > &)=0 |
Updates the cartesian velocity and torque commands of an active control. More... | |
virtual void | writeOnce (const JointPositions &motion_generator_input)=0 |
Updates the joint position commands of an active control, with internal controller. More... | |
virtual void | writeOnce (const JointVelocities &motion_generator_input)=0 |
Updates the joint velocity commands of an active control, with internal controller. More... | |
virtual void | writeOnce (const CartesianPose &motion_generator_input)=0 |
Updates the cartesian pose commands of an active control, with internal controller. More... | |
virtual void | writeOnce (const CartesianVelocities &motion_generator_input)=0 |
Updates the cartesian velocity commands of an active control, with internal controller. More... | |
Allows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot.
+hint: To create an ActiveControlBase, see franka::ActiveTorqueControl or franka::ActiveMotionGenerator
+
+
|
+ +pure virtual | +
Waits for a robot state update and returns it.
+NetworkException | if the connection is lost, e.g. after a timeout. |
ProtocolException | if robot returns an unexpected message. |
ControlException | if robot is in an error state. |
Implemented in franka::ActiveControl.
+ +
+
|
+ +pure virtual | +
Updates the cartesian position and torque commands of an active control.
+hint: implemented in ActiveMotionGenerator<CartesianPose>
+ +Implemented in franka::ActiveControl.
+ +
+
|
+ +pure virtual | +
Updates the cartesian pose commands of an active control, with internal controller.
+motion_generator_input | the new motion generator input |
Implemented in franka::ActiveControl.
+ +
+
|
+ +pure virtual | +
Updates the cartesian velocity and torque commands of an active control.
+hint: implemented in ActiveMotionGenerator<CartesianVelocities>
+ +Implemented in franka::ActiveControl.
+ +
+
|
+ +pure virtual | +
Updates the cartesian velocity commands of an active control, with internal controller.
+motion_generator_input | the new motion generator input |
Implemented in franka::ActiveControl.
+ +
+
|
+ +pure virtual | +
Updates the joint position and torque commands of an active control.
+hint: implemented in ActiveMotionGenerator<JointPositions>
+ +Implemented in franka::ActiveControl.
+ +
+
|
+ +pure virtual | +
Updates the joint position commands of an active control, with internal controller.
+motion_generator_input | the new motion generator input |
Implemented in franka::ActiveControl.
+ +
+
|
+ +pure virtual | +
Updates the joint velocity and torque commands of an active control.
+hint: implemented in ActiveMotionGenerator<JointVelocities>
+ +Implemented in franka::ActiveControl.
+ +
+
|
+ +pure virtual | +
Updates the joint velocity commands of an active control, with internal controller.
+motion_generator_input | the new motion generator input |
Implemented in franka::ActiveControl.
+ +
+
|
+ +pure virtual | +
Updates torque commands of an active control.
+hint: implemented in ActiveTorqueControl
+ +Implemented in franka::ActiveTorqueControl, and franka::ActiveControl.
+ ++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::ActiveMotionGenerator< MotionGeneratorType >, including all inherited members.
+ActiveControl(std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock) | franka::ActiveControl | protected |
ActiveControlBase()=default (defined in franka::ActiveControlBase) | franka::ActiveControlBase | protected |
control_finished | franka::ActiveControl | protected |
control_lock | franka::ActiveControl | protected |
last_read_access | franka::ActiveControl | protected |
motion_id | franka::ActiveControl | protected |
readOnce() override | franka::ActiveControl | virtual |
Robot class | franka::ActiveMotionGenerator< MotionGeneratorType > | friend |
robot_impl | franka::ActiveControl | protected |
writeOnce(const MotionGeneratorType &motion_generator_input, const std::optional< const Torques > &control_input) override | franka::ActiveMotionGenerator< MotionGeneratorType > | |
franka::ActiveControl::writeOnce(const Torques &) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const JointPositions &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const JointVelocities &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const CartesianPose &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const CartesianVelocities &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const JointPositions &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const JointVelocities &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const CartesianPose &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const CartesianVelocities &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
~ActiveControl() override (defined in franka::ActiveControl) | franka::ActiveControl | |
~ActiveControlBase()=default (defined in franka::ActiveControlBase) | franka::ActiveControlBase | virtual |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Allows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot. + More...
+ +#include <active_motion_generator.h>
+Public Member Functions | |
void | writeOnce (const MotionGeneratorType &motion_generator_input, const std::optional< const Torques > &control_input) override |
Updates the motion generator commands of an active control. More... | |
Public Member Functions inherited from franka::ActiveControl | |
std::pair< RobotState, Duration > | readOnce () override |
Waits for a robot state update and returns it. More... | |
void | writeOnce (const Torques &) override |
Updates torque commands of an active control. More... | |
void | writeOnce (const JointPositions &, const std::optional< const Torques > &) override |
Updates the joint position and torque commands of an active control. More... | |
void | writeOnce (const JointVelocities &, const std::optional< const Torques > &) override |
Updates the joint velocity and torque commands of an active control. More... | |
void | writeOnce (const CartesianPose &, const std::optional< const Torques > &) override |
Updates the cartesian position and torque commands of an active control. More... | |
void | writeOnce (const CartesianVelocities &, const std::optional< const Torques > &) override |
Updates the cartesian velocity and torque commands of an active control. More... | |
void | writeOnce (const JointPositions &motion_generator_input) override |
Updates the joint position commands of an active control, with internal controller. More... | |
void | writeOnce (const JointVelocities &motion_generator_input) override |
Updates the joint velocity commands of an active control, with internal controller. More... | |
void | writeOnce (const CartesianPose &motion_generator_input) override |
Updates the cartesian pose commands of an active control, with internal controller. More... | |
void | writeOnce (const CartesianVelocities &motion_generator_input) override |
Updates the cartesian velocity commands of an active control, with internal controller. More... | |
+Friends | |
+class | Robot |
franka::Robot as friend to allow construction of ActiveMotionGenerator<MotionGeneratorType> in start<MotionGeneratorType>Control methods | |
+Additional Inherited Members | |
Protected Member Functions inherited from franka::ActiveControl | |
ActiveControl (std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock) | |
Construct a new ActiveControl object. More... | |
Protected Attributes inherited from franka::ActiveControl | |
+std::shared_ptr< Robot::Impl > | robot_impl |
shared pointer to Robot::Impl instance for read and write accesses | |
+uint32_t | motion_id |
motion id of running motion | |
+std::unique_lock< std::mutex > | control_lock |
control-lock preventing parallel control processes | |
+bool | control_finished |
flag indicating if control process is finished | |
+std::optional< Duration > | last_read_access |
duration to last read access | |
Allows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot.
+hint: To create an ActiveMotionGenerator, see franka::Robot
+
+
|
+ +override | +
Updates the motion generator commands of an active control.
+motion_generator_input | the new motion generator input |
control_input | optional: the external control input for each joint, if an external controller is used |
ControlException | if an error related to torque control or motion generation occurred, or the motion was already finished. |
NetworkException | if the connection is lost, e.g. after a timeout. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::ActiveTorqueControl, including all inherited members.
+ActiveControl(std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock) | franka::ActiveControl | protected |
ActiveControlBase()=default (defined in franka::ActiveControlBase) | franka::ActiveControlBase | protected |
control_finished | franka::ActiveControl | protected |
control_lock | franka::ActiveControl | protected |
last_read_access | franka::ActiveControl | protected |
motion_id | franka::ActiveControl | protected |
readOnce() override | franka::ActiveControl | virtual |
Robot class | franka::ActiveTorqueControl | friend |
robot_impl | franka::ActiveControl | protected |
writeOnce(const Torques &control_input) override | franka::ActiveTorqueControl | virtual |
franka::ActiveControl::writeOnce(const JointPositions &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const JointVelocities &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const CartesianPose &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const CartesianVelocities &, const std::optional< const Torques > &) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const JointPositions &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const JointVelocities &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const CartesianPose &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
franka::ActiveControl::writeOnce(const CartesianVelocities &motion_generator_input) override | franka::ActiveControl | inlinevirtual |
~ActiveControl() override (defined in franka::ActiveControl) | franka::ActiveControl | |
~ActiveControlBase()=default (defined in franka::ActiveControlBase) | franka::ActiveControlBase | virtual |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Allows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot. + More...
+ +#include <active_torque_control.h>
+Public Member Functions | |
void | writeOnce (const Torques &control_input) override |
Updates the joint-level based torque commands of an active joint effort control. More... | |
Public Member Functions inherited from franka::ActiveControl | |
std::pair< RobotState, Duration > | readOnce () override |
Waits for a robot state update and returns it. More... | |
void | writeOnce (const JointPositions &, const std::optional< const Torques > &) override |
Updates the joint position and torque commands of an active control. More... | |
void | writeOnce (const JointVelocities &, const std::optional< const Torques > &) override |
Updates the joint velocity and torque commands of an active control. More... | |
void | writeOnce (const CartesianPose &, const std::optional< const Torques > &) override |
Updates the cartesian position and torque commands of an active control. More... | |
void | writeOnce (const CartesianVelocities &, const std::optional< const Torques > &) override |
Updates the cartesian velocity and torque commands of an active control. More... | |
void | writeOnce (const JointPositions &motion_generator_input) override |
Updates the joint position commands of an active control, with internal controller. More... | |
void | writeOnce (const JointVelocities &motion_generator_input) override |
Updates the joint velocity commands of an active control, with internal controller. More... | |
void | writeOnce (const CartesianPose &motion_generator_input) override |
Updates the cartesian pose commands of an active control, with internal controller. More... | |
void | writeOnce (const CartesianVelocities &motion_generator_input) override |
Updates the cartesian velocity commands of an active control, with internal controller. More... | |
+Friends | |
+class | Robot |
franka::Robot as friend to allow construction of ActiveTorqueControl in startTorqueControl methods | |
+Additional Inherited Members | |
Protected Member Functions inherited from franka::ActiveControl | |
ActiveControl (std::shared_ptr< Robot::Impl > robot_impl, uint32_t motion_id, std::unique_lock< std::mutex > control_lock) | |
Construct a new ActiveControl object. More... | |
Protected Attributes inherited from franka::ActiveControl | |
+std::shared_ptr< Robot::Impl > | robot_impl |
shared pointer to Robot::Impl instance for read and write accesses | |
+uint32_t | motion_id |
motion id of running motion | |
+std::unique_lock< std::mutex > | control_lock |
control-lock preventing parallel control processes | |
+bool | control_finished |
flag indicating if control process is finished | |
+std::optional< Duration > | last_read_access |
duration to last read access | |
Allows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot.
+hint: To create an ActiveTorqueControl, see franka::Robot
+
+
|
+ +overridevirtual | +
Updates the joint-level based torque commands of an active joint effort control.
+control_input | the new joint-level based torques |
ControlException | if an error related to torque control or motion generation occurred, or the motion was already finished. |
NetworkException | if the connection is lost, e.g. after a timeout. |
Reimplemented from franka::ActiveControl.
+ ++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::CartesianPose, including all inherited members.
+CartesianPose(const std::array< double, 16 > &cartesian_pose) noexcept | franka::CartesianPose | |
CartesianPose(const std::array< double, 16 > &cartesian_pose, const std::array< double, 2 > &elbow) noexcept | franka::CartesianPose | |
CartesianPose(std::initializer_list< double > cartesian_pose) | franka::CartesianPose | |
CartesianPose(std::initializer_list< double > cartesian_pose, std::initializer_list< double > elbow) | franka::CartesianPose | |
elbow | franka::CartesianPose | |
hasElbow() const noexcept | franka::CartesianPose | |
motion_finished | franka::Finishable | |
O_T_EE | franka::CartesianPose |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Stores values for Cartesian pose motion generation. + More...
+ +#include <control_types.h>
+Public Member Functions | |
CartesianPose (const std::array< double, 16 > &cartesian_pose) noexcept | |
Creates a new CartesianPose instance. More... | |
CartesianPose (const std::array< double, 16 > &cartesian_pose, const std::array< double, 2 > &elbow) noexcept | |
Creates a new CartesianPose instance. More... | |
CartesianPose (std::initializer_list< double > cartesian_pose) | |
Creates a new CartesianPose instance. More... | |
CartesianPose (std::initializer_list< double > cartesian_pose, std::initializer_list< double > elbow) | |
Creates a new CartesianPose instance. More... | |
bool | hasElbow () const noexcept |
Determines whether there is a stored elbow configuration. More... | |
+Public Attributes | |
std::array< double, 16 > | O_T_EE {} |
Homogeneous transformation \(^O{\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). More... | |
std::array< double, 2 > | elbow {} |
Elbow configuration. More... | |
Public Attributes inherited from franka::Finishable | |
+bool | motion_finished = false |
Determines whether to finish a currently running motion. | |
Stores values for Cartesian pose motion generation.
+ +
+
|
+ +noexcept | +
Creates a new CartesianPose instance.
+[in] | cartesian_pose | Desired vectorized homogeneous transformation matrix \(^O {\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). Equivalently, it is the desired end effector pose in base frame. |
+
|
+ +noexcept | +
Creates a new CartesianPose instance.
+[in] | cartesian_pose | Desired vectorized homogeneous transformation matrix \(^O {\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). Equivalently, it is the desired end effector pose in base frame. |
[in] | elbow | Elbow configuration (see elbow member for more details). |
franka::CartesianPose::CartesianPose | +( | +std::initializer_list< double > | +cartesian_pose | ) | ++ |
Creates a new CartesianPose instance.
+[in] | cartesian_pose | Desired vectorized homogeneous transformation matrix \(^O {\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). Equivalently, it is the desired end effector pose in base frame. |
std::invalid_argument | if the given initializer list has an invalid number of arguments. |
franka::CartesianPose::CartesianPose | +( | +std::initializer_list< double > | +cartesian_pose, | +
+ | + | std::initializer_list< double > | +elbow | +
+ | ) | ++ |
Creates a new CartesianPose instance.
+[in] | cartesian_pose | Desired vectorized homogeneous transformation matrix \(^O {\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\). Equivalently, it is the desired end effector pose in base frame. |
[in] | elbow | Elbow configuration (see elbow member for more details). |
std::invalid_argument | if a given initializer list has an invalid number of arguments. |
+
|
+ +noexcept | +
Determines whether there is a stored elbow configuration.
+std::array<double, 2> franka::CartesianPose::elbow {} | +
Elbow configuration.
+The values of the array are:
with \(q_{elbow-flip}\) as specified in the robot interface specification page in the FCI Documentation.
+ +std::array<double, 16> franka::CartesianPose::O_T_EE {} | +
Homogeneous transformation \(^O{\mathbf{T}_{EE}}_{d}\), column major, that transforms from the end effector frame \(EE\) to base frame \(O\).
+Equivalently, it is the desired end effector pose in base frame.
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::CartesianVelocities, including all inherited members.
+CartesianVelocities(const std::array< double, 6 > &cartesian_velocities) noexcept | franka::CartesianVelocities | |
CartesianVelocities(const std::array< double, 6 > &cartesian_velocities, const std::array< double, 2 > &elbow) noexcept | franka::CartesianVelocities | |
CartesianVelocities(std::initializer_list< double > cartesian_velocities) | franka::CartesianVelocities | |
CartesianVelocities(std::initializer_list< double > cartesian_velocities, std::initializer_list< double > elbow) | franka::CartesianVelocities | |
elbow | franka::CartesianVelocities | |
hasElbow() const noexcept | franka::CartesianVelocities | |
motion_finished | franka::Finishable | |
O_dP_EE | franka::CartesianVelocities |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Stores values for Cartesian velocity motion generation. + More...
+ +#include <control_types.h>
+Public Member Functions | |
CartesianVelocities (const std::array< double, 6 > &cartesian_velocities) noexcept | |
Creates a new CartesianVelocities instance. More... | |
CartesianVelocities (const std::array< double, 6 > &cartesian_velocities, const std::array< double, 2 > &elbow) noexcept | |
Creates a new CartesianVelocities instance. More... | |
CartesianVelocities (std::initializer_list< double > cartesian_velocities) | |
Creates a new CartesianVelocities instance. More... | |
CartesianVelocities (std::initializer_list< double > cartesian_velocities, std::initializer_list< double > elbow) | |
Creates a new CartesianVelocities instance. More... | |
bool | hasElbow () const noexcept |
Determines whether there is a stored elbow configuration. More... | |
+Public Attributes | |
+std::array< double, 6 > | O_dP_EE {} |
Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\). | |
std::array< double, 2 > | elbow {} |
Elbow configuration. More... | |
Public Attributes inherited from franka::Finishable | |
+bool | motion_finished = false |
Determines whether to finish a currently running motion. | |
Stores values for Cartesian velocity motion generation.
+The Cartesian velocity of the end-effector is expressed in a frame parallel to the fixed/base frame, whose origin is the same as the end-effector frame. Rotations are thus expressed around the end-effector and parallel to the base frame.
+ +
+
|
+ +noexcept | +
Creates a new CartesianVelocities instance.
+[in] | cartesian_velocities | Desired Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\). |
+
|
+ +noexcept | +
Creates a new CartesianVelocities instance.
+[in] | cartesian_velocities | Desired Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\). |
[in] | elbow | Elbow configuration (see elbow member for more details). |
franka::CartesianVelocities::CartesianVelocities | +( | +std::initializer_list< double > | +cartesian_velocities | ) | ++ |
Creates a new CartesianVelocities instance.
+[in] | cartesian_velocities | Desired Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\). |
std::invalid_argument | if the given initializer list has an invalid number of arguments. |
franka::CartesianVelocities::CartesianVelocities | +( | +std::initializer_list< double > | +cartesian_velocities, | +
+ | + | std::initializer_list< double > | +elbow | +
+ | ) | ++ |
Creates a new CartesianVelocities instance.
+[in] | cartesian_velocities | Desired Cartesian velocity with respect to the base frame O with \((\dot x, \dot y, \dot z)\) in \([m/s]\) and \((\omega_x, \omega_y, \omega_z)\) in \([rad/s]\). |
[in] | elbow | Elbow configuration (see elbow member for more details). |
std::invalid_argument | if a given initializer list has an invalid number of arguments. |
+
|
+ +noexcept | +
Determines whether there is a stored elbow configuration.
+std::array<double, 2> franka::CartesianVelocities::elbow {} | +
Elbow configuration.
+The values of the array are:
with \(\alpha = -0.467002423653011\) \(rad\)
+ ++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::Duration, including all inherited members.
+Duration() noexcept | franka::Duration | |
Duration(uint64_t milliseconds) noexcept | franka::Duration | explicit |
Duration(std::chrono::duration< uint64_t, std::milli > duration) noexcept | franka::Duration | |
Duration(const Duration &)=default | franka::Duration | |
operator std::chrono::duration< uint64_t, std::milli >() const noexcept | franka::Duration | |
operator!=(const Duration &rhs) const noexcept | franka::Duration | |
operator%(const Duration &rhs) const noexcept | franka::Duration | |
operator%(uint64_t rhs) const noexcept | franka::Duration | |
operator%=(const Duration &rhs) noexcept | franka::Duration | |
operator%=(uint64_t rhs) noexcept | franka::Duration | |
operator*(uint64_t rhs) const noexcept | franka::Duration | |
operator*=(uint64_t rhs) noexcept | franka::Duration | |
operator+(const Duration &rhs) const noexcept | franka::Duration | |
operator+=(const Duration &rhs) noexcept | franka::Duration | |
operator-(const Duration &rhs) const noexcept | franka::Duration | |
operator-=(const Duration &rhs) noexcept | franka::Duration | |
operator/(const Duration &rhs) const noexcept | franka::Duration | |
operator/(uint64_t rhs) const noexcept | franka::Duration | |
operator/=(uint64_t rhs) noexcept | franka::Duration | |
operator<(const Duration &rhs) const noexcept | franka::Duration | |
operator<=(const Duration &rhs) const noexcept | franka::Duration | |
operator=(const Duration &)=default | franka::Duration | |
operator==(const Duration &rhs) const noexcept | franka::Duration | |
operator>(const Duration &rhs) const noexcept | franka::Duration | |
operator>=(const Duration &rhs) const noexcept | franka::Duration | |
toMSec() const noexcept | franka::Duration | |
toSec() const noexcept | franka::Duration |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Represents a duration with millisecond resolution. + More...
+ +#include <duration.h>
+Public Member Functions | |
+ | Duration () noexcept |
Creates a new Duration instance with zero milliseconds. | |
Duration (uint64_t milliseconds) noexcept | |
Creates a new Duration instance from the given number of milliseconds. More... | |
Duration (std::chrono::duration< uint64_t, std::milli > duration) noexcept | |
Creates a new Duration instance from an std::chrono::duration. More... | |
+ | Duration (const Duration &)=default |
Creates a copy of a Duration instance. | |
Duration & | operator= (const Duration &)=default |
Assigns the contents of one Duration to another. More... | |
operator std::chrono::duration< uint64_t, std::milli > () const noexcept | |
Returns the stored duration as an std::chrono::duration. More... | |
double | toSec () const noexcept |
Returns the stored duration in \([s]\). More... | |
uint64_t | toMSec () const noexcept |
Returns the stored duration in \([ms]\). More... | |
Arithmetic operators | |
Duration | operator+ (const Duration &rhs) const noexcept |
Performs addition. More... | |
Duration & | operator+= (const Duration &rhs) noexcept |
Performs addition. More... | |
Duration | operator- (const Duration &rhs) const noexcept |
Performs subtraction. More... | |
Duration & | operator-= (const Duration &rhs) noexcept |
Performs subtraction. More... | |
Duration | operator* (uint64_t rhs) const noexcept |
Performs multiplication. More... | |
Duration & | operator*= (uint64_t rhs) noexcept |
Performs multiplication. More... | |
uint64_t | operator/ (const Duration &rhs) const noexcept |
Performs division. More... | |
Duration | operator/ (uint64_t rhs) const noexcept |
Performs division. More... | |
Duration & | operator/= (uint64_t rhs) noexcept |
Performs division. More... | |
Duration | operator% (const Duration &rhs) const noexcept |
Performs the modulo operation. More... | |
Duration | operator% (uint64_t rhs) const noexcept |
Performs the modulo operation. More... | |
Duration & | operator%= (const Duration &rhs) noexcept |
Performs the modulo operation. More... | |
Duration & | operator%= (uint64_t rhs) noexcept |
Performs the modulo operation. More... | |
Comparison operators | |
bool | operator== (const Duration &rhs) const noexcept |
Compares two durations for equality. More... | |
bool | operator!= (const Duration &rhs) const noexcept |
Compares two durations for inequality. More... | |
bool | operator< (const Duration &rhs) const noexcept |
Compares two durations. More... | |
bool | operator<= (const Duration &rhs) const noexcept |
Compares two durations. More... | |
bool | operator> (const Duration &rhs) const noexcept |
Compares two durations. More... | |
bool | operator>= (const Duration &rhs) const noexcept |
Compares two durations. More... | |
Represents a duration with millisecond resolution.
+
+
|
+ +explicitnoexcept | +
Creates a new Duration instance from the given number of milliseconds.
+[in] | milliseconds | Number of milliseconds. |
+
|
+ +noexcept | +
+
|
+ +noexcept | +
Returns the stored duration as an std::chrono::duration.
+
+
|
+ +noexcept | +
Compares two durations for inequality.
+[in] | rhs | Right-hand side of the comparison. |
+
|
+ +noexcept | +
Performs the modulo operation.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs the modulo operation.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs the modulo operation.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs the modulo operation.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs multiplication.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs multiplication.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs addition.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs addition.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs subtraction.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs subtraction.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs division.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs division.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Performs division.
+[in] | rhs | Right-hand side of the operation. |
+
|
+ +noexcept | +
Compares two durations.
+[in] | rhs | Right-hand side of the comparison. |
+
|
+ +noexcept | +
Compares two durations.
+[in] | rhs | Right-hand side of the comparison. |
+
|
+ +default | +
Assigns the contents of one Duration to another.
+
+
|
+ +noexcept | +
Compares two durations for equality.
+[in] | rhs | Right-hand side of the comparison. |
+
|
+ +noexcept | +
Compares two durations.
+[in] | rhs | Right-hand side of the comparison. |
+
|
+ +noexcept | +
Compares two durations.
+[in] | rhs | Right-hand side of the comparison. |
+
|
+ +noexcept | +
Returns the stored duration in \([ms]\).
+
+
|
+ +noexcept | +
Returns the stored duration in \([s]\).
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::Gripper, including all inherited members.
+grasp(double width, double speed, double force, double epsilon_inner=0.005, double epsilon_outer=0.005) const | franka::Gripper | |
Gripper(const std::string &franka_address) | franka::Gripper | explicit |
Gripper(Gripper &&gripper) noexcept | franka::Gripper | |
homing() const | franka::Gripper | |
move(double width, double speed) const | franka::Gripper | |
operator=(Gripper &&gripper) noexcept | franka::Gripper | |
readOnce() const | franka::Gripper | |
ServerVersion typedef | franka::Gripper | |
serverVersion() const noexcept | franka::Gripper | |
stop() const | franka::Gripper | |
~Gripper() noexcept | franka::Gripper |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Maintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands. + More...
+ +#include <gripper.h>
+Public Types | |
+using | ServerVersion = uint16_t |
Version of the gripper server. | |
+Public Member Functions | |
Gripper (const std::string &franka_address) | |
Establishes a connection with a gripper connected to a robot. More... | |
Gripper (Gripper &&gripper) noexcept | |
Move-constructs a new Gripper instance. More... | |
Gripper & | operator= (Gripper &&gripper) noexcept |
Move-assigns this Gripper from another Gripper instance. More... | |
+ | ~Gripper () noexcept |
Closes the connection. | |
bool | homing () const |
Performs homing of the gripper. More... | |
bool | grasp (double width, double speed, double force, double epsilon_inner=0.005, double epsilon_outer=0.005) const |
Grasps an object. More... | |
bool | move (double width, double speed) const |
Moves the gripper fingers to a specified width. More... | |
bool | stop () const |
Stops a currently running gripper move or grasp. More... | |
GripperState | readOnce () const |
Waits for a gripper state update and returns it. More... | |
ServerVersion | serverVersion () const noexcept |
Returns the software version reported by the connected server. More... | |
Maintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands.
+
+
|
+ +explicit | +
Establishes a connection with a gripper connected to a robot.
+[in] | franka_address | IP/hostname of the robot the gripper is connected to. |
NetworkException | if the connection is unsuccessful. |
IncompatibleVersionException | if this version of libfranka is not supported. |
+
|
+ +noexcept | +
bool franka::Gripper::grasp | +( | +double | +width, | +
+ | + | double | +speed, | +
+ | + | double | +force, | +
+ | + | double | +epsilon_inner = 0.005 , |
+
+ | + | double | +epsilon_outer = 0.005 |
+
+ | ) | +const | +
Grasps an object.
+An object is considered grasped if the distance \(d\) between the gripper fingers satisfies \((\text{width} - \text{epsilon_inner}) < d < (\text{width} + \text{epsilon_outer})\).
+[in] | width | Size of the object to grasp in \([m]\). |
[in] | speed | Closing speed in \([\frac{m}{s}]\). |
[in] | force | Grasping force in \([N]\). |
[in] | epsilon_inner | Maximum tolerated deviation when the actual grasped width is smaller than the commanded grasp width. |
[in] | epsilon_outer | Maximum tolerated deviation when the actual grasped width is larger than the commanded grasp width. |
CommandException | if an error occurred. |
NetworkException | if the connection is lost, e.g. after a timeout. |
bool franka::Gripper::homing | +( | +) | +const | +
Performs homing of the gripper.
+After changing the gripper fingers, a homing needs to be done. This is needed to estimate the maximum grasping width.
+CommandException | if an error occurred. |
NetworkException | if the connection is lost, e.g. after a timeout. |
bool franka::Gripper::move | +( | +double | +width, | +
+ | + | double | +speed | +
+ | ) | +const | +
Moves the gripper fingers to a specified width.
+[in] | width | Intended opening width in \([m]\). |
[in] | speed | Closing speed in \([\frac{m}{s}]\). |
CommandException | if an error occurred. |
NetworkException | if the connection is lost, e.g. after a timeout. |
GripperState franka::Gripper::readOnce | +( | +) | +const | +
Waits for a gripper state update and returns it.
+NetworkException | if the connection is lost, e.g. after a timeout. |
InvalidOperationException | if another readOnce is already running. |
+
|
+ +noexcept | +
Returns the software version reported by the connected server.
+bool franka::Gripper::stop | +( | +) | +const | +
Stops a currently running gripper move or grasp.
+CommandException | if an error occurred. |
NetworkException | if the connection is lost, e.g. after a timeout. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::JointPositions, including all inherited members.
+JointPositions(const std::array< double, 7 > &joint_positions) noexcept | franka::JointPositions | |
JointPositions(std::initializer_list< double > joint_positions) | franka::JointPositions | |
motion_finished | franka::Finishable | |
q | franka::JointPositions |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Stores values for joint position motion generation. + More...
+ +#include <control_types.h>
+Public Member Functions | |
JointPositions (const std::array< double, 7 > &joint_positions) noexcept | |
Creates a new JointPositions instance. More... | |
JointPositions (std::initializer_list< double > joint_positions) | |
Creates a new JointPositions instance. More... | |
+Public Attributes | |
+std::array< double, 7 > | q {} |
Desired joint angles in [rad]. | |
Public Attributes inherited from franka::Finishable | |
+bool | motion_finished = false |
Determines whether to finish a currently running motion. | |
Stores values for joint position motion generation.
+ +
+
|
+ +noexcept | +
Creates a new JointPositions instance.
+[in] | joint_positions | Desired joint angles in \([rad]\). |
franka::JointPositions::JointPositions | +( | +std::initializer_list< double > | +joint_positions | ) | ++ |
Creates a new JointPositions instance.
+[in] | joint_positions | Desired joint angles in \([rad]\). |
std::invalid_argument | if the given initializer list has an invalid number of arguments. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::JointVelocities, including all inherited members.
+dq | franka::JointVelocities | |
JointVelocities(const std::array< double, 7 > &joint_velocities) noexcept | franka::JointVelocities | |
JointVelocities(std::initializer_list< double > joint_velocities) | franka::JointVelocities | |
motion_finished | franka::Finishable |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Stores values for joint velocity motion generation. + More...
+ +#include <control_types.h>
+Public Member Functions | |
JointVelocities (const std::array< double, 7 > &joint_velocities) noexcept | |
Creates a new JointVelocities instance. More... | |
JointVelocities (std::initializer_list< double > joint_velocities) | |
Creates a new JointVelocities instance. More... | |
+Public Attributes | |
+std::array< double, 7 > | dq {} |
Desired joint velocities in \([\frac{rad}{s}]\). | |
Public Attributes inherited from franka::Finishable | |
+bool | motion_finished = false |
Determines whether to finish a currently running motion. | |
Stores values for joint velocity motion generation.
+ +
+
|
+ +noexcept | +
Creates a new JointVelocities instance.
+[in] | joint_velocities | Desired joint velocities in \([\frac{rad}{s}]\). |
franka::JointVelocities::JointVelocities | +( | +std::initializer_list< double > | +joint_velocities | ) | ++ |
Creates a new JointVelocities instance.
+[in] | joint_velocities | Desired joint velocities in \([\frac{rad}{s}]\). |
std::invalid_argument | if the given initializer list has an invalid number of arguments. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::Model, including all inherited members.
+bodyJacobian(Frame frame, const franka::RobotState &robot_state) const | franka::Model | |
bodyJacobian(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const | franka::Model | |
coriolis(const franka::RobotState &robot_state) const noexcept | franka::Model | |
coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept | franka::Model | |
gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexcept | franka::Model | |
gravity(const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const noexcept | franka::Model | |
gravity(const franka::RobotState &robot_state) const noexcept | franka::Model | |
mass(const franka::RobotState &robot_state) const noexcept | franka::Model | |
mass(const std::array< double, 7 > &q, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept | franka::Model | |
Model(franka::Network &network, const std::string &urdf_model) | franka::Model | explicit |
Model(franka::Network &network, std::unique_ptr< RobotModelBase > robot_model) | franka::Model | explicit |
Model(Model &&model) noexcept | franka::Model | |
operator=(Model &&model) noexcept | franka::Model | |
pose(Frame frame, const franka::RobotState &robot_state) const | franka::Model | |
pose(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const | franka::Model | |
zeroJacobian(Frame frame, const franka::RobotState &robot_state) const | franka::Model | |
zeroJacobian(Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const | franka::Model | |
~Model() noexcept | franka::Model |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Calculates poses of joints and dynamic properties of the robot. + More...
+ +#include <model.h>
+Public Member Functions | |
Model (franka::Network &network, const std::string &urdf_model) | |
Creates a new Model instance. More... | |
Model (franka::Network &network, std::unique_ptr< RobotModelBase > robot_model) | |
Creates a new Model instance only for the tests. More... | |
Model (Model &&model) noexcept | |
Move-constructs a new Model instance. More... | |
Model & | operator= (Model &&model) noexcept |
Move-assigns this Model from another Model instance. More... | |
+ | ~Model () noexcept |
Unloads the model library. | |
std::array< double, 16 > | pose (Frame frame, const franka::RobotState &robot_state) const |
Gets the 4x4 pose matrix for the given frame in base frame. More... | |
std::array< double, 16 > | pose (Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const |
Gets the 4x4 pose matrix for the given frame in base frame. More... | |
std::array< double, 42 > | bodyJacobian (Frame frame, const franka::RobotState &robot_state) const |
Gets the 6x7 Jacobian for the given frame, relative to that frame. More... | |
std::array< double, 42 > | bodyJacobian (Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const |
Gets the 6x7 Jacobian for the given frame, relative to that frame. More... | |
std::array< double, 42 > | zeroJacobian (Frame frame, const franka::RobotState &robot_state) const |
Gets the 6x7 Jacobian for the given joint relative to the base frame. More... | |
std::array< double, 42 > | zeroJacobian (Frame frame, const std::array< double, 7 > &q, const std::array< double, 16 > &F_T_EE, const std::array< double, 16 > &EE_T_K) const |
Gets the 6x7 Jacobian for the given joint relative to the base frame. More... | |
std::array< double, 49 > | mass (const franka::RobotState &robot_state) const noexcept |
Calculates the 7x7 mass matrix. More... | |
std::array< double, 49 > | mass (const std::array< double, 7 > &q, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept |
Calculates the 7x7 mass matrix. More... | |
std::array< double, 7 > | coriolis (const franka::RobotState &robot_state) const noexcept |
Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\). More... | |
std::array< double, 7 > | coriolis (const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &I_total, double m_total, const std::array< double, 3 > &F_x_Ctotal) const noexcept |
Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\). More... | |
std::array< double, 7 > | gravity (const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexcept |
Calculates the gravity vector. More... | |
std::array< double, 7 > | gravity (const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const noexcept |
Calculates the gravity vector. More... | |
std::array< double, 7 > | gravity (const franka::RobotState &robot_state) const noexcept |
Calculates the gravity vector using the robot state. More... | |
Calculates poses of joints and dynamic properties of the robot.
+ +
+
|
+ +explicit | +
Creates a new Model instance.
+This constructor is for internal use only.
+[in] | network | For internal use. |
ModelException | if the model library cannot be loaded. |
+
|
+ +explicit | +
Creates a new Model instance only for the tests.
+This constructor is for the unittests for enabling mocks.
+[in] | network | For internal use. |
[in] | robot_model | unique pointer to the mocked robot_model |
+
|
+ +noexcept | +
std::array<double, 42> franka::Model::bodyJacobian | +( | +Frame | +frame, | +
+ | + | const franka::RobotState & | +robot_state | +
+ | ) | +const | +
Gets the 6x7 Jacobian for the given frame, relative to that frame.
+The Jacobian is represented as a 6x7 matrix in column-major format.
+[in] | frame | The desired frame. |
[in] | robot_state | State from which the pose should be calculated. |
std::array<double, 42> franka::Model::bodyJacobian | +( | +Frame | +frame, | +
+ | + | const std::array< double, 7 > & | +q, | +
+ | + | const std::array< double, 16 > & | +F_T_EE, | +
+ | + | const std::array< double, 16 > & | +EE_T_K | +
+ | ) | +const | +
Gets the 6x7 Jacobian for the given frame, relative to that frame.
+The Jacobian is represented as a 6x7 matrix in column-major format.
+[in] | frame | The desired frame. |
[in] | q | Joint position. |
[in] | F_T_EE | End effector in flange frame. |
[in] | EE_T_K | Stiffness frame K in the end effector frame. |
+
|
+ +noexcept | +
Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).
+[in] | robot_state | State from which the Coriolis force vector should be calculated. |
+
|
+ +noexcept | +
Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).
+[in] | q | Joint position. |
[in] | dq | Joint velocity. |
[in] | I_total | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\). |
[in] | m_total | Weight of the attached total load including end effector. Unit: \([kg]\). |
[in] | F_x_Ctotal | Translation from flange to center of mass of the attached total load. Unit: \([m]\). |
+
|
+ +noexcept | +
Calculates the gravity vector using the robot state.
+Unit: \([Nm]\).
+[in] | robot_state | State from which the gravity vector should be calculated. |
+
|
+ +noexcept | +
Calculates the gravity vector.
+Unit: \([Nm]\).
+[in] | robot_state | State from which the gravity vector should be calculated. |
[in] | gravity_earth | Earth's gravity vector. Unit: \(\frac{m}{s^2}\). |
+
|
+ +noexcept | +
Calculates the gravity vector.
+Unit: \([Nm]\).
+[in] | q | Joint position. |
[in] | m_total | Weight of the attached total load including end effector. Unit: \([kg]\). |
[in] | F_x_Ctotal | Translation from flange to center of mass of the attached total load. Unit: \([m]\). |
[in] | gravity_earth | Earth's gravity vector. Unit: \(\frac{m}{s^2}\). Default to {0.0, 0.0, -9.81}. |
+
|
+ +noexcept | +
Calculates the 7x7 mass matrix.
+Unit: \([kg \times m^2]\).
+[in] | robot_state | State from which the mass matrix should be calculated. |
+
|
+ +noexcept | +
Calculates the 7x7 mass matrix.
+Unit: \([kg \times m^2]\).
+[in] | q | Joint position. |
[in] | I_total | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\). |
[in] | m_total | Weight of the attached total load including end effector. Unit: \([kg]\). |
[in] | F_x_Ctotal | Translation from flange to center of mass of the attached total load. Unit: \([m]\). |
std::array<double, 16> franka::Model::pose | +( | +Frame | +frame, | +
+ | + | const franka::RobotState & | +robot_state | +
+ | ) | +const | +
Gets the 4x4 pose matrix for the given frame in base frame.
+The pose is represented as a 4x4 matrix in column-major format.
+[in] | frame | The desired frame. |
[in] | robot_state | State from which the pose should be calculated. |
std::array<double, 16> franka::Model::pose | +( | +Frame | +frame, | +
+ | + | const std::array< double, 7 > & | +q, | +
+ | + | const std::array< double, 16 > & | +F_T_EE, | +
+ | + | const std::array< double, 16 > & | +EE_T_K | +
+ | ) | +const | +
Gets the 4x4 pose matrix for the given frame in base frame.
+The pose is represented as a 4x4 matrix in column-major format.
+[in] | frame | The desired frame. |
[in] | q | Joint position. |
[in] | F_T_EE | End effector in flange frame. |
[in] | EE_T_K | Stiffness frame K in the end effector frame. |
std::array<double, 42> franka::Model::zeroJacobian | +( | +Frame | +frame, | +
+ | + | const franka::RobotState & | +robot_state | +
+ | ) | +const | +
Gets the 6x7 Jacobian for the given joint relative to the base frame.
+The Jacobian is represented as a 6x7 matrix in column-major format.
+[in] | frame | The desired frame. |
[in] | robot_state | State from which the pose should be calculated. |
std::array<double, 42> franka::Model::zeroJacobian | +( | +Frame | +frame, | +
+ | + | const std::array< double, 7 > & | +q, | +
+ | + | const std::array< double, 16 > & | +F_T_EE, | +
+ | + | const std::array< double, 16 > & | +EE_T_K | +
+ | ) | +const | +
Gets the 6x7 Jacobian for the given joint relative to the base frame.
+The Jacobian is represented as a 6x7 matrix in column-major format.
+[in] | frame | The desired frame. |
[in] | q | Joint position. |
[in] | F_T_EE | End effector in flange frame. |
[in] | EE_T_K | Stiffness frame K in the end effector frame. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::Robot, including all inherited members.
+automaticErrorRecovery() | franka::Robot | |
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) | franka::Robot | |
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) | franka::Robot | |
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) | franka::Robot | |
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) | franka::Robot | |
control(std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) | franka::Robot | |
control(std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) | franka::Robot | |
control(std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) | franka::Robot | |
control(std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) | franka::Robot | |
control(std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) | franka::Robot | |
getRobotModel() -> std::string | franka::Robot | |
loadModel() | franka::Robot | |
loadModel(std::unique_ptr< RobotModelBase > robot_model) (defined in franka::Robot) | franka::Robot | |
operator=(Robot &&other) noexcept | franka::Robot | |
read(std::function< bool(const RobotState &)> read_callback) | franka::Robot | |
readOnce() | franka::Robot | virtual |
Robot(const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50) | franka::Robot | explicit |
Robot(Robot &&other) noexcept | franka::Robot | |
Robot(std::shared_ptr< Impl > robot_impl) | franka::Robot | protected |
Robot()=default | franka::Robot | protected |
serverVersion() const noexcept | franka::Robot | |
ServerVersion typedef | franka::Robot | |
setCartesianImpedance(const std::array< double, 6 > &K_x) | franka::Robot | |
setCollisionBehavior(const std::array< double, 7 > &lower_torque_thresholds_acceleration, const std::array< double, 7 > &upper_torque_thresholds_acceleration, const std::array< double, 7 > &lower_torque_thresholds_nominal, const std::array< double, 7 > &upper_torque_thresholds_nominal, const std::array< double, 6 > &lower_force_thresholds_acceleration, const std::array< double, 6 > &upper_force_thresholds_acceleration, const std::array< double, 6 > &lower_force_thresholds_nominal, const std::array< double, 6 > &upper_force_thresholds_nominal) | franka::Robot | |
setCollisionBehavior(const std::array< double, 7 > &lower_torque_thresholds, const std::array< double, 7 > &upper_torque_thresholds, const std::array< double, 6 > &lower_force_thresholds, const std::array< double, 6 > &upper_force_thresholds) | franka::Robot | |
setEE(const std::array< double, 16 > &NE_T_EE) | franka::Robot | |
setGuidingMode(const std::array< bool, 6 > &guiding_mode, bool elbow) | franka::Robot | |
setJointImpedance(const std::array< double, 7 > &K_theta) | franka::Robot | |
setK(const std::array< double, 16 > &EE_T_K) | franka::Robot | |
setLoad(double load_mass, const std::array< double, 3 > &F_x_Cload, const std::array< double, 9 > &load_inertia) | franka::Robot | |
startCartesianPoseControl(const research_interface::robot::Move::ControllerMode &control_type) | franka::Robot | virtual |
startCartesianVelocityControl(const research_interface::robot::Move::ControllerMode &control_type) | franka::Robot | virtual |
startJointPositionControl(const research_interface::robot::Move::ControllerMode &control_type) | franka::Robot | virtual |
startJointVelocityControl(const research_interface::robot::Move::ControllerMode &control_type) | franka::Robot | virtual |
startTorqueControl() | franka::Robot | virtual |
stop() | franka::Robot | |
~Robot() noexcept | franka::Robot | virtual |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot. + More...
+ +#include <robot.h>
+Public Types | |
+using | ServerVersion = uint16_t |
Version of the robot server. | |
+Public Member Functions | |
Robot (const std::string &franka_address, RealtimeConfig realtime_config=RealtimeConfig::kEnforce, size_t log_size=50) | |
Establishes a connection with the robot. More... | |
Robot (Robot &&other) noexcept | |
Move-constructs a new Robot instance. More... | |
Robot & | operator= (Robot &&other) noexcept |
Move-assigns this Robot from another Robot instance. More... | |
+virtual | ~Robot () noexcept |
Closes the connection. | |
void | read (std::function< bool(const RobotState &)> read_callback) |
Starts a loop for reading the current robot state. More... | |
virtual RobotState | readOnce () |
Waits for a robot state update and returns it. More... | |
Model | loadModel () |
Loads the model library from the robot. More... | |
+Model | loadModel (std::unique_ptr< RobotModelBase > robot_model) |
ServerVersion | serverVersion () const noexcept |
Returns the software version reported by the connected server. More... | |
Motion generation and joint-level torque commands | |
The following methods allow to perform motion generation and/or send joint-level torque commands without gravity and friction by providing callback functions. +Only one of these methods can be active at the same time; a franka::ControlException is thrown otherwise. +When a robot state is received, the callback function is used to calculate the response: the desired values for that time step. After sending back the response, the callback function will be called again with the most recently received robot state. Since the robot is controlled with a 1 kHz frequency, the callback functions have to compute their result in a short time frame in order to be accepted. Callback functions take two parameters: +
The following incomplete example shows the general structure of a callback function: +double time = 0.0;
+
+ franka::Duration time_step) -> franka::JointPositions {
+ time += time_step.toSec(); // Update time at the beginning of the callback.
+ franka::JointPositions output = getJointPositions(time);
+ if (time >= max_time) {
+ // Return MotionFinished at the end of the trajectory.
+ return franka::MotionFinished(output);
+ }
+ return output;
+}
+
+Stores values for joint position motion generation. Definition: control_types.h:72 Torques MotionFinished(Torques command) noexcept Helper method to indicate that a motion should stop after processing the given command. Definition: control_types.h:294 | |
void | control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) |
Starts a control loop for sending joint-level torque commands. More... | |
void | control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) |
Starts a control loop for sending joint-level torque commands and joint positions. More... | |
void | control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) |
Starts a control loop for sending joint-level torque commands and joint velocities. More... | |
void | control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) |
Starts a control loop for sending joint-level torque commands and Cartesian poses. More... | |
void | control (std::function< Torques(const RobotState &, franka::Duration)> control_callback, std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) |
Starts a control loop for sending joint-level torque commands and Cartesian velocities. More... | |
void | control (std::function< JointPositions(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) |
Starts a control loop for a joint position motion generator with a given controller mode. More... | |
void | control (std::function< JointVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) |
Starts a control loop for a joint velocity motion generator with a given controller mode. More... | |
void | control (std::function< CartesianPose(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) |
Starts a control loop for a Cartesian pose motion generator with a given controller mode. More... | |
void | control (std::function< CartesianVelocities(const RobotState &, franka::Duration)> motion_generator_callback, ControllerMode controller_mode=ControllerMode::kJointImpedance, bool limit_rate=false, double cutoff_frequency=kDefaultCutoffFrequency) |
Starts a control loop for a Cartesian velocity motion generator with a given controller mode. More... | |
Commands | |
Commands are executed by communicating with the robot over the network. +These functions should therefore not be called from within control or motion generator loops. + | |
auto | getRobotModel () -> std::string |
void | setCollisionBehavior (const std::array< double, 7 > &lower_torque_thresholds_acceleration, const std::array< double, 7 > &upper_torque_thresholds_acceleration, const std::array< double, 7 > &lower_torque_thresholds_nominal, const std::array< double, 7 > &upper_torque_thresholds_nominal, const std::array< double, 6 > &lower_force_thresholds_acceleration, const std::array< double, 6 > &upper_force_thresholds_acceleration, const std::array< double, 6 > &lower_force_thresholds_nominal, const std::array< double, 6 > &upper_force_thresholds_nominal) |
Changes the collision behavior. More... | |
void | setCollisionBehavior (const std::array< double, 7 > &lower_torque_thresholds, const std::array< double, 7 > &upper_torque_thresholds, const std::array< double, 6 > &lower_force_thresholds, const std::array< double, 6 > &upper_force_thresholds) |
Changes the collision behavior. More... | |
void | setJointImpedance (const std::array< double, 7 > &K_theta) |
Sets the impedance for each joint in the internal controller. More... | |
void | setCartesianImpedance (const std::array< double, 6 > &K_x) |
Sets the Cartesian stiffness/compliance (for x, y, z, roll, pitch, yaw) in the internal controller. More... | |
void | setGuidingMode (const std::array< bool, 6 > &guiding_mode, bool elbow) |
Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw). More... | |
void | setK (const std::array< double, 16 > &EE_T_K) |
Sets the transformation \(^{EE}T_K\) from end effector frame to stiffness frame. More... | |
void | setEE (const std::array< double, 16 > &NE_T_EE) |
Sets the transformation \(^{NE}T_{EE}\) from nominal end effector to end effector frame. More... | |
void | setLoad (double load_mass, const std::array< double, 3 > &F_x_Cload, const std::array< double, 9 > &load_inertia) |
Sets dynamic parameters of a payload. More... | |
void | automaticErrorRecovery () |
Runs automatic error recovery on the robot. More... | |
virtual std::unique_ptr< ActiveControlBase > | startTorqueControl () |
Starts a new torque controller. More... | |
virtual std::unique_ptr< ActiveControlBase > | startJointPositionControl (const research_interface::robot::Move::ControllerMode &control_type) |
Starts a new joint position motion generator. More... | |
virtual std::unique_ptr< ActiveControlBase > | startJointVelocityControl (const research_interface::robot::Move::ControllerMode &control_type) |
Starts a new joint velocity motion generator. More... | |
virtual std::unique_ptr< ActiveControlBase > | startCartesianPoseControl (const research_interface::robot::Move::ControllerMode &control_type) |
Starts a new cartesian position motion generator. More... | |
virtual std::unique_ptr< ActiveControlBase > | startCartesianVelocityControl (const research_interface::robot::Move::ControllerMode &control_type) |
Starts a new cartesian velocity motion generator. More... | |
void | stop () |
Stops all currently running motions. More... | |
+Protected Member Functions | |
Robot (std::shared_ptr< Impl > robot_impl) | |
Constructs a new Robot given a Robot::Impl. More... | |
+ | Robot ()=default |
Default constructor to enable mocking and testing. | |
Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot.
+
+
|
+ +explicit | +
Establishes a connection with the robot.
+[in] | franka_address | IP/hostname of the robot. |
[in] | realtime_config | if set to Enforce, an exception will be thrown if realtime priority cannot be set when required. Setting realtime_config to Ignore disables this behavior. |
[in] | log_size | sets how many last states should be kept for logging purposes. The log is provided when a ControlException is thrown. |
NetworkException | if the connection is unsuccessful. |
IncompatibleVersionException | if this version of libfranka is not supported. |
+
|
+ +noexcept | +
+
|
+ +protected | +
Constructs a new Robot given a Robot::Impl.
+This enables unittests with Robot::Impl-Mocks.
+robot_impl | Robot::Impl to use |
void franka::Robot::automaticErrorRecovery | +( | +) | ++ |
Runs automatic error recovery on the robot.
+Automatic error recovery e.g. resets the robot after a collision occurred.
+CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::control | +( | +std::function< CartesianPose(const RobotState &, franka::Duration)> | +motion_generator_callback, | +
+ | + | ControllerMode | +controller_mode = ControllerMode::kJointImpedance , |
+
+ | + | bool | +limit_rate = false , |
+
+ | + | double | +cutoff_frequency = kDefaultCutoffFrequency |
+
+ | ) | ++ |
Starts a control loop for a Cartesian pose motion generator with a given controller mode.
+Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.
+[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | controller_mode | Controller to use to execute the motion. |
[in] | limit_rate | True if rate limiting should be activated. False by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if Cartesian pose command elements are NaN or infinity. |
void franka::Robot::control | +( | +std::function< CartesianVelocities(const RobotState &, franka::Duration)> | +motion_generator_callback, | +
+ | + | ControllerMode | +controller_mode = ControllerMode::kJointImpedance , |
+
+ | + | bool | +limit_rate = false , |
+
+ | + | double | +cutoff_frequency = kDefaultCutoffFrequency |
+
+ | ) | ++ |
Starts a control loop for a Cartesian velocity motion generator with a given controller mode.
+Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.
+[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | controller_mode | Controller to use to execute the motion. |
[in] | limit_rate | True if rate limiting should be activated. False by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if Cartesian velocity command elements are NaN or infinity. |
void franka::Robot::control | +( | +std::function< JointPositions(const RobotState &, franka::Duration)> | +motion_generator_callback, | +
+ | + | ControllerMode | +controller_mode = ControllerMode::kJointImpedance , |
+
+ | + | bool | +limit_rate = false , |
+
+ | + | double | +cutoff_frequency = kDefaultCutoffFrequency |
+
+ | ) | ++ |
Starts a control loop for a joint position motion generator with a given controller mode.
+Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.
+[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | controller_mode | Controller to use to execute the motion. |
[in] | limit_rate | True if rate limiting should be activated. False by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint position commands are NaN or infinity. |
void franka::Robot::control | +( | +std::function< JointVelocities(const RobotState &, franka::Duration)> | +motion_generator_callback, | +
+ | + | ControllerMode | +controller_mode = ControllerMode::kJointImpedance , |
+
+ | + | bool | +limit_rate = false , |
+
+ | + | double | +cutoff_frequency = kDefaultCutoffFrequency |
+
+ | ) | ++ |
Starts a control loop for a joint velocity motion generator with a given controller mode.
+Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.
+[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | controller_mode | Controller to use to execute the motion. |
[in] | limit_rate | True if rate limiting should be activated. False by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint velocity commands are NaN or infinity. |
void franka::Robot::control | +( | +std::function< Torques(const RobotState &, franka::Duration)> | +control_callback, | +
+ | + | bool | +limit_rate = false , |
+
+ | + | double | +cutoff_frequency = kDefaultCutoffFrequency |
+
+ | ) | ++ |
Starts a control loop for sending joint-level torque commands.
+Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.
+[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. False by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque commands are NaN or infinity. |
void franka::Robot::control | +( | +std::function< Torques(const RobotState &, franka::Duration)> | +control_callback, | +
+ | + | std::function< CartesianPose(const RobotState &, franka::Duration)> | +motion_generator_callback, | +
+ | + | bool | +limit_rate = false , |
+
+ | + | double | +cutoff_frequency = kDefaultCutoffFrequency |
+
+ | ) | ++ |
Starts a control loop for sending joint-level torque commands and Cartesian poses.
+Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.
+[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. False by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque or Cartesian pose command elements are NaN or infinity. |
void franka::Robot::control | +( | +std::function< Torques(const RobotState &, franka::Duration)> | +control_callback, | +
+ | + | std::function< CartesianVelocities(const RobotState &, franka::Duration)> | +motion_generator_callback, | +
+ | + | bool | +limit_rate = false , |
+
+ | + | double | +cutoff_frequency = kDefaultCutoffFrequency |
+
+ | ) | ++ |
Starts a control loop for sending joint-level torque commands and Cartesian velocities.
+Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.
+[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. False by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque or Cartesian velocity command elements are NaN or infinity. |
void franka::Robot::control | +( | +std::function< Torques(const RobotState &, franka::Duration)> | +control_callback, | +
+ | + | std::function< JointPositions(const RobotState &, franka::Duration)> | +motion_generator_callback, | +
+ | + | bool | +limit_rate = false , |
+
+ | + | double | +cutoff_frequency = kDefaultCutoffFrequency |
+
+ | ) | ++ |
Starts a control loop for sending joint-level torque commands and joint positions.
+Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.
+[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. False by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque or joint position commands are NaN or infinity. |
void franka::Robot::control | +( | +std::function< Torques(const RobotState &, franka::Duration)> | +control_callback, | +
+ | + | std::function< JointVelocities(const RobotState &, franka::Duration)> | +motion_generator_callback, | +
+ | + | bool | +limit_rate = false , |
+
+ | + | double | +cutoff_frequency = kDefaultCutoffFrequency |
+
+ | ) | ++ |
Starts a control loop for sending joint-level torque commands and joint velocities.
+Sets realtime priority for the current thread. Cannot be executed while another control or motion generator loop is active.
+[in] | control_callback | Callback function providing joint-level torque commands. See here for more details. |
[in] | motion_generator_callback | Callback function for motion generation. See here for more details. |
[in] | limit_rate | True if rate limiting should be activated. False by default. This could distort your motion! |
[in] | cutoff_frequency | Cutoff frequency for a first order low-pass filter applied on the user commanded signal. Set to franka::kMaxCutoffFrequency to disable. |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
RealtimeException | if realtime priority cannot be set for the current thread. |
std::invalid_argument | if joint-level torque or joint velocity commands are NaN or infinity. |
auto franka::Robot::getRobotModel | +( | +) | +-> std::string | +
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
Model franka::Robot::loadModel | +( | +) | ++ |
Loads the model library from the robot.
+ModelException | if the model library cannot be loaded. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::read | +( | +std::function< bool(const RobotState &)> | +read_callback | ) | ++ |
Starts a loop for reading the current robot state.
+Cannot be executed while a control or motion generator loop is running.
+This minimal example will print the robot state 100 times:
[in] | read_callback | Callback function for robot state reading. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
+
|
+ +virtual | +
Waits for a robot state update and returns it.
+Cannot be executed while a control or motion generator loop is running.
+InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
+
|
+ +noexcept | +
Returns the software version reported by the connected server.
+void franka::Robot::setCartesianImpedance | +( | +const std::array< double, 6 > & | +K_x | ) | ++ |
Sets the Cartesian stiffness/compliance (for x, y, z, roll, pitch, yaw) in the internal controller.
+The values set using Robot::setCartesianImpedance are used in the direction of the stiffness frame, which can be set with Robot::setK.
+Inputs received by the torque controller are not affected by this setting.
+[in] | K_x | Cartesian impedance values \(K_x=(K_{x_{x,y,z}} \in [10,3000] \frac{N}{m}, K_{x_{R,P,Y}} \in [1,300] \frac{Nm}{rad})\) |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::setCollisionBehavior | +( | +const std::array< double, 7 > & | +lower_torque_thresholds, | +
+ | + | const std::array< double, 7 > & | +upper_torque_thresholds, | +
+ | + | const std::array< double, 6 > & | +lower_force_thresholds, | +
+ | + | const std::array< double, 6 > & | +upper_force_thresholds | +
+ | ) | ++ |
Changes the collision behavior.
+Set common torque and force boundaries for acceleration/deceleration and constant velocity movement phases.
+Forces or torques between lower and upper threshold are shown as contacts in the RobotState. Forces or torques above the upper threshold are registered as collision and cause the robot to stop moving.
+[in] | lower_torque_thresholds | Contact torque thresholds for each joint in \([Nm]\). |
[in] | upper_torque_thresholds | Collision torque thresholds for each joint in \([Nm]\). |
[in] | lower_force_thresholds | Contact force thresholds for \((x,y,z,R,P,Y)\) in \([N]\). |
[in] | upper_force_thresholds | Collision force thresholds for \((x,y,z,R,P,Y)\) in \([N]\). |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::setCollisionBehavior | +( | +const std::array< double, 7 > & | +lower_torque_thresholds_acceleration, | +
+ | + | const std::array< double, 7 > & | +upper_torque_thresholds_acceleration, | +
+ | + | const std::array< double, 7 > & | +lower_torque_thresholds_nominal, | +
+ | + | const std::array< double, 7 > & | +upper_torque_thresholds_nominal, | +
+ | + | const std::array< double, 6 > & | +lower_force_thresholds_acceleration, | +
+ | + | const std::array< double, 6 > & | +upper_force_thresholds_acceleration, | +
+ | + | const std::array< double, 6 > & | +lower_force_thresholds_nominal, | +
+ | + | const std::array< double, 6 > & | +upper_force_thresholds_nominal | +
+ | ) | ++ |
Changes the collision behavior.
+Set separate torque and force boundaries for acceleration/deceleration and constant velocity movement phases.
+Forces or torques between lower and upper threshold are shown as contacts in the RobotState. Forces or torques above the upper threshold are registered as collision and cause the robot to stop moving.
+[in] | lower_torque_thresholds_acceleration | Contact torque thresholds during acceleration/deceleration for each joint in \([Nm]\). |
[in] | upper_torque_thresholds_acceleration | Collision torque thresholds during acceleration/deceleration for each joint in \([Nm]\). |
[in] | lower_torque_thresholds_nominal | Contact torque thresholds for each joint in \([Nm]\). |
[in] | upper_torque_thresholds_nominal | Collision torque thresholds for each joint in \([Nm]\). |
[in] | lower_force_thresholds_acceleration | Contact force thresholds during acceleration/deceleration for \((x,y,z,R,P,Y)\) in \([N]\). |
[in] | upper_force_thresholds_acceleration | Collision force thresholds during acceleration/deceleration for \((x,y,z,R,P,Y)\) in \([N]\). |
[in] | lower_force_thresholds_nominal | Contact force thresholds for \((x,y,z,R,P,Y)\) in \([N]\). |
[in] | upper_force_thresholds_nominal | Collision force thresholds for \((x,y,z,R,P,Y)\) in \([N]\). |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::setEE | +( | +const std::array< double, 16 > & | +NE_T_EE | ) | ++ |
Sets the transformation \(^{NE}T_{EE}\) from nominal end effector to end effector frame.
+The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.
+[in] | NE_T_EE | Vectorized NE-to-EE transformation matrix \(^{NE}T_{EE}\), column-major. |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::setGuidingMode | +( | +const std::array< bool, 6 > & | +guiding_mode, | +
+ | + | bool | +elbow | +
+ | ) | ++ |
Locks or unlocks guiding mode movement in (x, y, z, roll, pitch, yaw).
+If a flag is set to true, movement is unlocked.
+[in] | guiding_mode | Unlocked movement in (x, y, z, R, P, Y) in guiding mode. |
[in] | elbow | True if the elbow is free in guiding mode, false otherwise. |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::setJointImpedance | +( | +const std::array< double, 7 > & | +K_theta | ) | ++ |
Sets the impedance for each joint in the internal controller.
+User-provided torques are not affected by this setting.
+[in] | K_theta | Joint impedance values \(K_{\theta_{1-7}} = \in [0,14250] \frac{Nm}{rad}\) |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::setK | +( | +const std::array< double, 16 > & | +EE_T_K | ) | ++ |
Sets the transformation \(^{EE}T_K\) from end effector frame to stiffness frame.
+The transformation matrix is represented as a vectorized 4x4 matrix in column-major format.
+[in] | EE_T_K | Vectorized EE-to-K transformation matrix \(^{EE}T_K\), column-major. |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
void franka::Robot::setLoad | +( | +double | +load_mass, | +
+ | + | const std::array< double, 3 > & | +F_x_Cload, | +
+ | + | const std::array< double, 9 > & | +load_inertia | +
+ | ) | ++ |
Sets dynamic parameters of a payload.
+[in] | load_mass | Mass of the load in \([kg]\). |
[in] | F_x_Cload | Translation from flange to center of mass of load \(^Fx_{C_\text{load}}\) in \([m]\). |
[in] | load_inertia | Inertia matrix \(I_\text{load}\) in \([kg \times m^2]\), column-major. |
CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
+
|
+ +virtual | +
Starts a new cartesian position motion generator.
+control_type | research_interface::robot::Move::ControllerMode control type for the operation |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
std::invalid_argument | if joint-level torque commands are NaN or infinity. |
+
|
+ +virtual | +
Starts a new cartesian velocity motion generator.
+control_type | research_interface::robot::Move::ControllerMode control type for the operation |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
std::invalid_argument | if joint-level torque commands are NaN or infinity. |
+
|
+ +virtual | +
Starts a new joint position motion generator.
+control_type | research_interface::robot::Move::ControllerMode control type for the operation |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
std::invalid_argument | if joint-level torque commands are NaN or infinity. |
+
|
+ +virtual | +
Starts a new joint velocity motion generator.
+control_type | research_interface::robot::Move::ControllerMode control type for the operation |
ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
std::invalid_argument | if joint-level torque commands are NaN or infinity. |
+
|
+ +virtual | +
Starts a new torque controller.
+ControlException | if an error related to torque control or motion generation occurred. |
InvalidOperationException | if a conflicting operation is already running. |
NetworkException | if the connection is lost, e.g. after a timeout. |
std::invalid_argument | if joint-level torque commands are NaN or infinity. |
void franka::Robot::stop | +( | +) | ++ |
Stops all currently running motions.
+If a control or motion generator loop is running in another thread, it will be preempted with a franka::ControlException.
+CommandException | if the Control reports an error. |
NetworkException | if the connection is lost, e.g. after a timeout. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::RobotModel, including all inherited members.
+coriolis(const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne) override | franka::RobotModel | virtual |
gravity(const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne) override | franka::RobotModel | virtual |
mass(const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne) override | franka::RobotModel | virtual |
RobotModel(const std::string &urdf) (defined in franka::RobotModel) | franka::RobotModel | |
~RobotModelBase()=default (defined in RobotModelBase) | RobotModelBase | virtual |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Implements RobotModelBase using Pinocchio. + More...
+ +#include <robot_model.h>
+Public Member Functions | |
+ | RobotModel (const std::string &urdf) |
void | coriolis (const std::array< double, 7 > &q, const std::array< double, 7 > &dq, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &c_ne) override |
Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\). More... | |
void | gravity (const std::array< double, 7 > &q, const std::array< double, 3 > &g_earth, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 7 > &g_ne) override |
Calculates the gravity vector. More... | |
void | mass (const std::array< double, 7 > &q, const std::array< double, 9 > &i_total, double m_total, const std::array< double, 3 > &f_x_ctotal, std::array< double, 49 > &m_ne) override |
Calculates the 7x7 mass matrix. More... | |
Implements RobotModelBase using Pinocchio.
+
+
|
+ +overridevirtual | +
Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).
+[in] | q | Joint position. |
[in] | dq | Joint velocity. |
[in] | i_total | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\). |
[in] | m_total | Weight of the attached total load including end effector. Unit: \([kg]\). |
[in] | f_x_ctotal | Translation from flange to center of mass of the attached total load. Unit: \([m]\). |
[out] | c_ne | Coriolis force vector. Unit: \([Nm]\). |
Implements RobotModelBase.
+ +
+
|
+ +overridevirtual | +
Calculates the gravity vector.
+Unit: \([Nm]\).
+[in] | q | Joint position. |
[in] | gravity_earth | Earth's gravity vector. Unit: \(\frac{m}{s^2}\). |
[in] | m_total | Weight of the attached total load including end effector. Unit: \([kg]\). |
[in] | f_x_Ctotal | Translation from flange to center of mass of the attached total load. |
[out] | g_ne | Gravity vector. Unit: \([Nm]\). |
Implements RobotModelBase.
+ +
+
|
+ +overridevirtual | +
Calculates the 7x7 mass matrix.
+Unit: \([kg \times m^2]\).
+[in] | q | Joint position. |
[in] | i_total | Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\). |
[in] | m_total | Weight of the attached total load including end effector. Unit: \([kg]\). |
[in] | f_x_ctotal | Translation from flange to center of mass of the attached total load. Unit: \([m]\). |
[out] | m_ne | Vectorized 7x7 mass matrix, column-major. |
Implements RobotModelBase.
+ ++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::Torques, including all inherited members.
+motion_finished | franka::Finishable | |
tau_J | franka::Torques | |
Torques(const std::array< double, 7 > &torques) noexcept | franka::Torques | |
Torques(std::initializer_list< double > torques) | franka::Torques |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Stores joint-level torque commands without gravity and friction. + More...
+ +#include <control_types.h>
+Public Member Functions | |
Torques (const std::array< double, 7 > &torques) noexcept | |
Creates a new Torques instance. More... | |
Torques (std::initializer_list< double > torques) | |
Creates a new Torques instance. More... | |
+Public Attributes | |
+std::array< double, 7 > | tau_J {} |
Desired torques in [Nm]. | |
Public Attributes inherited from franka::Finishable | |
+bool | motion_finished = false |
Determines whether to finish a currently running motion. | |
Stores joint-level torque commands without gravity and friction.
+ +
+
|
+ +noexcept | +
Creates a new Torques instance.
+[in] | torques | Desired joint-level torques without gravity and friction in \([Nm]\). |
franka::Torques::Torques | +( | +std::initializer_list< double > | +torques | ) | ++ |
Creates a new Torques instance.
+[in] | torques | Desired joint-level torques without gravity and friction in \([Nm]\). |
std::invalid_argument | if the given initializer list has an invalid number of arguments. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This is the complete list of members for franka::VacuumGripper, including all inherited members.
+dropOff(std::chrono::milliseconds timeout) const | franka::VacuumGripper | |
operator=(VacuumGripper &&vacuum_gripper) noexcept | franka::VacuumGripper | |
ProductionSetupProfile enum name | franka::VacuumGripper | |
readOnce() const | franka::VacuumGripper | |
ServerVersion typedef | franka::VacuumGripper | |
serverVersion() const noexcept | franka::VacuumGripper | |
stop() const | franka::VacuumGripper | |
vacuum(uint8_t vacuum, std::chrono::milliseconds timeout, ProductionSetupProfile profile=ProductionSetupProfile::kP0) const | franka::VacuumGripper | |
VacuumGripper(const std::string &franka_address) | franka::VacuumGripper | explicit |
VacuumGripper(VacuumGripper &&vacuum_gripper) noexcept | franka::VacuumGripper | |
~VacuumGripper() noexcept | franka::VacuumGripper |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state, and allows the execution of commands. + More...
+ +#include <vacuum_gripper.h>
+Public Types | |
enum class | ProductionSetupProfile { kP0 +, kP1 +, kP2 +, kP3 + } |
Vacuum production setup profile. | |
+using | ServerVersion = uint16_t |
Version of the vacuum gripper server. | |
+Public Member Functions | |
VacuumGripper (const std::string &franka_address) | |
Establishes a connection with a vacuum gripper connected to a robot. More... | |
VacuumGripper (VacuumGripper &&vacuum_gripper) noexcept | |
Move-constructs a new VacuumGripper instance. More... | |
VacuumGripper & | operator= (VacuumGripper &&vacuum_gripper) noexcept |
Move-assigns this VacuumGripper from another VacuumGripper instance. More... | |
+ | ~VacuumGripper () noexcept |
Closes the connection. | |
bool | vacuum (uint8_t vacuum, std::chrono::milliseconds timeout, ProductionSetupProfile profile=ProductionSetupProfile::kP0) const |
Vacuums an object. More... | |
bool | dropOff (std::chrono::milliseconds timeout) const |
Drops the grasped object off. More... | |
bool | stop () const |
Stops a currently running vacuum gripper vacuum or drop off operation. More... | |
VacuumGripperState | readOnce () const |
Waits for a vacuum gripper state update and returns it. More... | |
ServerVersion | serverVersion () const noexcept |
Returns the software version reported by the connected server. More... | |
Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state, and allows the execution of commands.
+
+
|
+ +explicit | +
Establishes a connection with a vacuum gripper connected to a robot.
+[in] | franka_address | IP/hostname of the robot the vacuum gripper is connected to. |
NetworkException | if the connection is unsuccessful. |
IncompatibleVersionException | if this version of libfranka is not supported. |
+
|
+ +noexcept | +
Move-constructs a new VacuumGripper instance.
+[in] | vacuum_gripper | Other VacuumGripper instance. |
bool franka::VacuumGripper::dropOff | +( | +std::chrono::milliseconds | +timeout | ) | +const | +
Drops the grasped object off.
+[in] | timeout | Dropoff timeout. Unit: \([ms]\). |
CommandException | if an error occurred. |
NetworkException | if the connection is lost, e.g. after a timeout. |
+
|
+ +noexcept | +
Move-assigns this VacuumGripper from another VacuumGripper instance.
+[in] | vacuum_gripper | Other VacuumGripper instance. |
VacuumGripperState franka::VacuumGripper::readOnce | +( | +) | +const | +
Waits for a vacuum gripper state update and returns it.
+NetworkException | if the connection is lost, e.g. after a timeout. |
InvalidOperationException | if another readOnce is already running. |
+
|
+ +noexcept | +
Returns the software version reported by the connected server.
+bool franka::VacuumGripper::stop | +( | +) | +const | +
Stops a currently running vacuum gripper vacuum or drop off operation.
+CommandException | if an error occurred. |
NetworkException | if the connection is lost, e.g. after a timeout. |
bool franka::VacuumGripper::vacuum | +( | +uint8_t | +vacuum, | +
+ | + | std::chrono::milliseconds | +timeout, | +
+ | + | ProductionSetupProfile | +profile = ProductionSetupProfile::kP0 |
+
+ | ) | +const | +
Vacuums an object.
+[in] | vacuum | Setpoint for control mode. Unit: \([10*mbar]\). |
[in] | timeout | Vacuum timeout. Unit: \([ms]\). |
[in] | profile | Production setup profile P0 to P3. Default: P0. |
CommandException | if an error occurred. |
NetworkException | if the connection is lost, e.g. after a timeout. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example indicating the network performance.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains helper functions for writing control loops. +More...
+#include <algorithm>
#include <array>
#include <cmath>
#include <stdexcept>
#include <string>
Go to the source code of this file.
++Functions | |
bool | franka::isValidElbow (const std::array< double, 2 > &elbow) noexcept |
Determines whether the given elbow configuration is valid or not. More... | |
bool | franka::isHomogeneousTransformation (const std::array< double, 16 > &transform) noexcept |
Determines whether the given array represents a valid homogeneous transformation matrix. More... | |
bool | franka::hasRealtimeKernel () |
Determines whether the current OS kernel is a realtime kernel. More... | |
bool | franka::setCurrentThreadToHighestSchedulerPriority (std::string *error_message) |
Sets the current thread to the highest possible scheduler priority. More... | |
template<size_t N> | |
void | franka::checkFinite (const std::array< double, N > &array) |
Checks if all elements of an array of the size N have a finite value. More... | |
void | franka::checkMatrix (const std::array< double, 16 > &transform) |
Checks if all elements of the transformation matrix are finite and if it is a homogeneous transformation. More... | |
void | franka::checkElbow (const std::array< double, 2 > &elbow) |
Checks if all elements of the elbow vector are finite and if the elbow configuration is valid. More... | |
Contains helper functions for writing control loops.
+
+
|
+ +inline | +
Checks if all elements of the elbow vector are finite and if the elbow configuration is valid.
+elbow | the elbow vector to check |
+
|
+ +inline | +
Checks if all elements of an array of the size N have a finite value.
+N | the size of the array |
array | the array to be checked |
+
|
+ +inline | +
Checks if all elements of the transformation matrix are finite and if it is a homogeneous transformation.
+transform | the transformation matrix to check |
bool franka::hasRealtimeKernel | +( | +) | ++ |
Determines whether the current OS kernel is a realtime kernel.
+On Linux, this checks for the existence of /sys/kernel/realtime
. On Windows, this always returns true.
+
|
+ +inlinenoexcept | +
Determines whether the given array represents a valid homogeneous transformation matrix.
+[in] | transform | 4x4 matrix in column-major format. |
+
|
+ +inlinenoexcept | +
Determines whether the given elbow configuration is valid or not.
+[in] | elbow | Elbow configuration. |
bool franka::setCurrentThreadToHighestSchedulerPriority | +( | +std::string * | +error_message | ) | ++ |
Sets the current thread to the highest possible scheduler priority.
+[out] | error_message | Contains an error message if the scheduler priority cannot be set successfully. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains helper types for returning motion generation and joint-level torque commands. +More...
+#include <array>
#include <cmath>
#include <initializer_list>
Go to the source code of this file.
++Classes | |
struct | franka::Finishable |
Helper type for control and motion generation loops. More... | |
class | franka::Torques |
Stores joint-level torque commands without gravity and friction. More... | |
class | franka::JointPositions |
Stores values for joint position motion generation. More... | |
class | franka::JointVelocities |
Stores values for joint velocity motion generation. More... | |
class | franka::CartesianPose |
Stores values for Cartesian pose motion generation. More... | |
class | franka::CartesianVelocities |
Stores values for Cartesian velocity motion generation. More... | |
+Enumerations | |
enum class | franka::ControllerMode { kJointImpedance +, kCartesianImpedance + } |
Available controller modes for a franka::Robot. | |
enum class | franka::RealtimeConfig { kEnforce +, kIgnore + } |
Used to decide whether to enforce realtime mode for a control loop thread. More... | |
+Functions | |
Torques | franka::MotionFinished (Torques command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
JointPositions | franka::MotionFinished (JointPositions command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
JointVelocities | franka::MotionFinished (JointVelocities command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
CartesianPose | franka::MotionFinished (CartesianPose command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
CartesianVelocities | franka::MotionFinished (CartesianVelocities command) noexcept |
Helper method to indicate that a motion should stop after processing the given command. More... | |
Contains helper types for returning motion generation and joint-level torque commands.
+
+
|
+ +strong | +
Used to decide whether to enforce realtime mode for a control loop thread.
+
+
|
+ +inlinenoexcept | +
Helper method to indicate that a motion should stop after processing the given command.
+[in] | command | Last command to be executed before the motion terminates. |
+
|
+ +inlinenoexcept | +
Helper method to indicate that a motion should stop after processing the given command.
+[in] | command | Last command to be executed before the motion terminates. |
+
|
+ +inlinenoexcept | +
Helper method to indicate that a motion should stop after processing the given command.
+[in] | command | Last command to be executed before the motion terminates. |
+
|
+ +inlinenoexcept | +
Helper method to indicate that a motion should stop after processing the given command.
+[in] | command | Last command to be executed before the motion terminates. |
+
|
+ +inlinenoexcept | +
Helper method to indicate that a motion should stop after processing the given command.
+[in] | command | Last command to be executed before the motion terminates. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
File in examples | Includes file in include |
---|---|
cartesian_impedance_control.cpp | franka / duration.h |
cartesian_impedance_control.cpp | franka / exception.h |
cartesian_impedance_control.cpp | franka / model.h |
cartesian_impedance_control.cpp | franka / robot.h |
communication_test.cpp | franka / active_control.h |
communication_test.cpp | franka / active_torque_control.h |
communication_test.cpp | franka / duration.h |
communication_test.cpp | franka / exception.h |
communication_test.cpp | franka / robot.h |
echo_robot_state.cpp | franka / exception.h |
echo_robot_state.cpp | franka / robot.h |
examples_common.cpp | franka / exception.h |
examples_common.cpp | franka / robot.h |
examples_common.h | franka / control_types.h |
examples_common.h | franka / duration.h |
examples_common.h | franka / robot.h |
examples_common.h | franka / robot_state.h |
force_control.cpp | franka / duration.h |
force_control.cpp | franka / exception.h |
force_control.cpp | franka / model.h |
force_control.cpp | franka / robot.h |
generate_cartesian_pose_motion.cpp | franka / exception.h |
generate_cartesian_pose_motion.cpp | franka / robot.h |
generate_cartesian_pose_motion_external_control_loop.cpp | franka / active_control.h |
generate_cartesian_pose_motion_external_control_loop.cpp | franka / active_motion_generator.h |
generate_cartesian_pose_motion_external_control_loop.cpp | franka / exception.h |
generate_cartesian_pose_motion_external_control_loop.cpp | franka / robot.h |
generate_cartesian_velocity_motion.cpp | franka / exception.h |
generate_cartesian_velocity_motion.cpp | franka / robot.h |
generate_cartesian_velocity_motion_external_control_loop.cpp | franka / active_control.h |
generate_cartesian_velocity_motion_external_control_loop.cpp | franka / active_motion_generator.h |
generate_cartesian_velocity_motion_external_control_loop.cpp | franka / exception.h |
generate_cartesian_velocity_motion_external_control_loop.cpp | franka / robot.h |
generate_consecutive_motions.cpp | franka / exception.h |
generate_consecutive_motions.cpp | franka / robot.h |
generate_elbow_motion.cpp | franka / exception.h |
generate_elbow_motion.cpp | franka / robot.h |
generate_joint_position_motion.cpp | franka / exception.h |
generate_joint_position_motion.cpp | franka / robot.h |
generate_joint_position_motion_external_control_loop.cpp | franka / active_control.h |
generate_joint_position_motion_external_control_loop.cpp | franka / active_motion_generator.h |
generate_joint_position_motion_external_control_loop.cpp | franka / exception.h |
generate_joint_position_motion_external_control_loop.cpp | franka / robot.h |
generate_joint_velocity_motion.cpp | franka / exception.h |
generate_joint_velocity_motion.cpp | franka / robot.h |
generate_joint_velocity_motion_external_control_loop.cpp | franka / active_control.h |
generate_joint_velocity_motion_external_control_loop.cpp | franka / active_motion_generator.h |
generate_joint_velocity_motion_external_control_loop.cpp | franka / exception.h |
generate_joint_velocity_motion_external_control_loop.cpp | franka / robot.h |
grasp_object.cpp | franka / exception.h |
grasp_object.cpp | franka / gripper.h |
joint_impedance_control.cpp | franka / duration.h |
joint_impedance_control.cpp | franka / exception.h |
joint_impedance_control.cpp | franka / model.h |
joint_impedance_control.cpp | franka / rate_limiting.h |
joint_impedance_control.cpp | franka / robot.h |
joint_point_to_point_motion.cpp | franka / exception.h |
joint_point_to_point_motion.cpp | franka / robot.h |
motion_with_control.cpp | franka / exception.h |
motion_with_control.cpp | franka / robot.h |
motion_with_control_external_control_loop.cpp | franka / active_control.h |
motion_with_control_external_control_loop.cpp | franka / active_motion_generator.h |
motion_with_control_external_control_loop.cpp | franka / exception.h |
motion_with_control_external_control_loop.cpp | franka / robot.h |
print_joint_poses.cpp | franka / exception.h |
print_joint_poses.cpp | franka / model.h |
vacuum_object.cpp | franka / exception.h |
vacuum_object.cpp | franka / vacuum_gripper.h |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+Files | |
file | active_control.h [code] |
Implements the ActiveControlBase abstract class. | |
file | active_control_base.h [code] |
Abstract interface class as the base of the active controllers. | |
file | active_motion_generator.h [code] |
Contains the franka::ActiveMotionGenerator type. | |
file | active_torque_control.h [code] |
Contains the franka::ActiveTorqueControl type. | |
file | control_tools.h [code] |
Contains helper functions for writing control loops. | |
file | control_types.h [code] |
Contains helper types for returning motion generation and joint-level torque commands. | |
file | duration.h [code] |
Contains the franka::Duration type. | |
file | errors.h [code] |
Contains the franka::Errors type. | |
file | exception.h [code] |
Contains exception definitions. | |
file | gripper.h [code] |
Contains the franka::Gripper type. | |
file | gripper_state.h [code] |
Contains the franka::GripperState type. | |
file | log.h [code] |
Contains helper types for logging sent commands and received robot states. | |
file | lowpass_filter.h [code] |
Contains functions for filtering signals with a low-pass filter. | |
file | model.h [code] |
Contains model library types. | |
file | rate_limiting.h [code] |
Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity. | |
file | robot.h [code] |
Contains the franka::Robot type. | |
file | robot_state.h [code] |
Contains the franka::RobotState types. | |
file | vacuum_gripper.h [code] |
Contains the franka::VacuumGripper type. | |
file | vacuum_gripper_state.h [code] |
Contains the franka::VacuumGripperState type. | |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+Files | |
file | examples_common.h [code] |
Contains common types and functions for the examples. | |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains the franka::Duration type. +More...
+#include <chrono>
#include <cstdint>
#include <ratio>
Go to the source code of this file.
++Classes | |
class | franka::Duration |
Represents a duration with millisecond resolution. More... | |
+Functions | |
Duration | franka::operator* (uint64_t lhs, const Duration &rhs) noexcept |
Performs multiplication. More... | |
Contains the franka::Duration type.
+
+
|
+ +noexcept | +
Performs multiplication.
+[in] | lhs | Left-hand side of the multiplication. |
[in] | rhs | Right-hand side of the multiplication. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to continuously read the robot state.
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains the franka::Errors type. +More...
+#include <array>
#include <ostream>
Go to the source code of this file.
++Classes | |
struct | franka::Errors |
Enumerates errors that can occur while controlling a franka::Robot. More... | |
+Functions | |
std::ostream & | franka::operator<< (std::ostream &ostream, const Errors &errors) |
Streams the errors as JSON array. More... | |
Contains the franka::Errors type.
+std::ostream& franka::operator<< | +( | +std::ostream & | +ostream, | +
+ | + | const Errors & | +errors | +
+ | ) | ++ |
Streams the errors as JSON array.
+[in] | ostream | Ostream instance |
[in] | errors | Errors struct instance to stream |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains common types and functions for the examples. +More...
+#include <array>
#include <Eigen/Core>
#include <franka/control_types.h>
#include <franka/duration.h>
#include <franka/robot.h>
#include <franka/robot_state.h>
Go to the source code of this file.
++Classes | |
class | MotionGenerator |
An example showing how to generate a joint pose motion to a goal position. More... | |
+Functions | |
void | setDefaultBehavior (franka::Robot &robot) |
Sets a default collision behavior, joint impedance and Cartesian impedance. More... | |
Contains common types and functions for the examples.
+void setDefaultBehavior | +( | +franka::Robot & | +robot | ) | ++ |
Sets a default collision behavior, joint impedance and Cartesian impedance.
+[in] | robot | Robot instance to set behavior on. |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains exception definitions. +More...
+Go to the source code of this file.
++Classes | |
struct | franka::Exception |
Base class for all exceptions used by libfranka . More... | |
struct | franka::ModelException |
ModelException is thrown if an error occurs when loading the model library. More... | |
struct | franka::NetworkException |
NetworkException is thrown if a connection to the robot cannot be established, or when a timeout occurs. More... | |
struct | franka::ProtocolException |
ProtocolException is thrown if the robot returns an incorrect message. More... | |
struct | franka::IncompatibleVersionException |
IncompatibleVersionException is thrown if the robot does not support this version of libfranka. More... | |
struct | franka::ControlException |
ControlException is thrown if an error occurs during motion generation or torque control. More... | |
struct | franka::CommandException |
CommandException is thrown if an error occurs during command execution. More... | |
struct | franka::RealtimeException |
RealtimeException is thrown if realtime priority cannot be set. More... | |
struct | franka::InvalidOperationException |
InvalidOperationException is thrown if an operation cannot be performed. More... | |
Contains exception definitions.
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
▼ examples | |
examples_common.h | Contains common types and functions for the examples |
▼ include | |
▼ franka | |
active_control.h | Implements the ActiveControlBase abstract class |
active_control_base.h | Abstract interface class as the base of the active controllers |
active_motion_generator.h | Contains the franka::ActiveMotionGenerator type |
active_torque_control.h | Contains the franka::ActiveTorqueControl type |
control_tools.h | Contains helper functions for writing control loops |
control_types.h | Contains helper types for returning motion generation and joint-level torque commands |
duration.h | Contains the franka::Duration type |
errors.h | Contains the franka::Errors type |
exception.h | Contains exception definitions |
gripper.h | Contains the franka::Gripper type |
gripper_state.h | Contains the franka::GripperState type |
log.h | Contains helper types for logging sent commands and received robot states |
lowpass_filter.h | Contains functions for filtering signals with a low-pass filter |
model.h | Contains model library types |
rate_limiting.h | Contains functions for limiting the rate of torques, Cartesian pose, Cartesian velocity, joint position and joint velocity |
robot.h | Contains the franka::Robot type |
robot_model.h | |
robot_model_base.h | |
robot_state.h | Contains the franka::RobotState types |
vacuum_gripper.h | Contains the franka::VacuumGripper type |
vacuum_gripper_state.h | Contains the franka::VacuumGripperState type |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
A simple PI force controller that renders in the Z axis the gravitational force corresponding to a target mass of 1 kg.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to generate a Cartesian motion.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to generate a Cartesian motion with an external control loop.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to generate a Cartesian velocity motion.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to generate a Cartesian velocity motion with an external control loop.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to execute consecutive motions with error recovery.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to move the robot's elbow.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to generate a joint position motion.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to generate a joint position motion with an external control loop..
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to generate a joint velocity motion.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to generate a joint velocity motion with an external control loop.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
This page explains how to interpret the graphs that are generated by doxygen.
+Consider the following example:
This will result in the following graph:
+The boxes in the above graph have the following meaning:
+The arrows have the following meaning:
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing how to control FRANKA's gripper.
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains the franka::Gripper type. +More...
+Go to the source code of this file.
++Classes | |
class | franka::Gripper |
Maintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands. More... | |
Contains the franka::Gripper type.
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains the franka::GripperState type. +More...
+Go to the source code of this file.
++Classes | |
struct | franka::GripperState |
Describes the gripper state. More... | |
+Functions | |
std::ostream & | franka::operator<< (std::ostream &ostream, const franka::GripperState &gripper_state) |
Streams the gripper state as JSON object: {"field_name_1": value, "field_name_2": value, ...}. More... | |
Contains the franka::GripperState type.
+std::ostream& franka::operator<< | +( | +std::ostream & | +ostream, | +
+ | + | const franka::GripperState & | +gripper_state | +
+ | ) | ++ |
Streams the gripper state as JSON object: {"field_name_1": value, "field_name_2": value, ...}.
+[in] | ostream | Ostream instance |
[in] | gripper_state | GripperState struct instance to stream |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
▼Cfranka::ActiveControlBase | Allows the user to read the state of a Robot and to send new control commands after starting a control process of a Robot |
▼Cfranka::ActiveControl | Documented in ActiveControlBase |
Cfranka::ActiveMotionGenerator< MotionGeneratorType > | Allows the user to read the state of a Robot and to send new motion generator commands after starting a control process of a Robot |
Cfranka::ActiveTorqueControl | Allows the user to read the state of a Robot and to send new torque control commands after starting a control process of a Robot |
Cfranka::Duration | Represents a duration with millisecond resolution |
Cfranka::Errors | Enumerates errors that can occur while controlling a franka::Robot |
▼Cfranka::Finishable | Helper type for control and motion generation loops |
Cfranka::CartesianPose | Stores values for Cartesian pose motion generation |
Cfranka::CartesianVelocities | Stores values for Cartesian velocity motion generation |
Cfranka::JointPositions | Stores values for joint position motion generation |
Cfranka::JointVelocities | Stores values for joint velocity motion generation |
Cfranka::Torques | Stores joint-level torque commands without gravity and friction |
Cfranka::Gripper | Maintains a network connection to the gripper, provides the current gripper state, and allows the execution of commands |
Cfranka::GripperState | Describes the gripper state |
Cfranka::Model | Calculates poses of joints and dynamic properties of the robot |
CMotionGenerator | An example showing how to generate a joint pose motion to a goal position |
Cfranka::Record | One row of the log contains a robot command of timestamp n and a corresponding robot state of timestamp n+1 |
Cfranka::Robot | Maintains a network connection to the robot, provides the current robot state, gives access to the model library and allows to control the robot |
Cfranka::RobotCommand | Command sent to the robot |
▼CRobotModelBase | Robot dynamic parameters computed from the URDF model with Pinocchio |
Cfranka::RobotModel | Implements RobotModelBase using Pinocchio |
Cfranka::RobotState | Describes the robot state |
▼Cstd::runtime_error | |
▼Cfranka::Exception | Base class for all exceptions used by libfranka |
Cfranka::CommandException | CommandException is thrown if an error occurs during command execution |
Cfranka::ControlException | ControlException is thrown if an error occurs during motion generation or torque control |
Cfranka::IncompatibleVersionException | IncompatibleVersionException is thrown if the robot does not support this version of libfranka |
Cfranka::InvalidOperationException | InvalidOperationException is thrown if an operation cannot be performed |
Cfranka::ModelException | ModelException is thrown if an error occurs when loading the model library |
Cfranka::NetworkException | NetworkException is thrown if a connection to the robot cannot be established, or when a timeout occurs |
Cfranka::ProtocolException | ProtocolException is thrown if the robot returns an incorrect message |
Cfranka::RealtimeException | RealtimeException is thrown if realtime priority cannot be set |
Cfranka::VacuumGripper | Maintains a network connection to the vacuum gripper, provides the current vacuum gripper state, and allows the execution of commands |
Cfranka::VacuumGripperState | Describes the vacuum gripper state |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
With this library, you can control research versions of Franka Robotics robots. See the Franka Control Interface (FCI) documentation for more information about what libfranka
can do and how to set it up.
libfranka
is licensed under the Apache 2.0 license.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ + |
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example showing a joint impedance type control that executes a Cartesian motion in the shape of a circle. The example illustrates how to use the internal inverse kinematics to map a Cartesian trajectory to joint space. The joint space target is tracked by an impedance control that additionally compensates coriolis terms using the libfranka model library. This example also serves to compare commanded vs. measured torques. The results are printed from a separate thread to avoid blocking print functions in the real-time loop.
++ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
An example that moves the robot to a target position by commanding joint positions.
+ |
+ libfranka
+ 0.14.0
+
+ FCI C++ API
+ |
+
Contains helper types for logging sent commands and received robot states. +More...
+Go to the source code of this file.
++Classes | |
struct | franka::RobotCommand |
Command sent to the robot. More... | |
struct | franka::Record |
One row of the log contains a robot command of timestamp n and a corresponding robot state of timestamp n+1. More... | |
+Functions | |
std::string | franka::logToCSV (const std::vector< Record > &log) |
Writes the log to a string in CSV format. More... | |
Contains helper types for logging sent commands and received robot states.
+std::string franka::logToCSV | +( | +const std::vector< Record > & | +log | ) | ++ |
Writes the log to a string in CSV format.
+If the string is not empty, the first row contains the header with names of columns. The following lines contain rows of values separated by commas.
+If the log is empty, the function returns an empty string.
+[in] | log | Log provided by the ControlException. |