Control Libraries 6.3.4
Loading...
Searching...
No Matches
CartesianAcceleration.cpp
1#include "state_representation/space/cartesian/CartesianAcceleration.hpp"
2#include "state_representation/exceptions/EmptyStateException.hpp"
3
4using namespace state_representation::exceptions;
5
6namespace state_representation {
8 this->set_type(StateType::CARTESIAN_ACCELERATION);
9}
10
11CartesianAcceleration::CartesianAcceleration(const std::string& name, const std::string& reference) :
12 CartesianState(name, reference) {
13 this->set_type(StateType::CARTESIAN_ACCELERATION);
14}
15
17 const std::string& name, const Eigen::Vector3d& linear_acceleration, const std::string& reference
18) : CartesianState(name, reference) {
19 this->set_type(StateType::CARTESIAN_ACCELERATION);
20 this->set_linear_acceleration(linear_acceleration);
21}
22
24 const std::string& name, const Eigen::Vector3d& linear_acceleration, const Eigen::Vector3d& angular_acceleration,
25 const std::string& reference
26) : CartesianState(name, reference) {
27 this->set_type(StateType::CARTESIAN_ACCELERATION);
28 this->set_linear_acceleration(linear_acceleration);
29 this->set_angular_acceleration(angular_acceleration);
30}
31
33 const std::string& name, const Eigen::Matrix<double, 6, 1>& acceleration, const std::string& reference
34) : CartesianState(name, reference) {
35 this->set_type(StateType::CARTESIAN_ACCELERATION);
36 this->set_acceleration(acceleration);
37}
38
40 // set all the state variables to 0 except linear and angular velocities
41 this->set_type(StateType::CARTESIAN_ACCELERATION);
42 this->set_zero();
44 this->set_empty(state.is_empty());
45}
46
48 CartesianAcceleration(static_cast<const CartesianState&>(acceleration)) {}
49
51
52CartesianAcceleration CartesianAcceleration::Zero(const std::string& name, const std::string& reference) {
53 return CartesianState::Identity(name, reference);
54}
55
56CartesianAcceleration CartesianAcceleration::Random(const std::string& name, const std::string& reference) {
57 // separating in the two lines in needed to avoid compilation error due to ambiguous constructor call
58 Eigen::Matrix<double, 6, 1> random = Eigen::Matrix<double, 6, 1>::Random();
59 return CartesianAcceleration(name, random, reference);
60}
61
63 this->CartesianState::operator+=(acceleration);
64 return (*this);
65}
66
68 return this->CartesianState::operator+(acceleration);
69}
70
72 this->CartesianState::operator-=(acceleration);
73 return (*this);
74}
75
77 return this->CartesianState::operator-(acceleration);
78}
79
80CartesianAcceleration& CartesianAcceleration::operator*=(double lambda) {
81 this->CartesianState::operator*=(lambda);
82 return (*this);
83}
84
86 return this->CartesianState::operator*(lambda);
87}
88
90 this->CartesianState::operator/=(lambda);
91 return (*this);
92}
93
95 return this->CartesianState::operator/(lambda);
96}
97
98CartesianAcceleration& CartesianAcceleration::operator*=(const Eigen::Matrix<double, 6, 6>& lambda) {
99 // sanity check
100 if (this->is_empty()) {
101 throw EmptyStateException(this->get_name() + " state is empty");
102 }
103 // operation
104 this->set_linear_acceleration(lambda.block<3, 3>(0, 0) * this->get_linear_acceleration());
105 this->set_angular_acceleration(lambda.block<3, 3>(3, 3) * this->get_angular_acceleration());
106 return (*this);
107}
108
109CartesianTwist CartesianAcceleration::operator*(const std::chrono::nanoseconds& dt) const {
110 // sanity check
111 if (this->is_empty()) {
112 throw EmptyStateException(this->get_name() + " state is empty");
113 }
114 // operations
115 CartesianTwist twist(this->get_name(), this->get_reference_frame());
116 // convert the period to a double with the second as reference
117 double period = dt.count();
118 period /= 1e9;
119 // convert the acceleration into a twist
120 twist.set_linear_velocity(period * this->get_linear_acceleration());
121 twist.set_angular_velocity(period * this->get_angular_acceleration());
122 return twist;
123}
124
126 double max_linear, double max_angular, double linear_noise_ratio, double angular_noise_ratio
127) {
128 // clamp linear
129 this->clamp_state_variable(max_linear, CartesianStateVariable::LINEAR_ACCELERATION, linear_noise_ratio);
130 // clamp angular
131 this->clamp_state_variable(max_angular, CartesianStateVariable::ANGULAR_ACCELERATION, angular_noise_ratio);
132}
133
135 double max_linear, double max_angular, double linear_noise_ratio, double angular_noise_ratio
136) const {
137 CartesianAcceleration result(*this);
138 result.clamp(max_linear, max_angular, linear_noise_ratio, angular_noise_ratio);
139 return result;
140}
141
143 CartesianAcceleration result(*this);
144 return result;
145}
146
147Eigen::VectorXd CartesianAcceleration::data() const {
148 return this->get_acceleration();
149}
150
151void CartesianAcceleration::set_data(const Eigen::VectorXd& data) {
152 if (data.size() != 6) {
154 "Input is of incorrect size: expected 6, given " + std::to_string(data.size()));
155 }
156 this->set_acceleration(data);
157}
158
159void CartesianAcceleration::set_data(const std::vector<double>& data) {
160 this->set_data(Eigen::VectorXd::Map(data.data(), data.size()));
161}
162
164 return this->CartesianState::inverse();
165}
166
167std::ostream& operator<<(std::ostream& os, const CartesianAcceleration& acceleration) {
168 if (acceleration.is_empty()) {
169 os << "Empty CartesianAcceleration";
170 } else {
171 os << acceleration.get_name() << " CartesianTwist expressed in " << acceleration.get_reference_frame() << " frame"
172 << std::endl;
173 os << "linear_velocity: (" << acceleration.get_linear_acceleration()(0) << ", ";
174 os << acceleration.get_linear_acceleration()(1) << ", ";
175 os << acceleration.get_linear_acceleration()(2) << ")" << std::endl;
176 os << "angular_velocity: (" << acceleration.get_angular_acceleration()(0) << ", ";
177 os << acceleration.get_angular_acceleration()(1) << ", ";
178 os << acceleration.get_angular_acceleration()(2) << ")";
179 }
180 return os;
181}
182
184 return state.operator*(acceleration);
185}
186
187CartesianAcceleration operator*(double lambda, const CartesianAcceleration& acceleration) {
188 return acceleration * lambda;
189}
190
191CartesianAcceleration operator*(const Eigen::Matrix<double, 6, 6>& lambda, const CartesianAcceleration& acceleration) {
192 CartesianAcceleration result(acceleration);
193 result *= lambda;
194 return result;
195}
196
197CartesianTwist operator*(const std::chrono::nanoseconds& dt, const CartesianAcceleration& acceleration) {
198 return acceleration * dt;
199}
200}// 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.
CartesianAcceleration operator+(const CartesianAcceleration &acceleration) const
Overload the + operator with an acceleration.
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.
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.
Class to represent a state in Cartesian space.
void set_zero()
Set the State to a zero value.
void set_acceleration(const Eigen::Matrix< double, 6, 1 > &acceleration)
Setter of the linear and angular acceleration from a 6d acceleration vector.
CartesianState inverse() const
Compute the inverse of the current CartesianState.
void set_angular_acceleration(const Eigen::Vector3d &angular_acceleration)
Setter of the angular velocity attribute.
CartesianState operator-(const CartesianState &state) const
Overload the - operator.
static CartesianState Identity(const std::string &name, const std::string &reference="world")
Constructor for the identity CartesianState (identity pose and 0 for the rest)
CartesianState & operator/=(double lambda)
Overload the /= operator with a scalar.
const Eigen::Vector3d & get_linear_acceleration() const
Getter of the linear acceleration attribute.
void set_linear_acceleration(const Eigen::Vector3d &linear_acceleration)
Setter of the linear acceleration attribute.
CartesianState & operator+=(const CartesianState &state)
Overload the += operator.
CartesianState & operator-=(const CartesianState &state)
Overload the -= operator.
CartesianState & operator*=(const CartesianState &state)
Overload the *= operator with another state by deriving the equations of motions.
const Eigen::Vector3d & get_angular_acceleration() const
Getter of the angular acceleration attribute.
CartesianState operator/(double lambda) const
Overload the / operator with 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)
Overload the * operator with a scalar.
Eigen::Matrix< double, 6, 1 > get_acceleration() const
Getter of the 6d acceleration from linear and angular acceleration attributes.
CartesianState operator+(const CartesianState &state) const
Overload the + operator.
Class to define twist in cartesian space as 3D linear and angular velocity vectors.
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 as const reference.
Definition: State.cpp:48
void set_type(const StateType &type)
Override the state type.
Definition: State.cpp:89
bool is_empty() const
Getter of the empty attribute.
Definition: State.cpp:23
void set_empty(bool empty=true)
Setter of the empty attribute.
Definition: State.cpp:27
Core state variables and objects.
CartesianAcceleration operator*(const CartesianState &state, const CartesianAcceleration &acceleration)
std::ostream & operator<<(std::ostream &os, const Ellipsoid &ellipsoid)
Definition: Ellipsoid.cpp:185