Franky
0.9.1
A High-Level Motion API for Franka
|
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... | |
Cartesian velocity of a robot.
This class encapsulates the cartesian velocity of a robot, which comproses the end effector twist and the elbow velocity.
|
default |
|
default |
franky::RobotVelocity::RobotVelocity | ( | const Twist & | end_effector_twist, |
double | elbow_velocity = 0.0 |
||
) |
end_effector_twist | The twist of the end effector. |
elbow_velocity | The velocity of the elbow. Default is 0.0. |
|
explicit |
vector_repr | The vector representation of the velocity. |
|
explicit |
franka_velocity | The franka velocity. |
franka::CartesianVelocities franky::RobotVelocity::as_franka_velocity | ( | ) | const |
Get the franka velocity.
|
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.
offset_world_frame | The offset to add to the current end-effector frame. |
|
inline |
Get the elbow velocity.
|
inline |
Get the end effector twist.
|
inline |
Transform the frame of the velocity by applying the given affine transform.
affine | The affine to apply. |
|
inline |
Transform the frame of the velocity by applying the given rotation.
rotation | The rotation to apply. |
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.