Control Libraries 6.3.4
Loading...
Searching...
No Matches
CartesianAcceleration.hpp
1#pragma once
2
3#include "state_representation/space/cartesian/CartesianState.hpp"
4#include "state_representation/space/cartesian/CartesianTwist.hpp"
5
6namespace state_representation {
7class CartesianTwist;
8
14private:
16
17public:
18 // delete inaccessible getter and setters
19 const Eigen::Vector3d& get_position() const = delete;
20 const Eigen::Quaterniond& get_orientation() const = delete;
21 Eigen::Vector4d get_orientation_coefficients() const = delete;
22 Eigen::Matrix<double, 7, 1> get_pose() const = delete;
23 Eigen::Matrix4d get_transformation_matrix() const = delete;
24 const Eigen::Vector3d& get_linear_velocity() const = delete;
25 const Eigen::Vector3d& get_angular_velocity() const = delete;
26 Eigen::Matrix<double, 6, 1> get_twist() const = delete;
27 const Eigen::Vector3d& get_force() const = delete;
28 const Eigen::Vector3d& get_torque() const = delete;
29 Eigen::Matrix<double, 6, 1> get_wrench() const = delete;
30 void set_position(const Eigen::Vector3d& position) = delete;
31 void set_position(const std::vector<double>& position) = delete;
32 void set_position(const double& x, const double& y, const double& z) = delete;
33 void set_orientation(const Eigen::Quaterniond& orientation) = delete;
34 void set_orientation(const Eigen::Vector4d& orientation) = delete;
35 void set_orientation(const std::vector<double>& orientation) = delete;
36 void set_orientation(const double& w, const double& x, const double& y, const double& z) = delete;
37 void set_pose(const Eigen::Vector3d& position, const Eigen::Quaterniond& orientation) = delete;
38 void set_pose(const Eigen::Matrix<double, 7, 1>& pose) = delete;
39 void set_pose(const std::vector<double>& pose) = delete;
40 void set_linear_velocity(const Eigen::Vector3d& linear_velocity) = delete;
41 void set_linear_velocity(const std::vector<double>& linear_velocity) = delete;
42 void set_linear_velocity(const double& x, const double& y, const double& z) = delete;
43 void set_angular_velocity(const Eigen::Vector3d& angular_velocity) = delete;
44 void set_angular_velocity(const std::vector<double>& angular_velocity) = delete;
45 void set_angular_velocity(const double& x, const double& y, const double& z) = delete;
46 void set_twist(const Eigen::Matrix<double, 6, 1>& twist) = delete;
47 void set_twist(const std::vector<double>& twist) = delete;
48 void set_force(const Eigen::Vector3d& force) = delete;
49 void set_force(const std::vector<double>& force) = delete;
50 void set_force(const double& x, const double& y, const double& z) = delete;
51 void set_torque(const Eigen::Vector3d& torque) = delete;
52 void set_torque(const std::vector<double>& torque) = delete;
53 void set_torque(const double& x, const double& y, const double& z) = delete;
54 void set_wrench(const Eigen::Matrix<double, 6, 1>& wrench) = delete;
55 void set_wrench(const std::vector<double>& wrench) = delete;
56 CartesianState operator*=(const CartesianState& state) = delete;
57 CartesianState operator*(const CartesianState& state) = delete;
58 friend CartesianState operator*=(const CartesianState& state, const CartesianAcceleration& acceleration) = delete;
59
63 explicit CartesianAcceleration();
64
70 explicit CartesianAcceleration(const std::string& name, const std::string& reference = "world");
71
76
81
86
90 explicit CartesianAcceleration(
91 const std::string& name, const Eigen::Vector3d& linear_acceleration, const std::string& reference = "world"
92 );
93
97 explicit CartesianAcceleration(
98 const std::string& name, const Eigen::Vector3d& linear_acceleration, const Eigen::Vector3d& angular_acceleration,
99 const std::string& reference = "world"
100 );
101
105 explicit CartesianAcceleration(
106 const std::string& name, const Eigen::Matrix<double, 6, 1>& acceleration, const std::string& reference = "world"
107 );
108
115 static CartesianAcceleration Zero(const std::string& name, const std::string& reference = "world");
116
123 static CartesianAcceleration Random(const std::string& name, const std::string& reference = "world");
124
131
138
144 CartesianAcceleration operator+(const CartesianAcceleration& acceleration) const;
145
152
158 CartesianAcceleration operator-(const CartesianAcceleration& acceleration) const;
159
165 CartesianAcceleration& operator*=(double lambda);
166
172 CartesianAcceleration operator*(double lambda) const;
173
179 CartesianAcceleration& operator/=(double lambda);
180
186 CartesianAcceleration operator/(double lambda) const;
187
193 CartesianAcceleration& operator*=(const Eigen::Matrix<double, 6, 6>& lambda);
194
200 CartesianTwist operator*(const std::chrono::nanoseconds& dt) const;
201
211 void clamp(double max_linear, double max_angular, double linear_noise_ratio = 0, double angular_noise_ratio = 0);
212
224 double max_linear, double max_angular, double noise_ratio = 0, double angular_noise_ratio = 0
225 ) const;
226
232
237 Eigen::VectorXd data() const override;
238
243 void set_data(const Eigen::VectorXd& data) override;
244
249 void set_data(const std::vector<double>& data) override;
250
256
262 std::vector<double>
263 norms(const CartesianStateVariable& state_variable_type = CartesianStateVariable::ACCELERATION) const override;
264
271 normalized(const CartesianStateVariable& state_variable_type = CartesianStateVariable::ACCELERATION) const;
272
279 friend std::ostream& operator<<(std::ostream& os, const CartesianAcceleration& acceleration);
280
286 friend CartesianAcceleration operator*(const CartesianState& state, const CartesianAcceleration& acceleration);
287
293 friend CartesianAcceleration operator*(double lambda, const CartesianAcceleration& acceleration);
294
301 operator*(const Eigen::Matrix<double, 6, 6>& lambda, const CartesianAcceleration& acceleration);
302
308 friend CartesianTwist operator*(const std::chrono::nanoseconds& dt, const CartesianAcceleration& acceleration);
309};
310
311inline std::vector<double> CartesianAcceleration::norms(const CartesianStateVariable& state_variable_type) const {
312 return CartesianState::norms(state_variable_type);
313}
314
315inline CartesianAcceleration CartesianAcceleration::normalized(const CartesianStateVariable& state_variable_type) const {
316 return CartesianState::normalized(state_variable_type);
317}
318}// 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 operator-(const CartesianAcceleration &acceleration) const
Overload the - operator with an acceleration.
CartesianAcceleration & operator+=(const CartesianAcceleration &acceleration)
Overload the += operator.
CartesianAcceleration copy() const
Return a copy of the CartesianAcceleration.
CartesianAcceleration & operator/=(double lambda)
Overload the /= operator with a scalar.
friend CartesianAcceleration operator*(const CartesianState &state, const CartesianAcceleration &acceleration)
Overload the * operator with a CartesianState.
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.
CartesianAcceleration & operator-=(const CartesianAcceleration &acceleration)
Overload the -= operator.
friend std::ostream & operator<<(std::ostream &os, const CartesianAcceleration &acceleration)
Overload the ostream operator for printing.
CartesianAcceleration operator+(const CartesianAcceleration &acceleration) const
Overload the + operator with an acceleration.
CartesianAcceleration & operator=(const CartesianAcceleration &acceleration)=default
Copy assignment operator that have 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.
static CartesianAcceleration Random(const std::string &name, const std::string &reference="world")
Constructor for a random 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 twist)
CartesianAcceleration operator/(double lambda) const
Overload the / operator with a scalar.
CartesianAcceleration inverse() const
Compute the inverse of the current CartesianAcceleration.
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 represent a state in Cartesian space.
virtual std::vector< double > norms(const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL) const
Compute the norms of the state variable specified by the input type (default is full state)
CartesianState normalized(const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL) const
Compute the normalized state at the state variable given in argument (default is full state)
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.
Core state variables and objects.