Control Libraries 7.4.0
Loading...
Searching...
No Matches
CartesianPose.hpp
1#pragma once
2
3#include "state_representation/space/cartesian/CartesianState.hpp"
4#include "state_representation/space/cartesian/CartesianTwist.hpp"
5#include "state_representation/space/cartesian/CartesianAcceleration.hpp"
6#include "state_representation/space/cartesian/CartesianWrench.hpp"
7
8namespace state_representation {
9
10class CartesianTwist;
11class CartesianAcceleration;
12class CartesianWrench;
13
19public:
20 // delete inaccessible getter and setters
21 const Eigen::Vector3d& get_linear_velocity() const = delete;
22 const Eigen::Vector3d& get_angular_velocity() const = delete;
23 Eigen::Matrix<double, 6, 1> get_twist() const = delete;
24 const Eigen::Vector3d& get_linear_acceleration() const = delete;
25 const Eigen::Vector3d& get_angular_acceleration() const = delete;
26 Eigen::Matrix<double, 6, 1> get_acceleration() 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_linear_velocity(const Eigen::Vector3d& linear_velocity) = delete;
31 void set_linear_velocity(const std::vector<double>& linear_velocity) = delete;
32 void set_linear_velocity(const double& x, const double& y, const double& z) = delete;
33 void set_angular_velocity(const Eigen::Vector3d& angular_velocity) = delete;
34 void set_angular_velocity(const std::vector<double>& angular_velocity) = delete;
35 void set_angular_velocity(const double& x, const double& y, const double& z) = delete;
36 void set_twist(const Eigen::Matrix<double, 6, 1>& twist) = delete;
37 void set_twist(const std::vector<double>& twist) = delete;
38 void set_linear_acceleration(const Eigen::Vector3d& linear_acceleration) = delete;
39 void set_linear_acceleration(const std::vector<double>& linear_acceleration) = delete;
40 void set_linear_acceleration(const double& x, const double& y, const double& z) = delete;
41 void set_angular_acceleration(const Eigen::Vector3d& angular_acceleration) = delete;
42 void set_angular_acceleration(const std::vector<double>& angular_acceleration) = delete;
43 void set_angular_acceleration(const double& x, const double& y, const double& z) = delete;
44 void set_acceleration(const Eigen::Matrix<double, 6, 1>& acceleration) = delete;
45 void set_acceleration(const std::vector<double>& acceleration) = delete;
46 void set_force(const Eigen::Vector3d& force) = delete;
47 void set_force(const std::vector<double>& force) = delete;
48 void set_force(const double& x, const double& y, const double& z) = delete;
49 void set_torque(const Eigen::Vector3d& torque) = delete;
50 void set_torque(const std::vector<double>& torque) = delete;
51 void set_torque(const double& x, const double& y, const double& z) = delete;
52 void set_wrench(const Eigen::Matrix<double, 6, 1>& wrench) = delete;
53 void set_wrench(const std::vector<double>& wrench) = delete;
54 CartesianPose& operator*=(const CartesianTwist& twist) = delete;
55 CartesianPose& operator*=(const CartesianAcceleration& acceleration) = delete;
56 CartesianPose& operator*=(const CartesianWrench& wrench) = delete;
57 CartesianState& operator+=(const CartesianTwist& twist) = delete;
58 CartesianState& operator+=(const CartesianAcceleration& acceleration) = delete;
59 CartesianState& operator+=(const CartesianWrench& wrench) = delete;
60 CartesianState operator+(const CartesianTwist& twist) const = delete;
61 CartesianState operator+(const CartesianAcceleration& acceleration) const = delete;
62 CartesianState operator+(const CartesianWrench& wrench) const = delete;
63 CartesianState& operator-=(const CartesianTwist& twist) = delete;
64 CartesianState& operator-=(const CartesianAcceleration& acceleration) = delete;
65 CartesianState& operator-=(const CartesianWrench& wrench) = delete;
66 CartesianState operator-(const CartesianTwist& twist) const = delete;
67 CartesianState operator-(const CartesianAcceleration& acceleration) const = delete;
68 CartesianState operator-(const CartesianWrench& wrench) const = delete;
69
70
74 explicit CartesianPose();
75
81 explicit CartesianPose(const std::string& name, const std::string& reference = "world");
82
86 CartesianPose(const CartesianPose& pose);
87
91 CartesianPose(const CartesianState& state);
92
96 CartesianPose(const CartesianTwist& twist);
97
104 explicit CartesianPose(
105 const std::string& name, const Eigen::Vector3d& position, const std::string& reference = "world"
106 );
107
116 explicit CartesianPose(const std::string& name, double x, double y, double z, const std::string& reference = "world");
117
124 explicit CartesianPose(
125 const std::string& name, const Eigen::Quaterniond& orientation, const std::string& reference = "world"
126 );
127
135 explicit CartesianPose(
136 const std::string& name, const Eigen::Vector3d& position, const Eigen::Quaterniond& orientation,
137 const std::string& reference = "world"
138 );
139
146 static CartesianPose Identity(const std::string& name, const std::string& reference = "world");
147
154 static CartesianPose Random(const std::string& name, const std::string& reference = "world");
155
161 CartesianPose& operator=(const CartesianPose& pose) = default;
162
166 Eigen::VectorXd data() const override;
167
171 void set_data(const Eigen::VectorXd& data) override;
172
176 void set_data(const std::vector<double>& data) override;
177
181 CartesianPose copy() const;
182
187 CartesianPose inverse() const;
188
195 CartesianPose normalized(const CartesianStateVariable& state_variable_type = CartesianStateVariable::POSE) const;
196
202 std::vector<double>
203 norms(const CartesianStateVariable& state_variable_type = CartesianStateVariable::POSE) const override;
204
212 CartesianPose& operator*=(const CartesianState& state);
213
221 CartesianPose& operator*=(const CartesianPose& pose);
222
230 CartesianState operator*(const CartesianState& state) const;
231
239 CartesianPose operator*(const CartesianPose& pose) const;
240
248 CartesianTwist operator*(const CartesianTwist& twist) const;
249
257 CartesianAcceleration operator*(const CartesianAcceleration& acceleration) const;
258
266 CartesianWrench operator*(const CartesianWrench& wrench) const;
267
274 CartesianPose& operator*=(double lambda);
275
282 CartesianPose operator*(double lambda) const;
283
291 friend CartesianPose operator*(double lambda, const CartesianPose& pose);
292
299 CartesianPose& operator/=(double lambda);
300
307 CartesianPose operator/(double lambda) const;
308
314 CartesianTwist operator/(const std::chrono::nanoseconds& dt) const;
315
321 CartesianPose& operator+=(const CartesianPose& pose);
322
328 CartesianPose& operator+=(const CartesianState& state);
329
335 CartesianPose operator+(const CartesianPose& pose) const;
336
342 CartesianState operator+(const CartesianState& state) const;
343
348 CartesianPose operator-() const;
349
355 CartesianPose& operator-=(const CartesianPose& pose);
356
362 CartesianPose& operator-=(const CartesianState& state);
363
369 CartesianPose operator-(const CartesianPose& pose) const;
370
376 CartesianState operator-(const CartesianState& state) const;
377
384 friend std::ostream& operator<<(std::ostream& os, const CartesianPose& pose);
385
386private:
388};
389
390}// 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.
void set_data(const Eigen::VectorXd &data) override
Set the pose data from an Eigen vector.
friend std::ostream & operator<<(std::ostream &os, const CartesianPose &pose)
Overload the ostream operator for printing.
CartesianPose operator-() const
Negate a Cartesian pose.
std::vector< double > norms(const CartesianStateVariable &state_variable_type=CartesianStateVariable::POSE) const override
Compute the norms of the state variable specified by the input type (default is full pose)
CartesianPose & operator=(const CartesianPose &pose)=default
Copy assignment operator that has to be defined to the custom assignment operator.
CartesianPose & operator/=(double lambda)
Scale inplace by a scalar.
static CartesianPose Identity(const std::string &name, const std::string &reference="world")
Constructor for the identity pose.
Eigen::VectorXd data() const override
Returns the pose data as an Eigen vector.
CartesianPose normalized(const CartesianStateVariable &state_variable_type=CartesianStateVariable::POSE) const
Compute the normalized pose at the state variable given in argument (default is full pose)
CartesianPose operator/(double lambda) const
Scale a Cartesian pose by a scalar.
CartesianPose copy() const
Return a copy of the Cartesian pose.
friend CartesianPose operator*(double lambda, const CartesianPose &pose)
Scale a Cartesian pose by a scalar.
CartesianPose inverse() const
Compute the inverse of the current Cartesian pose.
static CartesianPose Random(const std::string &name, const std::string &reference="world")
Constructor for a random pose.
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.