libfranka 0.15.0
FCI C++ API
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
franka::CartesianVelocities Class Reference

Stores values for Cartesian velocity motion generation. More...

#include <control_types.h>

Inheritance diagram for franka::CartesianVelocities:
Inheritance graph
[legend]
Collaboration diagram for franka::CartesianVelocities:
Collaboration graph
[legend]

Public Member Functions

 CartesianVelocities (const std::array< double, 6 > &cartesian_velocities) noexcept
 Creates a new CartesianVelocities instance.
 
 CartesianVelocities (const std::array< double, 6 > &cartesian_velocities, const std::array< double, 2 > &elbow) noexcept
 Creates a new CartesianVelocities instance.
 
 CartesianVelocities (std::initializer_list< double > cartesian_velocities)
 Creates a new CartesianVelocities instance.
 
 CartesianVelocities (std::initializer_list< double > cartesian_velocities, std::initializer_list< double > elbow)
 Creates a new CartesianVelocities instance.
 
bool hasElbow () const noexcept
 Determines whether there is a stored elbow configuration.
 

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.
 
- Public Attributes inherited from franka::Finishable
bool motion_finished = false
 Determines whether to finish a currently running motion.
 

Detailed Description

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.

Examples
generate_cartesian_velocity_motion.cpp, and generate_cartesian_velocity_motion_external_control_loop.cpp.

Constructor & Destructor Documentation

◆ CartesianVelocities() [1/4]

franka::CartesianVelocities::CartesianVelocities ( const std::array< double, 6 > &  cartesian_velocities)
noexcept

Creates a new CartesianVelocities instance.

Parameters
[in]cartesian_velocitiesDesired 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]\).

◆ CartesianVelocities() [2/4]

franka::CartesianVelocities::CartesianVelocities ( const std::array< double, 6 > &  cartesian_velocities,
const std::array< double, 2 > &  elbow 
)
noexcept

Creates a new CartesianVelocities instance.

Parameters
[in]cartesian_velocitiesDesired 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]elbowElbow configuration (see elbow member for more details).

◆ CartesianVelocities() [3/4]

franka::CartesianVelocities::CartesianVelocities ( std::initializer_list< double >  cartesian_velocities)

Creates a new CartesianVelocities instance.

Parameters
[in]cartesian_velocitiesDesired 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]\).
Exceptions
std::invalid_argumentif the given initializer list has an invalid number of arguments.

◆ CartesianVelocities() [4/4]

franka::CartesianVelocities::CartesianVelocities ( std::initializer_list< double >  cartesian_velocities,
std::initializer_list< double >  elbow 
)

Creates a new CartesianVelocities instance.

Parameters
[in]cartesian_velocitiesDesired 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]elbowElbow configuration (see elbow member for more details).
Exceptions
std::invalid_argumentif a given initializer list has an invalid number of arguments.

Member Function Documentation

◆ hasElbow()

bool franka::CartesianVelocities::hasElbow ( ) const
noexcept

Determines whether there is a stored elbow configuration.

Returns
True if there is a stored elbow configuration, false otherwise.

Member Data Documentation

◆ elbow

std::array<double, 2> franka::CartesianVelocities::elbow {}

Elbow configuration.

The values of the array are:

  • elbow[0]: Position of the 3rd joint in \([rad]\).
  • elbow[1]: Flip direction of the elbow (4th joint):
    • +1 if \(q_4 > \alpha\)
    • 0 if \(q_4 == \alpha \)
    • -1 if \(q_4 < \alpha \)
    with \(\alpha = -0.467002423653011\) \(rad\)

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