Control Libraries 7.4.0
Loading...
Searching...
No Matches
CartesianTwist.cpp
1#include "state_representation/space/cartesian/CartesianTwist.hpp"
2#include "state_representation/exceptions/EmptyStateException.hpp"
3
4namespace state_representation {
5
6using namespace exceptions;
7
9 this->set_type(StateType::CARTESIAN_TWIST);
10}
11
12CartesianTwist::CartesianTwist(const std::string& name, const std::string& reference) :
13 CartesianState(name, reference) {
14 this->set_type(StateType::CARTESIAN_TWIST);
15}
16
18 const std::string& name, const Eigen::Vector3d& linear_velocity, const std::string& reference
19) : CartesianState(name, reference) {
20 this->set_type(StateType::CARTESIAN_TWIST);
21 this->set_linear_velocity(linear_velocity);
22}
23
25 const std::string& name, const Eigen::Vector3d& linear_velocity, const Eigen::Vector3d& angular_velocity,
26 const std::string& reference
27) : CartesianState(name, reference) {
28 this->set_type(StateType::CARTESIAN_TWIST);
29 this->set_linear_velocity(linear_velocity);
30 this->set_angular_velocity(angular_velocity);
31}
32
34 const std::string& name, const Eigen::Matrix<double, 6, 1>& twist, const std::string& reference
35) : CartesianState(name, reference) {
36 this->set_type(StateType::CARTESIAN_TWIST);
37 this->set_twist(twist);
38}
39
41 this->set_type(StateType::CARTESIAN_TWIST);
42 if (state) {
43 this->set_zero();
44 this->set_twist(state.get_twist());
45 }
46}
47
49 CartesianTwist(static_cast<const CartesianState&>(twist)) {}
50
51CartesianTwist::CartesianTwist(const CartesianPose& pose) : CartesianTwist(pose / std::chrono::seconds(1)) {}
52
54 CartesianTwist(acceleration * std::chrono::seconds(1)) {}
55
56CartesianTwist CartesianTwist::Zero(const std::string& name, const std::string& reference) {
57 return CartesianState::Identity(name, reference);
58}
59
60CartesianTwist CartesianTwist::Random(const std::string& name, const std::string& reference) {
61 // separating in the two lines in needed to avoid compilation error due to ambiguous constructor call
62 Eigen::Matrix<double, 6, 1> random = Eigen::Matrix<double, 6, 1>::Random();
63 return CartesianTwist(name, random, reference);
64}
65
66Eigen::VectorXd CartesianTwist::data() const {
67 return this->get_twist();
68}
69
70void CartesianTwist::set_data(const Eigen::VectorXd& data) {
71 if (data.size() != 6) {
73 "Input is of incorrect size: expected 6, given " + std::to_string(data.size()));
74 }
75 this->set_twist(data);
76}
77
78void CartesianTwist::set_data(const std::vector<double>& data) {
79 this->set_data(Eigen::VectorXd::Map(data.data(), data.size()));
80}
81
83 double max_linear, double max_angular, double linear_noise_ratio, double angular_noise_ratio
84) {
85 // clamp linear
86 this->clamp_state_variable(max_linear, CartesianStateVariable::LINEAR_VELOCITY, linear_noise_ratio);
87 // clamp angular
88 this->clamp_state_variable(max_angular, CartesianStateVariable::ANGULAR_VELOCITY, angular_noise_ratio);
89}
90
92 double max_linear, double max_angular, double linear_noise_ratio, double angular_noise_ratio
93) const {
94 CartesianTwist result(*this);
95 result.clamp(max_linear, max_angular, linear_noise_ratio, angular_noise_ratio);
96 return result;
97}
98
100 CartesianTwist result(*this);
101 return result;
102}
103
107
108CartesianTwist CartesianTwist::normalized(const CartesianStateVariable& state_variable_type) const {
109 return CartesianState::normalized(state_variable_type);
110}
111
112std::vector<double> CartesianTwist::norms(const CartesianStateVariable& state_variable_type) const {
113 return CartesianState::norms(state_variable_type);
114}
115
116CartesianTwist& CartesianTwist::operator*=(double lambda) {
117 this->CartesianState::operator*=(lambda);
118 return (*this);
119}
120
122 return this->CartesianState::operator*(lambda);
123}
124
125CartesianTwist operator*(double lambda, const CartesianTwist& twist) {
126 return twist * lambda;
127}
128
129CartesianTwist operator*(const Eigen::Matrix<double, 6, 6>& lambda, const CartesianTwist& twist) {
130 CartesianTwist result(twist);
131 result.set_twist(lambda * result.get_twist());
132 return result;
133}
134
135CartesianPose CartesianTwist::operator*(const std::chrono::nanoseconds& dt) const {
136 // operations
137 CartesianPose displacement(this->get_name(), this->get_reference_frame());
138 // convert the period to a double with the second as reference
139 double period = dt.count();
140 period /= 1e9;
141 // convert the velocities into a displacement
142 displacement.set_position(period * this->get_linear_velocity());
143 Eigen::Quaterniond angular_displacement = Eigen::Quaterniond::Identity();
144 double angular_norm = this->get_angular_velocity().norm();
145 if (angular_norm > 1e-4) {
146 double theta = angular_norm * period * 0.5;
147 angular_displacement.w() = cos(theta);
148 angular_displacement.vec() = this->get_angular_velocity() / angular_norm * sin(theta);
149 }
150 displacement.set_orientation(angular_displacement);
151 return displacement;
152}
153
154CartesianPose operator*(const std::chrono::nanoseconds& dt, const CartesianTwist& twist) {
155 return twist * dt;
156}
157
159 this->CartesianState::operator/=(lambda);
160 return (*this);
161}
162
164 return this->CartesianState::operator/(lambda);
165}
166
167CartesianAcceleration CartesianTwist::operator/(const std::chrono::nanoseconds& dt) const {
168 CartesianAcceleration acceleration(this->get_name(), this->get_reference_frame());
169 // convert the period to a double with the second as reference
170 double period = dt.count();
171 period /= 1e9;
172 acceleration.set_linear_acceleration(this->get_linear_velocity() / period);
173 acceleration.set_angular_acceleration(this->get_angular_velocity() / period);
174 return acceleration;
175}
176
177CartesianTwist& CartesianTwist::operator+=(const CartesianTwist& twist) {
178 this->CartesianState::operator+=(twist);
179 return (*this);
180}
181
182CartesianTwist& CartesianTwist::operator+=(const CartesianState& state) {
183 this->CartesianState::operator+=(state);
184 return (*this);
185}
186
187CartesianTwist CartesianTwist::operator+(const CartesianTwist& twist) const {
188 return this->CartesianState::operator+(twist);
189}
190
191CartesianState CartesianTwist::operator+(const CartesianState& state) const {
192 return this->CartesianState::operator+(state);
193}
194
198
199CartesianTwist& CartesianTwist::operator-=(const CartesianTwist& twist) {
200 this->CartesianState::operator-=(twist);
201 return (*this);
202}
203
204CartesianTwist& CartesianTwist::operator-=(const CartesianState& state) {
205 this->CartesianState::operator-=(state);
206 return (*this);
207}
208
210 return this->CartesianState::operator-(twist);
211}
212
214 return this->CartesianState::operator-(state);
215}
216
217std::ostream& operator<<(std::ostream& os, const CartesianTwist& twist) {
218 os << twist.to_string();
219 return os;
220}
221
222}// 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 set_zero()
Set the State to a zero value.
CartesianState inverse() const
Compute the inverse of the current Cartesian state.
void set_orientation(const Eigen::Quaterniond &orientation)
Setter of the orientation.
const Eigen::Vector3d & get_linear_velocity() const
Getter of the linear velocity attribute.
void set_angular_acceleration(const Eigen::Vector3d &angular_acceleration)
Setter of the angular velocity attribute.
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.
Eigen::Matrix< double, 6, 1 > get_twist() const
Getter of the 6d twist from linear and angular velocity attributes.
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.
static CartesianState Identity(const std::string &name, const std::string &reference="world")
Constructor for the identity Cartesian state (identity pose and 0 for the rest)
CartesianState & operator/=(double lambda)
Scale inplace by a scalar.
void set_linear_acceleration(const Eigen::Vector3d &linear_acceleration)
Setter of the linear acceleration attribute.
void set_position(const Eigen::Vector3d &position)
Setter of the position.
std::string to_string() const override
Convert the state to its string representation.
void set_twist(const Eigen::Matrix< double, 6, 1 > &twist)
Setter of the linear and angular velocities from a 6d twist vector.
CartesianState & operator+=(const CartesianState &state)
Add inplace another Cartesian state.
CartesianState operator-() const
Negate a Cartesian state.
const Eigen::Vector3d & get_angular_velocity() const
Getter of the angular velocity attribute.
CartesianState & operator-=(const CartesianState &state)
Compute inplace the difference with another Cartesian state.
CartesianState & operator*=(const CartesianState &state)
Transform inplace a Cartesian state into the current reference frame.
CartesianState operator/(double lambda) const
Scale a Cartesian state by a scalar.
void set_linear_velocity(const Eigen::Vector3d &linear_velocity)
Setter of the linear velocity attribute.
void set_angular_velocity(const Eigen::Vector3d &angular_velocity)
Setter of the angular velocity attribute.
friend CartesianState operator*(double lambda, const CartesianState &state)
Scale a Cartesian state by a scalar.
CartesianState operator+(const CartesianState &state) const
Add another Cartesian state.
Class to define twist in Cartesian space as 3D linear and angular velocity vectors.
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
Negate a Cartesian twist.
CartesianTwist & operator/=(double lambda)
Scale inplace by a scalar.
const std::string & get_reference_frame() const
Getter of the reference frame as const reference.
const std::string & get_name() const
Getter of the name attribute.
Definition State.cpp:29
void set_type(const StateType &type)
Setter of the state type attribute.
Definition State.cpp:41
Core state variables and objects.
std::ostream & operator<<(std::ostream &os, const AnalogIOState &state)
CartesianAcceleration operator*(double lambda, const CartesianAcceleration &acceleration)