Control Libraries 7.4.0
Loading...
Searching...
No Matches
CartesianAcceleration.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/CartesianTwist.hpp"
6#include "state_representation/space/cartesian/CartesianWrench.hpp"
7
8namespace state_representation {
9
10class CartesianPose;
11class CartesianTwist;
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_velocity() const = delete;
27 const Eigen::Vector3d& get_angular_velocity() const = delete;
28 Eigen::Matrix<double, 6, 1> get_twist() 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_velocity(const Eigen::Vector3d& linear_velocity) = delete;
43 void set_linear_velocity(const std::vector<double>& linear_velocity) = delete;
44 void set_linear_velocity(const double& x, const double& y, const double& z) = delete;
45 void set_angular_velocity(const Eigen::Vector3d& angular_velocity) = delete;
46 void set_angular_velocity(const std::vector<double>& angular_velocity) = delete;
47 void set_angular_velocity(const double& x, const double& y, const double& z) = delete;
48 void set_twist(const Eigen::Matrix<double, 6, 1>& twist) = delete;
49 void set_twist(const std::vector<double>& twist) = 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 CartesianTwist& twist) = delete;
63 CartesianState& operator+=(const CartesianWrench& wrench) = delete;
64 CartesianState operator+(const CartesianPose& pose) const = delete;
65 CartesianState operator+(const CartesianTwist& twist) const = delete;
66 CartesianState operator+(const CartesianWrench& wrench) const = delete;
67 CartesianState& operator-=(const CartesianPose& pose) = delete;
68 CartesianState& operator-=(const CartesianTwist& twist) = delete;
69 CartesianState& operator-=(const CartesianWrench& wrench) = delete;
70 CartesianState operator-(const CartesianPose& pose) const = delete;
71 CartesianState operator-(const CartesianTwist& twist) const = delete;
72 CartesianState operator-(const CartesianWrench& wrench) const = delete;
73
77 explicit CartesianAcceleration();
78
84 explicit CartesianAcceleration(const std::string& name, const std::string& reference = "world");
85
90
95
101
105 explicit CartesianAcceleration(
106 const std::string& name, const Eigen::Vector3d& linear_acceleration, const std::string& reference = "world"
107 );
108
112 explicit CartesianAcceleration(
113 const std::string& name, const Eigen::Vector3d& linear_acceleration, const Eigen::Vector3d& angular_acceleration,
114 const std::string& reference = "world"
115 );
116
120 explicit CartesianAcceleration(
121 const std::string& name, const Eigen::Matrix<double, 6, 1>& acceleration, const std::string& reference = "world"
122 );
123
130 static CartesianAcceleration Zero(const std::string& name, const std::string& reference = "world");
131
138 static CartesianAcceleration Random(const std::string& name, const std::string& reference = "world");
139
146
150 Eigen::VectorXd data() const override;
151
155 void set_data(const Eigen::VectorXd& data) override;
156
160 void set_data(const std::vector<double>& data) override;
161
171 void clamp(double max_linear, double max_angular, double linear_noise_ratio = 0, double angular_noise_ratio = 0);
172
184 double max_linear, double max_angular, double noise_ratio = 0, double angular_noise_ratio = 0
185 ) const;
186
191
196
203 normalized(const CartesianStateVariable& state_variable_type = CartesianStateVariable::ACCELERATION) const;
204
210 std::vector<double>
211 norms(const CartesianStateVariable& state_variable_type = CartesianStateVariable::ACCELERATION) const override;
212
219 CartesianAcceleration& operator*=(double lambda);
220
227 CartesianAcceleration operator*(double lambda) const;
228
236 friend CartesianAcceleration operator*(double lambda, const CartesianAcceleration& acceleration);
237
245 operator*(const Eigen::Matrix<double, 6, 6>& lambda, const CartesianAcceleration& acceleration);
246
252 CartesianTwist operator*(const std::chrono::nanoseconds& dt) const;
253
260 friend CartesianTwist operator*(const std::chrono::nanoseconds& dt, const CartesianAcceleration& acceleration);
261
268 CartesianAcceleration& operator/=(double lambda);
269
276 CartesianAcceleration operator/(double lambda) const;
277
283 CartesianAcceleration& operator+=(const CartesianAcceleration& acceleration);
284
290 CartesianAcceleration& operator+=(const CartesianState& state);
291
297 CartesianAcceleration operator+(const CartesianAcceleration& acceleration) const;
298
304 CartesianState operator+(const CartesianState& state) const;
305
311
317 CartesianAcceleration& operator-=(const CartesianAcceleration& acceleration);
318
324 CartesianAcceleration& operator-=(const CartesianState& state);
325
331 CartesianAcceleration operator-(const CartesianAcceleration& acceleration) const;
332
338 CartesianState operator-(const CartesianState& state) const;
339
346 friend std::ostream& operator<<(std::ostream& os, const CartesianAcceleration& acceleration);
347
348private:
350};
351
352}// namespace state_representation
Class to define acceleration in Cartesian space as 3D linear and angular acceleration vectors.
void clamp(double max_linear, double max_angular, double linear_noise_ratio=0, double angular_noise_ratio=0)
Clamp inplace the magnitude of the acceleration to the values in argument.
CartesianAcceleration copy() const
Return a copy of the Cartesian acceleration.
CartesianAcceleration & operator/=(double lambda)
Scale inplace by a scalar.
CartesianAcceleration clamped(double max_linear, double max_angular, double noise_ratio=0, double angular_noise_ratio=0) const
Return the clamped twist.
Eigen::VectorXd data() const override
Returns the acceleration data as an Eigen vector.
friend std::ostream & operator<<(std::ostream &os, const CartesianAcceleration &acceleration)
Overload the ostream operator for printing.
CartesianAcceleration & operator=(const CartesianAcceleration &acceleration)=default
Copy assignment operator that has to be defined to the custom assignment operator.
static CartesianAcceleration Zero(const std::string &name, const std::string &reference="world")
Constructor for the zero acceleration.
friend CartesianAcceleration operator*(double lambda, const CartesianAcceleration &acceleration)
Scale a Cartesian acceleration by a scalar.
static CartesianAcceleration Random(const std::string &name, const std::string &reference="world")
Constructor for a random acceleration.
CartesianAcceleration operator-() const
Negate a Cartesian acceleration.
std::vector< double > norms(const CartesianStateVariable &state_variable_type=CartesianStateVariable::ACCELERATION) const override
Compute the norms of the state variable specified by the input type (default is full acceleration)
CartesianAcceleration operator/(double lambda) const
Scale a Cartesian acceleration by a scalar.
CartesianAcceleration inverse() const
Compute the inverse of the current Cartesian acceleration.
void set_data(const Eigen::VectorXd &data) override
Set the acceleration data from an Eigen vector.
CartesianAcceleration normalized(const CartesianStateVariable &state_variable_type=CartesianStateVariable::ACCELERATION) const
Compute the normalized acceleration at the state variable given in argument (default is full accelera...
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.
Class to define wrench in Cartesian space as 3D force and torque vectors.
Core state variables and objects.