Control Libraries 7.4.0
Loading...
Searching...
No Matches
CartesianTwist.hpp
1#pragma once
2
3#include "state_representation/space/cartesian/CartesianState.hpp"
4#include "state_representation/space/cartesian/CartesianPose.hpp"
5#include "state_representation/space/cartesian/CartesianAcceleration.hpp"
6#include "state_representation/space/cartesian/CartesianWrench.hpp"
7
8namespace state_representation {
9
10class CartesianPose;
11class CartesianAcceleration;
12class CartesianWrench;
13
19public:
20 // delete inaccessible getter and setters
21 const Eigen::Vector3d& get_position() const = delete;
22 const Eigen::Quaterniond& get_orientation() const = delete;
23 Eigen::Vector4d get_orientation_coefficients() const = delete;
24 Eigen::Matrix<double, 7, 1> get_pose() const = delete;
25 Eigen::Matrix4d get_transformation_matrix() const = delete;
26 const Eigen::Vector3d& get_linear_acceleration() const = delete;
27 const Eigen::Vector3d& get_angular_acceleration() const = delete;
28 Eigen::Matrix<double, 6, 1> get_acceleration() const = delete;
29 const Eigen::Vector3d& get_force() const = delete;
30 const Eigen::Vector3d& get_torque() const = delete;
31 Eigen::Matrix<double, 6, 1> get_wrench() const = delete;
32 void set_position(const Eigen::Vector3d& position) = delete;
33 void set_position(const std::vector<double>& position) = delete;
34 void set_position(const double& x, const double& y, const double& z) = delete;
35 void set_orientation(const Eigen::Quaterniond& orientation) = delete;
36 void set_orientation(const Eigen::Vector4d& orientation) = delete;
37 void set_orientation(const std::vector<double>& orientation) = delete;
38 void set_orientation(const double& w, const double& x, const double& y, const double& z) = delete;
39 void set_pose(const Eigen::Vector3d& position, const Eigen::Quaterniond& orientation) = delete;
40 void set_pose(const Eigen::Matrix<double, 7, 1>& pose) = delete;
41 void set_pose(const std::vector<double>& pose) = delete;
42 void set_linear_acceleration(const Eigen::Vector3d& linear_acceleration) = delete;
43 void set_linear_acceleration(const std::vector<double>& linear_acceleration) = delete;
44 void set_linear_acceleration(const double& x, const double& y, const double& z) = delete;
45 void set_angular_acceleration(const Eigen::Vector3d& angular_acceleration) = delete;
46 void set_angular_acceleration(const std::vector<double>& angular_acceleration) = delete;
47 void set_angular_acceleration(const double& x, const double& y, const double& z) = delete;
48 void set_acceleration(const Eigen::Matrix<double, 6, 1>& acceleration) = delete;
49 void set_acceleration(const std::vector<double>& acceleration) = delete;
50 void set_force(const Eigen::Vector3d& force) = delete;
51 void set_force(const std::vector<double>& force) = delete;
52 void set_force(const double& x, const double& y, const double& z) = delete;
53 void set_torque(const Eigen::Vector3d& torque) = delete;
54 void set_torque(const std::vector<double>& torque) = delete;
55 void set_torque(const double& x, const double& y, const double& z) = delete;
56 void set_wrench(const Eigen::Matrix<double, 6, 1>& wrench) = delete;
57 void set_wrench(const std::vector<double>& wrench) = delete;
58 CartesianState& operator*=(const CartesianState& state) = delete;
59 CartesianState operator*(const CartesianState& state) const = delete;
60 Eigen::Vector3d operator*(const Eigen::Vector3d& vector) const = delete;
61 CartesianState& operator+=(const CartesianPose& pose) = delete;
62 CartesianState& operator+=(const CartesianAcceleration& acceleration) = delete;
63 CartesianState& operator+=(const CartesianWrench& wrench) = delete;
64 CartesianState operator+(const CartesianPose& pose) const = delete;
65 CartesianState operator+(const CartesianAcceleration& acceleration) const = delete;
66 CartesianState operator+(const CartesianWrench& wrench) const = delete;
67 CartesianState& operator-=(const CartesianPose& pose) = delete;
68 CartesianState& operator-=(const CartesianAcceleration& acceleration) = delete;
69 CartesianState& operator-=(const CartesianWrench& wrench) = delete;
70 CartesianState operator-(const CartesianPose& pose) const = delete;
71 CartesianState operator-(const CartesianAcceleration& acceleration) const = delete;
72 CartesianState operator-(const CartesianWrench& wrench) const = delete;
73
77 explicit CartesianTwist();
78
84 explicit CartesianTwist(const std::string& name, const std::string& reference = "world");
85
89 CartesianTwist(const CartesianTwist& twist);
90
94 CartesianTwist(const CartesianState& state);
95
100 CartesianTwist(const CartesianPose& pose);
101
106 CartesianTwist(const CartesianAcceleration& acceleration);
107
111 explicit CartesianTwist(
112 const std::string& name, const Eigen::Vector3d& linear_velocity, const std::string& reference = "world"
113 );
114
118 explicit CartesianTwist(
119 const std::string& name, const Eigen::Vector3d& linear_velocity, const Eigen::Vector3d& angular_velocity,
120 const std::string& reference = "world"
121 );
122
126 explicit CartesianTwist(
127 const std::string& name, const Eigen::Matrix<double, 6, 1>& twist, const std::string& reference = "world"
128 );
129
136 static CartesianTwist Zero(const std::string& name, const std::string& reference = "world");
137
144 static CartesianTwist Random(const std::string& name, const std::string& reference = "world");
145
151 CartesianTwist& operator=(const CartesianTwist& twist) = default;
152
156 Eigen::VectorXd data() const override;
157
161 void set_data(const Eigen::VectorXd& data) override;
162
166 void set_data(const std::vector<double>& data) override;
167
177 void clamp(double max_linear, double max_angular, double linear_noise_ratio = 0, double angular_noise_ratio = 0);
178
190 double max_linear, double max_angular, double noise_ratio = 0, double angular_noise_ratio = 0
191 ) const;
192
196 CartesianTwist copy() const;
197
201 CartesianTwist inverse() const;
202
208 CartesianTwist normalized(const CartesianStateVariable& state_variable_type = CartesianStateVariable::TWIST) const;
209
215 std::vector<double>
216 norms(const CartesianStateVariable& state_variable_type = CartesianStateVariable::TWIST) const override;
217
224 CartesianTwist& operator*=(double lambda);
225
232 CartesianTwist operator*(double lambda) const;
233
241 friend CartesianTwist operator*(double lambda, const CartesianTwist& twist);
242
249 friend CartesianTwist operator*(const Eigen::Matrix<double, 6, 6>& lambda, const CartesianTwist& twist);
250
256 CartesianPose operator*(const std::chrono::nanoseconds& dt) const;
257
264 friend CartesianPose operator*(const std::chrono::nanoseconds& dt, const CartesianTwist& twist);
265
272 CartesianTwist& operator/=(double lambda);
273
280 CartesianTwist operator/(double lambda) const;
281
287 CartesianAcceleration operator/(const std::chrono::nanoseconds& dt) const;
288
294 CartesianTwist& operator+=(const CartesianTwist& twist);
295
301 CartesianTwist& operator+=(const CartesianState& state);
302
308 CartesianTwist operator+(const CartesianTwist& twist) const;
309
315 CartesianState operator+(const CartesianState& state) const;
316
322
328 CartesianTwist& operator-=(const CartesianTwist& twist);
329
335 CartesianTwist& operator-=(const CartesianState& state);
336
342 CartesianTwist operator-(const CartesianTwist& twist) const;
343
349 CartesianState operator-(const CartesianState& state) const;
350
357 friend std::ostream& operator<<(std::ostream& os, const CartesianTwist& twist);
358
359private:
361};
362
363}// namespace state_representation
Class to define acceleration in Cartesian space as 3D linear and angular acceleration vectors.
Class to define Cartesian pose in Cartesian space as 3D position and quaternion based orientation.
Class to represent a state in Cartesian space.
void clamp_state_variable(double max_norm, const CartesianStateVariable &state_variable_type, double noise_ratio=0)
Clamp inplace the norm of the a specific state variable.
Class to define twist in Cartesian space as 3D linear and angular velocity vectors.
friend std::ostream & operator<<(std::ostream &os, const CartesianTwist &twist)
Overload the ostream operator for printing.
std::vector< double > norms(const CartesianStateVariable &state_variable_type=CartesianStateVariable::TWIST) const override
Compute the norms of the state variable specified by the input type (default is full twist)
Eigen::VectorXd data() const override
Returns the twist data as an Eigen vector.
CartesianTwist clamped(double max_linear, double max_angular, double noise_ratio=0, double angular_noise_ratio=0) const
Return the clamped twist.
static CartesianTwist Random(const std::string &name, const std::string &reference="world")
Constructor for a random twist.
friend CartesianTwist operator*(double lambda, const CartesianTwist &twist)
Scale a Cartesian twist by a scalar.
static CartesianTwist Zero(const std::string &name, const std::string &reference="world")
Constructor for the zero twist.
void set_data(const Eigen::VectorXd &data) override
Set the twist data from an Eigen vector.
void clamp(double max_linear, double max_angular, double linear_noise_ratio=0, double angular_noise_ratio=0)
Clamp inplace the magnitude of the twist to the values in argument.
CartesianTwist copy() const
Return a copy of the Cartesian twist.
CartesianTwist normalized(const CartesianStateVariable &state_variable_type=CartesianStateVariable::TWIST) const
Compute the normalized twist at the state variable given in argument (default is full twist)
CartesianTwist operator/(double lambda) const
Scale a Cartesian twist by a scalar.
CartesianTwist inverse() const
Compute the inverse of the current Cartesian twist.
CartesianTwist & operator=(const CartesianTwist &twist)=default
Copy assignment operator that has to be defined to the custom assignment operator.
CartesianTwist operator-() const
Negate a Cartesian twist.
CartesianTwist & operator/=(double lambda)
Scale inplace by a scalar.
Class to define wrench in Cartesian space as 3D force and torque vectors.
Core state variables and objects.