Franky 0.12.0
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, std::optional< double > elbow_velocity=std::nullopt) | |
RobotVelocity (const Vector7d &vector_repr, bool ignore_elbow=false) | |
RobotVelocity (const Vector6d &vector_repr, std::optional< double > elbow_velocity=std::nullopt) | |
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. | |
franka::CartesianVelocities | as_franka_velocity (const std::optional< ElbowState > &elbow_state=std::nullopt, FlipDirection default_elbow_flip_direction=FlipDirection::kNegative) const |
Get the franka velocity. | |
RobotVelocity | transform (const Affine &affine) const |
Transform the frame of the velocity by applying the given affine transform. | |
template<typename RotationMatrixType > | |
RobotVelocity | transform (const RotationMatrixType &rotation) const |
Transform the frame of the velocity by applying the given rotation. | |
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. | |
RobotVelocity | withElbowVelocity (const std::optional< double > elbow_velocity) const |
Get the velocity with a new elbow velocity. | |
Twist | end_effector_twist () const |
Get the end effector twist. | |
std::optional< double > | elbow_velocity () const |
Get the elbow velocity. | |
Friends | |
std::ostream & | operator<< (std::ostream &os, const RobotVelocity &robot_velocity) |
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, |
std::optional< double > | elbow_velocity = std::nullopt |
||
) |
end_effector_twist | The twist of the end effector. |
elbow_velocity | The velocity of the elbow (optional). |
|
explicit |
vector_repr | The vector representation of the velocity. |
ignore_elbow | Whether to ignore the elbow velocity. Default is false. |
|
explicit |
vector_repr | The vector representation of the velocity. |
elbow_velocity | The velocity of the elbow (optional). |
|
explicit |
franka_velocity | The franka velocity. |
franka::CartesianVelocities franky::RobotVelocity::as_franka_velocity | ( | const std::optional< ElbowState > & | elbow_state = std::nullopt , |
FlipDirection | default_elbow_flip_direction = FlipDirection::kNegative |
||
) | const |
Get the franka velocity.
elbow_state | The elbow state to use. Note, that franka::CartesianVelocities contains the elbow state and not the elbow velocity, contrary to RobotVelocity. |
default_elbow_flip_direction | The default flip direction of the elbow if it is not set. |
|
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.
|
inline |
Get the velocity with a new elbow velocity.
elbow_velocity | The new elbow velocity. |
|
friend |