5 #include <franka/control_types.h>
25 #pragma clang diagnostic push
26 #pragma clang diagnostic ignored "-Wimplicit-conversion"
32 #pragma clang diagnostic pop
75 template<
typename RotationMatrixType>
77 return {rotation * end_effector_twist_, elbow_velocity_};
97 return end_effector_twist_;
106 return elbow_velocity_;
110 Twist end_effector_twist_;
111 double elbow_velocity_ = 0.0;
118 template<
typename RotationMatrixType>
120 return robot_velocity.
transform(rotation);
Cartesian velocity of a robot.
Definition: robot_velocity.hpp:18
RobotVelocity(const RobotVelocity &robot_velocity)
RobotVelocity transform(const RotationMatrixType &rotation) const
Transform the frame of the velocity by applying the given rotation.
Definition: robot_velocity.hpp:76
RobotVelocity transform(const Affine &affine) const
Transform the frame of the velocity by applying the given affine transform.
Definition: robot_velocity.hpp:65
Vector7d vector_repr() const
Get the vector representation of the velocity. It consists of the linear and angular velocity of the ...
Definition: robot_velocity.cpp:30
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....
Definition: robot_velocity.hpp:87
franka::CartesianVelocities as_franka_velocity() const
Get the franka velocity.
Definition: robot_velocity.cpp:36
Twist end_effector_twist() const
Get the end effector twist.
Definition: robot_velocity.hpp:96
std::optional< double > elbow_velocity() const
Get the elbow velocity.
Definition: robot_velocity.hpp:105
Twist of a frame.
Definition: twist.hpp:12
Twist propagateThroughLink(const Eigen::Vector3d &link_translation) const
Propagate the twist through a link with the given translation. Hence, suppose this twist is the twist...
Definition: twist.hpp:71
Definition: gripper.cpp:3
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition: cartesian_state.hpp:76
Eigen::Vector< double, 7 > Vector7d
Definition: types.hpp:9
@ CartesianVelocities
Definition: control_signal_type.hpp:12
Eigen::Affine3d Affine
Definition: types.hpp:13