Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
robot_velocity.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <optional>
4#include <Eigen/Core>
5#include <franka/control_types.h>
6
7#include "franky/types.hpp"
8#include "franky/twist.hpp"
10
11namespace franky {
12
20 public:
22
24
25 // Suppress implicit conversion warning
26#pragma clang diagnostic push
27#pragma clang diagnostic ignored "-Wimplicit-conversion"
32 RobotVelocity(const Twist &end_effector_twist, std::optional<double> elbow_velocity = std::nullopt);
33#pragma clang diagnostic pop
34
39 explicit RobotVelocity(const Vector7d &vector_repr, bool ignore_elbow = false);
40
45 explicit RobotVelocity(const Vector6d &vector_repr, std::optional<double> elbow_velocity = std::nullopt);
46
50 explicit RobotVelocity(franka::CartesianVelocities franka_velocity);
51
58 [[nodiscard]] Vector7d vector_repr() const;
59
68 [[nodiscard]] franka::CartesianVelocities as_franka_velocity(
69 const std::optional<ElbowState> &elbow_state = std::nullopt,
71
78 [[nodiscard]] inline RobotVelocity transform(const Affine &affine) const {
79 return transform(affine.rotation());
80 }
81
88 template<typename RotationMatrixType>
90 return {rotation * end_effector_twist_, elbow_velocity_};
91 }
92
100 [[nodiscard]] inline RobotVelocity changeEndEffectorFrame(const Eigen::Vector3d &offset_world_frame) const {
101 return {end_effector_twist_.propagateThroughLink(offset_world_frame), elbow_velocity_};
102 }
103
110 [[nodiscard]] inline RobotVelocity withElbowVelocity(const std::optional<double> elbow_velocity) const {
111 return {end_effector_twist_, elbow_velocity};
112 }
113
119 [[nodiscard]] inline Twist end_effector_twist() const {
120 return end_effector_twist_;
121 }
122
128 [[nodiscard]] inline std::optional<double> elbow_velocity() const {
129 return elbow_velocity_;
130 }
131
132 friend std::ostream& operator<<(std::ostream& os, const RobotVelocity& robot_velocity);
133
134 private:
135 Twist end_effector_twist_;
136 std::optional<double> elbow_velocity_ = std::nullopt;
137};
138
140 return robot_velocity.transform(affine);
141}
142
143template<typename RotationMatrixType>
147
148} // namespace franky
Cartesian velocity of a robot.
Definition robot_velocity.hpp:19
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.
Definition robot_velocity.cpp:41
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:89
friend std::ostream & operator<<(std::ostream &os, const RobotVelocity &robot_velocity)
Definition robot_velocity.cpp:49
RobotVelocity transform(const Affine &affine) const
Transform the frame of the velocity by applying the given affine transform.
Definition robot_velocity.hpp:78
RobotVelocity withElbowVelocity(const std::optional< double > elbow_velocity) const
Get the velocity with a new elbow velocity.
Definition robot_velocity.hpp:110
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:35
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:100
std::optional< double > elbow_velocity() const
Get the elbow velocity.
Definition robot_velocity.hpp:128
Twist end_effector_twist() const
Get the end effector twist.
Definition robot_velocity.hpp:119
Twist of a frame.
Definition twist.hpp:13
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:72
Definition dynamics_limit.cpp:8
std::array< double, dims > toStdD(const Eigen::Matrix< double, dims, 1 > &vector)
Definition util.hpp:18
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition cartesian_state.hpp:78
Eigen::Vector< double, 7 > Vector7d
Definition types.hpp:12
Eigen::Vector< double, 6 > Vector6d
Definition types.hpp:11
FlipDirection
Flip direction of a joint.
Definition elbow_state.hpp:12
Eigen::Affine3d Affine
Definition types.hpp:16