cartesian_trajectory_segment.cpp
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2021 FZI Forschungszentrum Informatik
3 // Created on behalf of Universal Robots A/S
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 // -- END LICENSE BLOCK ------------------------------------------------
17 
18 //-----------------------------------------------------------------------------
25 //-----------------------------------------------------------------------------
26 
28 #include <algorithm>
29 #include <cmath>
30 #include "Eigen/src/Core/GlobalFunctions.h"
31 #include "Eigen/src/Core/Matrix.h"
32 #include "Eigen/src/Core/util/Constants.h"
33 #include "Eigen/src/Geometry/Quaternion.h"
34 #include <Eigen/Dense>
35 
37 {
40 
42  const Time& end_time, const CartesianState& end_state)
43  : QuinticSplineSegment(start_time, convert(start_state), end_time, convert(end_state)){};
44 
46 {
47  // Sample from the underlying spline segment.
48  SplineState s(7);
50 
51  if (time < this->startTime() || time > this->endTime())
52  {
53  state.p = Eigen::Vector3d(s.position[0], s.position[1], s.position[2]);
54  state.q = Eigen::Quaterniond(s.position[3], s.position[4], s.position[5], s.position[6]).normalized();
55 
56  state.v = Eigen::Vector3d::Zero();
57  state.w = Eigen::Vector3d::Zero();
58  state.v_dot = Eigen::Vector3d::Zero();
59  state.w_dot = Eigen::Vector3d::Zero();
60  }
61  else
62  {
63  state = convert(s);
64  }
65 }
66 
68 {
69  SplineState spline_state;
70 
71  // Note: The pre-multiplication of velocity and acceleration terms with
72  // `state.q.inverse()` transforms them into the body-local reference frame.
73  // The calculation performed is `state.q.inverse() * w * state.q()`
74  // This is required for computing quaternion-based velocities and
75  // accelerations below.
76 
77  // Convenience method
78  auto fill = [](auto& vec, const auto& first, const auto& second) {
79  vec.push_back(first.x());
80  vec.push_back(first.y());
81  vec.push_back(first.z());
82 
83  vec.push_back(second.w());
84  vec.push_back(second.x());
85  vec.push_back(second.y());
86  vec.push_back(second.z());
87  };
88 
89  // Spline positions
90  fill(spline_state.position, state.p, state.q);
91 
92  // Spline velocities
93  if (std::isnan(state.v.x()) || std::isnan(state.v.y()) || std::isnan(state.v.z()) || std::isnan(state.w.x()) ||
94  std::isnan(state.w.y()) || std::isnan(state.w.z()))
95  {
96  return spline_state; // with uninitialized velocity/acceleration data
97  }
98  Eigen::Quaterniond q_dot;
99  Eigen::Vector3d tmp = state.q.inverse() * state.w;
100  Eigen::Quaterniond omega(0, tmp.x(), tmp.y(), tmp.z());
101  // Calculate quaternion based velocity
102  q_dot.coeffs() = 0.5 * (state.q * omega).coeffs();
103 
104  fill(spline_state.velocity, state.q.inverse() * state.v, q_dot);
105 
106  // Spline accelerations
107  if (std::isnan(state.v_dot.x()) || std::isnan(state.v_dot.y()) || std::isnan(state.v_dot.z()) ||
108  std::isnan(state.w_dot.x()) || std::isnan(state.w_dot.y()) || std::isnan(state.w_dot.z()))
109  {
110  return spline_state; // with uninitialized acceleration data
111  }
112  Eigen::Quaterniond q_ddot;
113  tmp = state.q.inverse() * state.w_dot;
114  Eigen::Quaterniond omega_dot(0, tmp.x(), tmp.y(), tmp.z());
115  // Calculate quaternion based acceleration
116  q_ddot.coeffs() = 0.5 * (state.q * omega_dot).coeffs() + 0.5 * (q_dot * omega).coeffs();
117 
118  fill(spline_state.acceleration, state.q.inverse() * state.v_dot, q_ddot);
119 
120  return spline_state;
121 };
122 
124 {
125  // Note: The pre-multiplication of velocity and acceleration terms with
126  // `state.q.()` transforms them back into correct reference frame.
127  // The calculation performed is `state.q() * w * state.q.inverse()`
128 
129  CartesianState state;
130 
131  // Cartesian positions
132  if (s.position.empty())
133  {
134  return state; // with positions/velocities/accelerations zero initialized
135  }
136  state.p = Eigen::Vector3d(s.position[0], s.position[1], s.position[2]);
137  state.q = Eigen::Quaterniond(s.position[3], s.position[4], s.position[5], s.position[6]).normalized();
138 
139  // Cartesian velocities
140  if (s.velocity.empty())
141  {
142  return state; // with velocities/accelerations zero initialized
143  }
144  Eigen::Quaterniond q_dot(s.velocity[3], s.velocity[4], s.velocity[5], s.velocity[6]);
145 
146  // Calculate vel from quaternion based velocity
147  Eigen::Quaterniond omega;
148  omega.coeffs() = 2.0 * (state.q.inverse() * q_dot).coeffs();
149 
150  state.v = Eigen::Vector3d(s.velocity[0], s.velocity[1], s.velocity[2]);
151  state.w = Eigen::Vector3d(omega.x(), omega.y(), omega.z());
152 
153  // Cartesian accelerations
154  if (s.acceleration.empty())
155  {
156  // Re-transform vel to the correct reference frame.
157  state.v = state.q * state.v;
158  state.w = state.q * state.w;
159  return state; // with accelerations zero initialized
160  }
161  Eigen::Quaterniond q_ddot(s.acceleration[3], s.acceleration[4], s.acceleration[5], s.acceleration[6]);
162 
163  // Calculate acc from quaternion based acceleration
164  Eigen::Quaterniond omega_dot;
165  omega_dot.coeffs() = 2.0 * ((state.q.inverse() * q_ddot).coeffs() -
166  ((state.q.inverse() * q_dot) * (state.q.inverse() * q_dot)).coeffs());
167 
168  state.v_dot = Eigen::Vector3d(s.acceleration[0], s.acceleration[1], s.acceleration[2]);
169  state.w_dot = Eigen::Vector3d(omega_dot.x(), omega_dot.y(), omega_dot.z());
170 
171  // Re-transform vel and acc to the correct reference frame.
172  state.v = state.q * state.v;
173  state.w = state.q * state.w;
174  state.v_dot = state.q * state.v_dot;
175  state.w_dot = state.q * state.w_dot;
176 
177  return state;
178 }
179 
180 std::ostream& operator<<(std::ostream& out, const CartesianTrajectorySegment::SplineState& state)
181 {
182  out << "pos:\n";
183  for (size_t i = 0; i < state.position.size(); ++i)
184  {
185  out << state.position[i] << '\n';
186  }
187  out << "vel:\n";
188  for (size_t i = 0; i < state.velocity.size(); ++i)
189  {
190  out << state.velocity[i] << '\n';
191  }
192  out << "acc:\n";
193  for (size_t i = 0; i < state.acceleration.size(); ++i)
194  {
195  out << state.acceleration[i] << '\n';
196  }
197 
198  return out;
199 }
200 } // namespace ros_controllers_cartesian
ros_controllers_cartesian::Time
CartesianTrajectorySegment::Time Time
Definition: cartesian_trajectory_segment.cpp:38
ros_controllers_cartesian
Definition: cartesian_state.h:29
s
XmlRpcServer s
ros_controllers_cartesian::CartesianState::v
Eigen::Vector3d v
linear velocity,
Definition: cartesian_state.h:101
cartesian_trajectory_segment.h
trajectory_interface::QuinticSplineSegment::endTime
Time endTime() const
ros_controllers_cartesian::operator<<
std::ostream & operator<<(std::ostream &os, const CartesianTrajectorySegment::SplineState &state)
Stream operator for testing and debugging.
Definition: cartesian_trajectory_segment.cpp:180
ros_controllers_cartesian::CartesianState::v_dot
Eigen::Vector3d v_dot
linear acceleration,
Definition: cartesian_state.h:105
trajectory_interface::PosVelAccState::position
std::vector< Scalar > position
ros_controllers_cartesian::CartesianState::q
Eigen::Quaterniond q
rotation
Definition: cartesian_state.h:98
ros_controllers_cartesian::CartesianState::w_dot
Eigen::Vector3d w_dot
angular acceleration,
Definition: cartesian_state.h:106
ros_controllers_cartesian::CartesianTrajectorySegment::CartesianTrajectorySegment
CartesianTrajectorySegment()=delete
ros_controllers_cartesian::CartesianState
Cartesian state with pose, velocity and acceleration.
Definition: cartesian_state.h:38
trajectory_interface::PosVelAccState::velocity
std::vector< Scalar > velocity
ros_controllers_cartesian::convert
CartesianTrajectorySegment::SplineState convert(const CartesianState &state)
Convert a CartesianState into a ros_controllers_cartesian::SplineState.
Definition: cartesian_trajectory_segment.cpp:67
ros_controllers_cartesian::CartesianTrajectorySegment::sample
void sample(const Time &time, CartesianState &state) const
Sample the CartesianState at the given time.
Definition: cartesian_trajectory_segment.cpp:45
ros_controllers_cartesian::CartesianState::p
Eigen::Vector3d p
position
Definition: cartesian_state.h:97
ros_controllers_cartesian::CartesianState::w
Eigen::Vector3d w
angular velocity,
Definition: cartesian_state.h:102
trajectory_interface::PosVelAccState
trajectory_interface::QuinticSplineSegment::Time
Scalar Time
trajectory_interface::PosVelAccState::acceleration
std::vector< Scalar > acceleration
trajectory_interface::QuinticSplineSegment::startTime
Time startTime() const
ros_controllers_cartesian::CartesianTrajectorySegment::SplineState
QuinticSplineSegment::State SplineState
State of a 7-dimensional Spline.
Definition: cartesian_trajectory_segment.h:81
trajectory_interface::QuinticSplineSegment::sample
void sample(const Time &time, State &state) const
ros_controllers_cartesian::CartesianTrajectorySegment::Time
QuinticSplineSegment::Time Time
Relative time in seconds.
Definition: cartesian_trajectory_segment.h:69
trajectory_interface::QuinticSplineSegment


cartesian_trajectory_interpolation
Author(s):
autogenerated on Tue Oct 15 2024 02:09:14