GraftUKFAttitude.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Chad Rockey
32  */
33 
34  #include <graft/GraftUKFAttitude.h>
35  #include <ros/console.h>
36 
38  graft_state_.setZero();
39  graft_state_(0,0) = 1.0; // Normalize quaternion
40  graft_control_.setZero();
41  graft_covariance_.setIdentity();
42  Q_.setZero();
43  }
44 
46 
47 }
48 
49 VectorXd verticalConcatenate(VectorXd& m, VectorXd& n){
50  if(m.rows() == 0){
51  return n;
52  }
53  VectorXd out;
54  out.resize(m.rows()+n.rows(), m.cols());
55  out << m,n;
56  return out;
57 }
58 
59 MatrixXd verticalConcatenate(MatrixXd& m, MatrixXd& n){
60  if(m.rows() == 0){
61  return n;
62  }
63  MatrixXd out;
64  out.resize(m.rows()+n.rows(), m.cols());
65  out << m,n;
66  return out;
67 }
68 
69 MatrixXd matrixSqrt(MatrixXd matrix){
70  // Use LLT Cholesky decomposiion to create stable Matrix Sqrt
71  return Eigen::LLT<Eigen::MatrixXd>(matrix).matrixL();
72 }
73 
74 std::vector<MatrixXd > generateSigmaPoints(MatrixXd state, MatrixXd covariance, double lambda){
75  std::vector<MatrixXd > out;
76 
77  double gamma = std::sqrt((state.rows()+lambda));
78  MatrixXd sig_sqrt = gamma*matrixSqrt(covariance);
79 
80  // i = 0, push back state as is
81  out.push_back(state);
82 
83  // i = 1,...,n
84  for(size_t i = 1; i <= state.rows(); i++){
85  out.push_back(state + sig_sqrt.col(i-1));
86  }
87 
88  // i = n + 1,...,2n
89  for(size_t i = state.rows() + 1; i <= 2*state.rows(); i++){
90  out.push_back(state - sig_sqrt.col(i-(state.rows()+1)));
91  }
92 
93  return out;
94 }
95 
96 MatrixXd meanFromSigmaPoints(std::vector<MatrixXd >& sigma_points, double n, double lambda){
97  double weight_zero = lambda / (n + lambda);
98  MatrixXd out = weight_zero * sigma_points[0];
99  double weight_i = 1.0/(2*(n + lambda));
100  for(size_t i = 1; i <= 2*n; i++){
101  out = out + weight_i * sigma_points[i];
102  }
103  return out;
104 }
105 
107 MatrixXd covarianceFromSigmaPoints(std::vector<MatrixXd >& sigma_points, MatrixXd& mean, MatrixXd process_noise, double n, double alpha, double beta, double lambda){
108  double cov_weight_zero = lambda / (n + lambda) + (1 - alpha*alpha + beta);
109  MatrixXd out = cov_weight_zero * (sigma_points[0] - mean) * (sigma_points[0] - mean).transpose();
110  double weight_i = 1.0/(2*(n + lambda));
111  for(size_t i = 1; i <= 2*n; i++){
112  out = out + weight_i * (sigma_points[i] - mean) * (sigma_points[i] - mean).transpose();
113  }
114  return out+process_noise;
115 }
116 
117 MatrixXd crossCovariance(std::vector<MatrixXd >& sigma_points, MatrixXd& mean, std::vector<MatrixXd >& meas_sigma_points, MatrixXd& meas_mean, double alpha, double beta, double lambda){
118  double n = sigma_points[0].rows();
119  double cov_weight_zero = lambda / (n + lambda) + (1 - alpha*alpha + beta);
120  MatrixXd out = cov_weight_zero * (sigma_points[0] - mean) * (meas_sigma_points[0] - meas_mean).transpose();
121  double weight_i = 1.0/(2*(n + lambda));
122  for(size_t i = 1; i <= 2*n; i++){
123  out = out + weight_i * (sigma_points[i] - mean) * (meas_sigma_points[i] - meas_mean).transpose();
124  }
125  return out;
126 }
127 
128 Matrix<double, 4, 4> quaternionUpdateMatrix(const double wx, const double wy, const double wz){
129  Matrix<double, 4, 4> out;
130  out << 0, wx, wy, wz,
131  -wx, 0, -wz, wy,
132  -wy, wz, 0, -wx,
133  -wz, -wy, wx, 0;
134  return out;
135 }
136 
137 Matrix<double, 4, 1> unitQuaternion(const Matrix<double, 4, 1>& q){
138  double q_mag = std::sqrt(q(0)*q(0) + q(1)*q(1) + q(2)*q(2) + q(3)*q(3));
139  return q / q_mag;
140 }
141 
142 Matrix<double, 4, 1> updatedQuaternion(const Matrix<double, 4, 1>& q, const double wx, const double wy, const double wz, double dt){
143  Matrix<double, 4, 1> out;
144  Matrix<double, 4, 4> I = Matrix<double, 4, 4>::Identity();
145  double s = 1.0/2.0 * std::sqrt(wx*wx*dt*dt + wy*wy*dt*dt + wz*wz*dt*dt);
146  double k = 0.0;
147  double q_mag = std::sqrt(q(0)*q(0) + q(1)*q(1) + q(2)*q(2) + q(3)*q(3));
148  double err = 1.0 - q_mag*q_mag;
149 
150  double correction_factor = 1 - 1.0/2.0*s*s + 1.0/24.0*s*s*s*s + k * dt * err; // Cosine taylor series
151  MatrixXd correction = I*(correction_factor);
152  double update_factor = 1.0/2.0*dt*(1.0 - 1.0/6.0*s*s + 1.0/120.0*s*s*s*s); // Sinc taylor series
153  Matrix<double, 4, 4> quaterion_update_matrix = quaternionUpdateMatrix(wx, wy, wz);
154  MatrixXd update = update_factor*quaterion_update_matrix;
155  out = (correction-update)*q;
156 
157 
158  double out_mag = std::sqrt(out(0)*out(0) + out(1)*out(1) + out(2)*out(2) + out(3)*out(3));
159  double out_err = 1.0 - out_mag*out_mag;
160 
161  return out;
162 }
163 
164 MatrixXd GraftUKFAttitude::f(MatrixXd x, double dt){
165  Matrix<double, SIZE, 1> out;
166  out.setZero();
167  Matrix<double, 4, 1> new_q = updatedQuaternion(x.block(0, 0, 4, 1), x(4), x(5), x(6), dt);
168  out.block(0, 0, 4, 1) = new_q;
169  out(4) = x(4); // wx
170  out(5) = x(5); // wy
171  out(6) = x(6); // wz
172  return out;
173 }
174 
175 graft::GraftState::ConstPtr stateMsgFromMatrix(const MatrixXd& state){
176  graft::GraftState::Ptr out(new graft::GraftState());
177  out->pose.orientation.w = state(0);
178  out->pose.orientation.x = state(1);
179  out->pose.orientation.y = state(2);
180  out->pose.orientation.z = state(3);
181  out->twist.angular.x = state(4);
182  out->twist.angular.y = state(5);
183  out->twist.angular.z = state(6);
184  return out;
185 }
186 
187 std::vector<MatrixXd > GraftUKFAttitude::predict_sigma_points(std::vector<MatrixXd >& sigma_points, double dt){
188  std::vector<MatrixXd > out;
189  for(size_t i = 0; i < sigma_points.size(); i++){
190  out.push_back(f(sigma_points[i], dt));
191  }
192  return out;
193 }
194 
197 }
198 
199 graft::GraftStatePtr GraftUKFAttitude::getMessageFromState(Matrix<double, SIZE, 1>& state, Matrix<double, SIZE, SIZE>& covariance){
200  graft::GraftStatePtr msg(new graft::GraftState());
201  msg->pose.orientation.w = state(0);
202  msg->pose.orientation.x = state(1);
203  msg->pose.orientation.y = state(2);
204  msg->pose.orientation.z = state(3);
205  msg->twist.angular.x = state(4);
206  msg->twist.angular.y = state(5);
207  msg->twist.angular.z = state(6);
208 
209  for(size_t i = 0; i < SIZE*SIZE; i++){
210  msg->covariance[i] = covariance(i);
211  }
212  return msg;
213 }
214 
215 VectorXd addElementToVector(const VectorXd& vec, const double element){
216  if(vec.size() == 0){
217  VectorXd out(1);
218  out(0) = element;
219  return out;
220  }
221  VectorXd out(vec.size() + 1);
222  out << vec, element;
223  return out;
224 }
225 
226 MatrixXd addElementToColumnMatrix(const MatrixXd& mat, const double element){
227  MatrixXd out(mat.rows() + 1, 1);
228  MatrixXd small(1, 1);
229  small(0,0) = element;
230  if(mat.rows() == 0){
231  return small;
232  }
233  out << mat, small;
234  return out;
235 }
236 
237 geometry_msgs::Vector3 normalized_acceleration(const geometry_msgs::Vector3& accel){
238  geometry_msgs::Vector3 out;
239  double mag = std::sqrt(accel.x*accel.x + accel.y*accel.y + accel.z*accel.z);
240  out.x = accel.x / mag;
241  out.y = accel.y / mag;
242  out.z = accel.z / mag;
243  return out;
244 }
245 
246 // Returns measurement vector
247 VectorXd getMeasurements(const std::vector<boost::shared_ptr<GraftSensor> >& topics, const std::vector<MatrixXd>& predicted_sigma_points, std::vector<MatrixXd>& output_measurement_sigmas, MatrixXd& output_innovation_covariance){
248  VectorXd actual_measurement;
249  output_measurement_sigmas.clear();
250  VectorXd innovation_covariance_diagonal;
251  innovation_covariance_diagonal.resize(0);
252  // Convert the predicted_sigma_points into messages
253  std::vector<graft::GraftState::ConstPtr> predicted_sigma_msgs;
254  for(size_t i = 0; i < predicted_sigma_points.size(); i++){
255  predicted_sigma_msgs.push_back(stateMsgFromMatrix(predicted_sigma_points[i]));
256  output_measurement_sigmas.push_back(MatrixXd());
257  }
258 
259 
260  // For each topic
261  for(size_t i = 0; i < topics.size(); i++){
262  // Get the measurement msg and covariance
263  graft::GraftSensorResidual::ConstPtr meas = topics[i]->z();
264  // Get the predicted measurements
265  std::vector<graft::GraftSensorResidual::ConstPtr> residuals_msgs;
266  for(size_t j = 0; j < predicted_sigma_msgs.size(); j++){
267  graft::GraftSensorResidual::Ptr msg = topics[i]->h(*predicted_sigma_msgs[j]);
268  residuals_msgs.push_back(msg);
269 
270  }
271  // Assemble outputs for this topic
272  if(meas == NULL){ // Timeout or not received or invalid, skip
273  continue;
274  }
275  // Angular Velocity X
276  if(meas->twist_covariance[21] > 1e-20){
277  actual_measurement = addElementToVector(actual_measurement, meas->twist.angular.x);
278  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[21]);
279  for(size_t j = 0; j < residuals_msgs.size(); j++){
280  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.angular.x);
281  }
282  }
283  // Angular Velocity Y
284  if(meas->twist_covariance[28] > 1e-20){
285  actual_measurement = addElementToVector(actual_measurement, meas->twist.angular.y);
286  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[28]);
287  for(size_t j = 0; j < residuals_msgs.size(); j++){
288  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.angular.y);
289  }
290  }
291  // Angular Velocity Z
292  if(meas->twist_covariance[35] > 1e-20){
293  actual_measurement = addElementToVector(actual_measurement, meas->twist.angular.z);
294  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[35]);
295  for(size_t j = 0; j < residuals_msgs.size(); j++){
296  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.angular.z);
297  }
298  }
299  // Linear Acceleration
300  if(meas->accel_covariance[0] > 1e-20 && meas->accel_covariance[4] > 1e-20 && meas->accel_covariance[8] > 1e-20){
301  geometry_msgs::Vector3 accel_meas_norm = normalized_acceleration(meas->accel);
302  actual_measurement = addElementToVector(actual_measurement, accel_meas_norm.x);
303  actual_measurement = addElementToVector(actual_measurement, accel_meas_norm.y);
304  actual_measurement = addElementToVector(actual_measurement, accel_meas_norm.z);
305  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->accel_covariance[0]);
306  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->accel_covariance[4]);
307  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->accel_covariance[8]);
308  for(size_t j = 0; j < residuals_msgs.size(); j++){
309  geometry_msgs::Vector3 res_meas_norm = normalized_acceleration(residuals_msgs[j]->accel);
310  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], res_meas_norm.x);
311  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], res_meas_norm.y);
312  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], res_meas_norm.z);
313  }
314  }
315  }
316 
317  // Convert covariance vector to matrix
318  output_innovation_covariance = innovation_covariance_diagonal.asDiagonal();
319 
320  return actual_measurement;
321 }
322 
323 void clearMessages(std::vector<boost::shared_ptr<GraftSensor> >& topics){
324  for(size_t i = 0; i < topics.size(); i++){
325  topics[i]->clearMessage();
326  }
327 }
328 
330  if(topics_.size() == 0 || topics_[0] == NULL){
331  return 0;
332  }
334  double dt = (t - last_update_time_).toSec();
335  if(last_update_time_.toSec() < 0.0001){ // No previous updates
336  ROS_WARN("Negative dt, skipping update.");
337  last_update_time_ = t;
338  return 0.0;
339  }
340  last_update_time_ = t;
341 
342  // Prediction
343  double lambda = alpha_*alpha_*(SIZE + kappa_) - SIZE;
344  std::vector<MatrixXd > previous_sigma_points = generateSigmaPoints(graft_state_, graft_covariance_, lambda);
345  std::vector<MatrixXd > predicted_sigma_points = predict_sigma_points(previous_sigma_points, dt);
346  MatrixXd predicted_mean = meanFromSigmaPoints(predicted_sigma_points, graft_state_.rows(), lambda);
347  MatrixXd predicted_covariance = covarianceFromSigmaPoints(predicted_sigma_points, predicted_mean, Q_, graft_state_.rows(), alpha_, beta_, lambda);
348 
349  // Update
350  std::vector<MatrixXd> observation_sigma_points = generateSigmaPoints(predicted_mean, predicted_covariance, lambda);
351  std::vector<MatrixXd> predicted_observation_sigma_points;
352  MatrixXd measurement_noise;
353  MatrixXd z = getMeasurements(topics_, observation_sigma_points, predicted_observation_sigma_points, measurement_noise);
354  if(z.size() == 0){ // No measurements
355  return 0.0;
356  }
357  MatrixXd predicted_measurement = meanFromSigmaPoints(predicted_observation_sigma_points, graft_state_.rows(), lambda);
358  MatrixXd predicted_measurement_uncertainty = covarianceFromSigmaPoints(predicted_observation_sigma_points, predicted_measurement, measurement_noise, graft_state_.rows(), alpha_, beta_, lambda);
359  MatrixXd cross_covariance = crossCovariance(observation_sigma_points, predicted_mean, predicted_observation_sigma_points, predicted_measurement, alpha_, beta_, lambda);
360  MatrixXd K = cross_covariance * predicted_measurement_uncertainty.partialPivLu().inverse();
361  graft_state_ = predicted_mean + K*(z - predicted_measurement);
362  graft_state_.block(0, 0, 4, 1) = unitQuaternion(graft_state_.block(0, 0, 4, 1));
363  graft_covariance_ = predicted_covariance - K*predicted_measurement_uncertainty*K.transpose();
364 
366  return dt;
367 }
368 
370  topics_ = topics;
371 }
372 
373 void GraftUKFAttitude::setInitialCovariance(std::vector<double>& P){
374  graft_covariance_.setZero();
375  size_t diagonal_size = std::sqrt(graft_covariance_.size());
376  if(P.size() == graft_covariance_.size()){ // Full matrix
377  for(size_t i = 0; i < P.size(); i++){
378  graft_covariance_(i) = P[i];
379  }
380  } else if(P.size() == diagonal_size){ // Diagonal matrix
381  for(size_t i = 0; i < P.size(); i++){
382  graft_covariance_(i*(diagonal_size+1)) = P[i];
383  }
384  } else { // Not specified correctly
385  ROS_ERROR("initial_covariance is size %zu, expected %zu.\nUsing Identity.\nThis probably won't work well.", P.size(), graft_covariance_.size());
386  graft_covariance_.setIdentity();
387  }
388  std::cout << "cov:\n" << graft_covariance_ << std::endl;
389 }
390 
391 void GraftUKFAttitude::setProcessNoise(std::vector<double>& Q){
392  Q_.setZero();
393  size_t diagonal_size = std::sqrt(Q_.size());
394  if(Q.size() == Q_.size()){ // Full process nosie matrix
395  for(size_t i = 0; i < Q.size(); i++){
396  Q_(i) = Q[i];
397  }
398  } else if(Q.size() == diagonal_size){ // Diagonal matrix
399  for(size_t i = 0; i < Q.size(); i++){
400  Q_(i*(diagonal_size+1)) = Q[i];
401  }
402  } else { // Not specified correctly
403  ROS_ERROR("Process noise parameter 'Q' is size %zu, expected %zu.\nUsing 0.1*Identity.\nThis probably won't work well.", Q.size(), Q_.size());
404  Q_.setIdentity();
405  Q_ = 0.1 * Q_;
406  }
407 }
408 
409 void GraftUKFAttitude::setAlpha(const double alpha){
410  alpha_ = alpha;
411 }
412 
413 void GraftUKFAttitude::setKappa(const double kappa){
414  kappa_ = kappa;
415 }
416 
417 void GraftUKFAttitude::setBeta(const double beta){
418  beta_ = beta;
419 }
GraftUKFAttitude::beta_
double beta_
Definition: GraftUKFAttitude.h:90
GraftUKFAttitude::kappa_
double kappa_
Definition: GraftUKFAttitude.h:91
boost::shared_ptr
GraftUKFAttitude::~GraftUKFAttitude
~GraftUKFAttitude()
Definition: GraftUKFAttitude.cpp:45
s
XmlRpcServer s
GraftUKFAttitude::setTopics
void setTopics(std::vector< boost::shared_ptr< GraftSensor > > &topics)
Definition: GraftUKFAttitude.cpp:369
getMeasurements
VectorXd getMeasurements(const std::vector< boost::shared_ptr< GraftSensor > > &topics, const std::vector< MatrixXd > &predicted_sigma_points, std::vector< MatrixXd > &output_measurement_sigmas, MatrixXd &output_innovation_covariance)
Definition: GraftUKFAttitude.cpp:247
GraftUKFAttitude::last_update_time_
ros::Time last_update_time_
Definition: GraftUKFAttitude.h:86
GraftUKFAttitude::setAlpha
void setAlpha(const double alpha)
Definition: GraftUKFAttitude.cpp:409
TimeBase< Time, Duration >::toSec
double toSec() const
matrixSqrt
MatrixXd matrixSqrt(MatrixXd matrix)
Definition: GraftUKFAttitude.cpp:69
GraftUKFAttitude::setBeta
void setBeta(const double beta)
Definition: GraftUKFAttitude.cpp:417
GraftUKFAttitude.h
GraftUKFAttitude::graft_control_
Matrix< double, SIZE, 1 > graft_control_
Definition: GraftUKFAttitude.h:81
GraftUKFAttitude::predictAndUpdate
double predictAndUpdate()
Definition: GraftUKFAttitude.cpp:329
GraftUKFAttitude::topics_
std::vector< boost::shared_ptr< GraftSensor > > topics_
Definition: GraftUKFAttitude.h:93
GraftUKFAttitude::getMessageFromState
graft::GraftStatePtr getMessageFromState()
Definition: GraftUKFAttitude.cpp:195
GraftUKFAttitude::f
MatrixXd f(MatrixXd x, double dt)
Definition: GraftUKFAttitude.cpp:164
console.h
GraftUKFAttitude::graft_state_
Matrix< double, SIZE, 1 > graft_state_
Definition: GraftUKFAttitude.h:80
GraftUKFAttitude::GraftUKFAttitude
GraftUKFAttitude()
Definition: GraftUKFAttitude.cpp:37
GraftUKFAttitude::alpha_
double alpha_
Definition: GraftUKFAttitude.h:89
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
clearMessages
void clearMessages(std::vector< boost::shared_ptr< GraftSensor > > &topics)
Definition: GraftUKFAttitude.cpp:323
verticalConcatenate
VectorXd verticalConcatenate(VectorXd &m, VectorXd &n)
Definition: GraftUKFAttitude.cpp:49
quaternionUpdateMatrix
Matrix< double, 4, 4 > quaternionUpdateMatrix(const double wx, const double wy, const double wz)
Definition: GraftUKFAttitude.cpp:128
ROS_WARN
#define ROS_WARN(...)
GraftUKFAttitude::setProcessNoise
void setProcessNoise(std::vector< double > &Q)
Definition: GraftUKFAttitude.cpp:391
crossCovariance
MatrixXd crossCovariance(std::vector< MatrixXd > &sigma_points, MatrixXd &mean, std::vector< MatrixXd > &meas_sigma_points, MatrixXd &meas_mean, double alpha, double beta, double lambda)
Definition: GraftUKFAttitude.cpp:117
normalized_acceleration
geometry_msgs::Vector3 normalized_acceleration(const geometry_msgs::Vector3 &accel)
Definition: GraftUKFAttitude.cpp:237
addElementToVector
VectorXd addElementToVector(const VectorXd &vec, const double element)
Definition: GraftUKFAttitude.cpp:215
stateMsgFromMatrix
graft::GraftState::ConstPtr stateMsgFromMatrix(const MatrixXd &state)
Definition: GraftUKFAttitude.cpp:175
covarianceFromSigmaPoints
MatrixXd covarianceFromSigmaPoints(std::vector< MatrixXd > &sigma_points, MatrixXd &mean, MatrixXd process_noise, double n, double alpha, double beta, double lambda)
Definition: GraftUKFAttitude.cpp:107
GraftUKFAttitude::setKappa
void setKappa(const double kappa)
Definition: GraftUKFAttitude.cpp:413
ros::Time
unitQuaternion
Matrix< double, 4, 1 > unitQuaternion(const Matrix< double, 4, 1 > &q)
Definition: GraftUKFAttitude.cpp:137
GraftUKFAttitude::setInitialCovariance
void setInitialCovariance(std::vector< double > &P)
Definition: GraftUKFAttitude.cpp:373
GraftUKFAttitude::graft_covariance_
Matrix< double, SIZE, SIZE > graft_covariance_
Definition: GraftUKFAttitude.h:82
updatedQuaternion
Matrix< double, 4, 1 > updatedQuaternion(const Matrix< double, 4, 1 > &q, const double wx, const double wy, const double wz, double dt)
Definition: GraftUKFAttitude.cpp:142
ROS_ERROR
#define ROS_ERROR(...)
GraftUKFAttitude::predict_sigma_points
std::vector< MatrixXd > predict_sigma_points(std::vector< MatrixXd > &sigma_points, double dt)
Definition: GraftUKFAttitude.cpp:187
generateSigmaPoints
std::vector< MatrixXd > generateSigmaPoints(MatrixXd state, MatrixXd covariance, double lambda)
Definition: GraftUKFAttitude.cpp:74
SIZE
#define SIZE
Definition: GraftUKFAbsolute.h:47
addElementToColumnMatrix
MatrixXd addElementToColumnMatrix(const MatrixXd &mat, const double element)
Definition: GraftUKFAttitude.cpp:226
GraftUKFAttitude::Q_
Matrix< double, SIZE, SIZE > Q_
Definition: GraftUKFAttitude.h:84
ros::Time::now
static Time now()


graft
Author(s): Chad Rockey
autogenerated on Wed Mar 2 2022 00:20:33