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

Cartesian velocity of a robot. More...

#include <robot_velocity.hpp>

Public Member Functions

 RobotVelocity ()
 
 RobotVelocity (const RobotVelocity &robot_velocity)
 
 RobotVelocity (const Twist &end_effector_twist, double elbow_velocity=0.0)
 
 RobotVelocity (const Vector7d &vector_repr)
 
 RobotVelocity (franka::CartesianVelocities franka_velocity)
 
Vector7d vector_repr () const
 Get the vector representation of the velocity. It consists of the linear and angular velocity of the end effector and the joint velocity of the elbow. More...
 
franka::CartesianVelocities as_franka_velocity () const
 Get the franka velocity. More...
 
RobotVelocity transform (const Affine &affine) const
 Transform the frame of the velocity by applying the given affine transform. More...
 
template<typename RotationMatrixType >
RobotVelocity transform (const RotationMatrixType &rotation) const
 Transform the frame of the velocity by applying the given rotation. More...
 
RobotVelocity changeEndEffectorFrame (const Eigen::Vector3d &offset_world_frame) const
 Change the end-effector frame by adding the given offset to the current end-effector frame. Note that the offset must be given in world coordinates. More...
 
Twist end_effector_twist () const
 Get the end effector twist. More...
 
std::optional< double > elbow_velocity () const
 Get the elbow velocity. More...
 

Detailed Description

Cartesian velocity of a robot.

This class encapsulates the cartesian velocity of a robot, which comproses the end effector twist and the elbow velocity.

Constructor & Destructor Documentation

◆ RobotVelocity() [1/5]

franky::RobotVelocity::RobotVelocity ( )
default

◆ RobotVelocity() [2/5]

franky::RobotVelocity::RobotVelocity ( const RobotVelocity robot_velocity)
default

◆ RobotVelocity() [3/5]

franky::RobotVelocity::RobotVelocity ( const Twist end_effector_twist,
double  elbow_velocity = 0.0 
)
Parameters
end_effector_twistThe twist of the end effector.
elbow_velocityThe velocity of the elbow. Default is 0.0.

◆ RobotVelocity() [4/5]

franky::RobotVelocity::RobotVelocity ( const Vector7d vector_repr)
explicit
Parameters
vector_reprThe vector representation of the velocity.

◆ RobotVelocity() [5/5]

franky::RobotVelocity::RobotVelocity ( franka::CartesianVelocities  franka_velocity)
explicit
Parameters
franka_velocityThe franka velocity.

Member Function Documentation

◆ as_franka_velocity()

franka::CartesianVelocities franky::RobotVelocity::as_franka_velocity ( ) const

Get the franka velocity.

Returns
The franka velocity.

◆ changeEndEffectorFrame()

RobotVelocity franky::RobotVelocity::changeEndEffectorFrame ( const Eigen::Vector3d &  offset_world_frame) const
inline

Change the end-effector frame by adding the given offset to the current end-effector frame. Note that the offset must be given in world coordinates.

Parameters
offset_world_frameThe offset to add to the current end-effector frame.
Returns
The velocity of the new end-effector frame.

◆ elbow_velocity()

std::optional<double> franky::RobotVelocity::elbow_velocity ( ) const
inline

Get the elbow velocity.

Returns
The elbow velocity.

◆ end_effector_twist()

Twist franky::RobotVelocity::end_effector_twist ( ) const
inline

Get the end effector twist.

Returns
The end effector twist.

◆ transform() [1/2]

RobotVelocity franky::RobotVelocity::transform ( const Affine affine) const
inline

Transform the frame of the velocity by applying the given affine transform.

Parameters
affineThe affine to apply.
Returns
The velocity after the transformation.

◆ transform() [2/2]

template<typename RotationMatrixType >
RobotVelocity franky::RobotVelocity::transform ( const RotationMatrixType &  rotation) const
inline

Transform the frame of the velocity by applying the given rotation.

Parameters
rotationThe rotation to apply.
Returns
The velocity after the transformation.

◆ vector_repr()

Vector7d franky::RobotVelocity::vector_repr ( ) const

Get the vector representation of the velocity. It consists of the linear and angular velocity of the end effector and the joint velocity of the elbow.

Returns
The vector representation of the velocity.

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