GraftUKFAbsolute.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/GraftUKFAbsolute.h>
35  #include <ros/console.h>
36 
38  graft_state_.setZero();
39  graft_state_(3) = 1.0; // Normalize quaternion
40  graft_control_.setZero();
41  graft_covariance_.setIdentity();
42  Q_.setZero();
43  }
44 
46 
47 }
48 
49 MatrixXd verticalConcatenate(MatrixXd& m, MatrixXd& n){
50  MatrixXd out;
51  out.resize(m.rows()+n.rows(), m.cols());
52  out << m,n;
53  return out;
54 }
55 
56 MatrixXd matrixSqrt(MatrixXd matrix){
57  // Use LLT Cholesky decomposiion to create stable Matrix Sqrt
58  return Eigen::LLT<Eigen::MatrixXd>(matrix).matrixL();
59 }
60 
61 std::vector<MatrixXd > generateSigmaPoints(MatrixXd state, MatrixXd covariance, double lambda){
62  std::vector<MatrixXd > out;
63 
64  double gamma = std::sqrt((state.rows()+lambda));
65  MatrixXd sig_sqrt = gamma*matrixSqrt(covariance);
66 
67  // i = 0, push back state as is
68  out.push_back(state);
69 
70  // i = 1,...,n
71  for(size_t i = 1; i <= state.rows(); i++){
72  out.push_back(state + sig_sqrt.col(i-1));
73  }
74 
75  // i = n + 1,...,2n
76  for(size_t i = state.rows() + 1; i <= 2*state.rows(); i++){
77  out.push_back(state - sig_sqrt.col(i-(state.rows()+1)));
78  }
79  return out;
80 }
81 
82 MatrixXd meanFromSigmaPoints(std::vector<MatrixXd >& sigma_points, double n, double lambda){
83  double weight_zero = lambda / (n + lambda);
84  MatrixXd out = weight_zero * sigma_points[0];
85  double weight_i = 1.0/(2*(n + lambda));
86  for(size_t i = 1; i <= 2*n; i++){
87  out = out + weight_i * sigma_points[i];
88  }
89  return out;
90 }
91 
93 MatrixXd covarianceFromSigmaPoints(std::vector<MatrixXd >& sigma_points, MatrixXd& mean, MatrixXd process_noise, double n, double alpha, double beta, double lambda){
94  double cov_weight_zero = lambda / (n + lambda) + (1 - alpha*alpha + beta);
95  MatrixXd out = cov_weight_zero * (sigma_points[0] - mean) * (sigma_points[0] - mean).transpose();
96  double weight_i = 1.0/(2*(n + lambda));
97  for(size_t i = 1; i <= 2*n; i++){
98  out = out + weight_i * (sigma_points[i] - mean) * (sigma_points[i] - mean).transpose();
99  }
100  return out+process_noise;
101 }
102 
103 MatrixXd crossCovariance(std::vector<MatrixXd >& sigma_points, MatrixXd& mean, std::vector<MatrixXd >& meas_sigma_points, MatrixXd& meas_mean, double alpha, double beta, double lambda){
104  double n = sigma_points[0].rows();
105  double cov_weight_zero = lambda / (n + lambda) + (1 - alpha*alpha + beta);
106  MatrixXd out = cov_weight_zero * (sigma_points[0] - mean) * (meas_sigma_points[0] - meas_mean).transpose();
107  double weight_i = 1.0/(2*(n + lambda));
108  for(size_t i = 1; i <= 2*n; i++){
109  out = out + weight_i * (sigma_points[i] - mean) * (meas_sigma_points[i] - meas_mean).transpose();
110  }
111  return out;
112 }
113 
114 Matrix<double, 4, 4> quaternionUpdateMatrix(const double wx, const double wy, const double wz){
115  Matrix<double, 4, 4> out;
116  out << 0, wx, wy, wz,
117  -wx, 0, -wz, wy,
118  -wy, wz, 0, -wx,
119  -wz, -wy, wx, 0;
120  return out;
121 }
122 
123 Matrix<double, 4, 1> unitQuaternion(const Matrix<double, 4, 1>& q){
124  double q_mag = std::sqrt(q(0)*q(0) + q(1)*q(1) + q(2)*q(2) + q(3)*q(3));
125  return q / q_mag;
126 }
127 
128 Matrix<double, 4, 1> updatedQuaternion(const Matrix<double, 4, 1>& q, const double wx, const double wy, const double wz, double dt){
129  Matrix<double, 4, 1> out;
130  Matrix<double, 4, 4> I = Matrix<double, 4, 4>::Identity();
131  double s = 1.0/2.0 * std::sqrt(wx*wx*dt*dt + wy*wy*dt*dt + wz*wz*dt*dt);
132  double k = 0.0;
133  double q_mag = std::sqrt(q(0)*q(0) + q(1)*q(1) + q(2)*q(2) + q(3)*q(3));
134  double err = 1.0 - q_mag*q_mag;
135 
136  double correction_factor = 1 - 1.0/2.0*s*s + 1.0/24.0*s*s*s*s + k * dt * err; // Cosine taylor series
137  MatrixXd correction = I*(correction_factor);
138  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
139  Matrix<double, 4, 4> quaterion_update_matrix = quaternionUpdateMatrix(wx, wy, wz);
140  MatrixXd update = update_factor*quaterion_update_matrix;
141  out = (correction-update)*q;
142 
143 
144  double out_mag = std::sqrt(out(0)*out(0) + out(1)*out(1) + out(2)*out(2) + out(3)*out(3));
145  double out_err = 1.0 - out_mag*out_mag;
146 
147  return out;
148 }
149 
150 MatrixXd transformVelocitites(const MatrixXd vel, const MatrixXd quaternion){
151  Matrix<double, 3, 1> out;
152  geometry_msgs::Quaternion gquat;
153  gquat.w = quaternion(0);
154  gquat.x = quaternion(1);
155  gquat.y = quaternion(2);
156  gquat.z = quaternion(3);
157  tf::Quaternion tfq;
158  tf::quaternionMsgToTF(gquat, tfq);
159  tf::Transform tft(tfq, tf::Vector3(0, 0, 0));
160  tf::Vector3 vel_vector(vel(0), vel(1), vel(2));
161  tf::Vector3 transformed = tft*vel_vector; // .inverse()
162 
163  out(0) = transformed.getX();
164  out(1) = transformed.getY();
165  out(2) = transformed.getZ();
166 
167  return out;
168 }
169 
170 MatrixXd GraftUKFAbsolute::f(MatrixXd x, double dt){
171  Matrix<double, SIZE, 1> out;
172  out.setZero();
173  MatrixXd rotated_linear_velocity = transformVelocitites(x.block(7, 0, 3, 1), x.block(3, 0, 4, 1));
174  out(0) = x(0)+rotated_linear_velocity(0)*dt; // x + v_absx*dt
175  out(1) = x(1)+rotated_linear_velocity(1)*dt; // y + v_absy*dt
176  out(2) = x(2)+rotated_linear_velocity(2)*dt; // z + v_absz*dt
177  Matrix<double, 4, 1> new_q = updatedQuaternion(x.block(3, 0, 4, 1), x(10), x(11), x(12), dt);
178  out.block(3, 0, 4, 1) = new_q; // quaternion
179  out(7) = x(7); // vx
180  out(8) = x(8); // vy
181  out(9) = x(9); // vz
182  out(10) = x(10); // wz
183  out(11) = x(11); // wy
184  out(12) = x(12); // wz
185  return out;
186 }
187 
188 graft::GraftState::ConstPtr stateMsgFromMatrix(const MatrixXd& state){
189  graft::GraftState::Ptr out(new graft::GraftState());
190  out->pose.position.x = state(0);
191  out->pose.position.y = state(1);
192  out->pose.position.z = state(2);
193  out->pose.orientation.w = state(3);
194  out->pose.orientation.x = state(4);
195  out->pose.orientation.y = state(5);
196  out->pose.orientation.z = state(6);
197  out->twist.linear.x = state(7);
198  out->twist.linear.y = state(8);
199  out->twist.linear.z = state(9);
200  out->twist.angular.x = state(10);
201  out->twist.angular.y = state(11);
202  out->twist.angular.z = state(12);
203  return out;
204 }
205 
206 std::vector<MatrixXd > GraftUKFAbsolute::predict_sigma_points(std::vector<MatrixXd >& sigma_points, double dt){
207  std::vector<MatrixXd > out;
208  for(size_t i = 0; i < sigma_points.size(); i++){
209  out.push_back(f(sigma_points[i], dt));
210  }
211  return out;
212 }
213 
216 }
217 
218 graft::GraftStatePtr GraftUKFAbsolute::getMessageFromState(Matrix<double, SIZE, 1>& state, Matrix<double, SIZE, SIZE>& covariance){
219  graft::GraftStatePtr msg(new graft::GraftState());
220  msg->pose.position.x = state(0);
221  msg->pose.position.y = state(1);
222  msg->pose.position.z = state(2);
223  msg->pose.orientation.w = state(3);
224  msg->pose.orientation.x = state(4);
225  msg->pose.orientation.y = state(5);
226  msg->pose.orientation.z = state(6);
227  msg->twist.linear.x = state(7);
228  msg->twist.linear.y = state(8);
229  msg->twist.linear.z = state(9);
230  msg->twist.angular.x = state(10);
231  msg->twist.angular.y = state(11);
232  msg->twist.angular.z = state(12);
233 
234  for(size_t i = 0; i < SIZE*SIZE; i++){
235  msg->covariance[i] = covariance(i);
236  }
237  return msg;
238 }
239 
240 VectorXd addElementToVector(const VectorXd& vec, const double& element){
241  VectorXd out(vec.size() + 1);
242  out << vec, element;
243  return out;
244 }
245 
246 MatrixXd addElementToColumnMatrix(const MatrixXd& mat, const double& element){
247  MatrixXd out(mat.rows() + 1, 1);
248  MatrixXd small(1, 1);
249  small(0,0) = element;
250  if(mat.rows() == 0){
251  return small;
252  }
253  out << mat, small;
254  return out;
255 }
256 
257 // Returns measurement vector
258 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){
259  VectorXd actual_measurement;
260  output_measurement_sigmas.clear();
261  VectorXd innovation_covariance_diagonal;
262  innovation_covariance_diagonal.resize(0);
263  // Convert the predicted_sigma_points into messages
264  std::vector<graft::GraftState::ConstPtr> predicted_sigma_msgs;
265  for(size_t i = 0; i < predicted_sigma_points.size(); i++){
266  predicted_sigma_msgs.push_back(stateMsgFromMatrix(predicted_sigma_points[i]));
267  output_measurement_sigmas.push_back(MatrixXd());
268  }
269 
270 
271  // For each topic
272  for(size_t i = 0; i < topics.size(); i++){
273  // Get the measurement msg and covariance
274  graft::GraftSensorResidual::ConstPtr meas = topics[i]->z();
275  // Get the predicted measurements
276  std::vector<graft::GraftSensorResidual::ConstPtr> residuals_msgs;
277  for(size_t j = 0; j < predicted_sigma_msgs.size(); j++){
278  residuals_msgs.push_back(topics[i]->h(*predicted_sigma_msgs[j]));
279  }
280  // Assemble outputs for this topic
281  if(meas == NULL){ // Timeout or not received or invalid, skip
282  continue;
283  }
284  // Position X
285  if(meas->pose_covariance[0] > 1e-20){
286  actual_measurement = addElementToVector(actual_measurement, meas->pose.position.x);
287  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->pose_covariance[0]);
288  for(size_t j = 0; j < residuals_msgs.size(); j++){
289  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->pose.position.x);
290  }
291  }
292  // Position Y
293  if(meas->pose_covariance[7] > 1e-20){
294  actual_measurement = addElementToVector(actual_measurement, meas->pose.position.y);
295  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->pose_covariance[7]);
296  for(size_t j = 0; j < residuals_msgs.size(); j++){
297  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->pose.position.y);
298  }
299  }
300  // Position Z
301  if(meas->pose_covariance[14] > 1e-20){
302  actual_measurement = addElementToVector(actual_measurement, meas->pose.position.z);
303  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->pose_covariance[14]);
304  for(size_t j = 0; j < residuals_msgs.size(); j++){
305  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->pose.position.z);
306  }
307  }
308  // Linear Velocity X
309  if(meas->twist_covariance[0] > 1e-20){
310  actual_measurement = addElementToVector(actual_measurement, meas->twist.linear.x);
311  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[0]);
312  for(size_t j = 0; j < residuals_msgs.size(); j++){
313  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.linear.x);
314  }
315  }
316  // Linear Velocity Y
317  if(meas->twist_covariance[7] > 1e-20){
318  actual_measurement = addElementToVector(actual_measurement, meas->twist.linear.y);
319  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[7]);
320  for(size_t j = 0; j < residuals_msgs.size(); j++){
321  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.linear.y);
322  }
323  }
324  // Linear Velocity Z
325  if(meas->twist_covariance[14] > 1e-20){
326  actual_measurement = addElementToVector(actual_measurement, meas->twist.linear.z);
327  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[14]);
328  for(size_t j = 0; j < residuals_msgs.size(); j++){
329  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.linear.z);
330  }
331  }
332  // Angular Velocity X
333  if(meas->twist_covariance[21] > 1e-20){
334  actual_measurement = addElementToVector(actual_measurement, meas->twist.angular.x);
335  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[21]);
336  for(size_t j = 0; j < residuals_msgs.size(); j++){
337  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.angular.x);
338  }
339  }
340  // Angular Velocity Y
341  if(meas->twist_covariance[28] > 1e-20){
342  actual_measurement = addElementToVector(actual_measurement, meas->twist.angular.y);
343  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[28]);
344  for(size_t j = 0; j < residuals_msgs.size(); j++){
345  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.angular.y);
346  }
347  }
348  // Angular Velocity Z
349  if(meas->twist_covariance[35] > 1e-20){
350  actual_measurement = addElementToVector(actual_measurement, meas->twist.angular.z);
351  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[35]);
352  for(size_t j = 0; j < residuals_msgs.size(); j++){
353  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.angular.z);
354  }
355  }
356  }
357 
358  // Convert covariance vector to matrix
359  output_innovation_covariance = innovation_covariance_diagonal.asDiagonal();
360 
361  return actual_measurement;
362 }
363 
364 void clearMessages(std::vector<boost::shared_ptr<GraftSensor> >& topics){
365  for(size_t i = 0; i < topics.size(); i++){
366  topics[i]->clearMessage();
367  }
368 }
369 
371  if(topics_.size() == 0 || topics_[0] == NULL){
372  return 0;
373  }
375  double dt = (t - last_update_time_).toSec();
376  if(last_update_time_.toSec() < 0.0001){ // No previous updates
377  ROS_WARN("Negative dt - odom");
378  last_update_time_ = t;
379  return 0.0;
380  }
381  last_update_time_ = t;
382 
383  // Prediction
384  double lambda = alpha_*alpha_*(SIZE + kappa_) - SIZE;
385  std::vector<MatrixXd > previous_sigma_points = generateSigmaPoints(graft_state_, graft_covariance_, lambda);
386  std::vector<MatrixXd > predicted_sigma_points = predict_sigma_points(previous_sigma_points, dt);
387  MatrixXd predicted_mean = meanFromSigmaPoints(predicted_sigma_points, graft_state_.rows(), lambda);
388  MatrixXd predicted_covariance = covarianceFromSigmaPoints(predicted_sigma_points, predicted_mean, Q_, graft_state_.rows(), alpha_, beta_, lambda);
389 
390  // Update
391  std::vector<MatrixXd> observation_sigma_points = generateSigmaPoints(predicted_mean, predicted_covariance, lambda);
392  std::vector<MatrixXd> predicted_observation_sigma_points;
393  MatrixXd measurement_noise;
394  MatrixXd z = getMeasurements(topics_, observation_sigma_points, predicted_observation_sigma_points, measurement_noise);
395  if(z.size() == 0){ // No measurements
396  return 0.0;
397  }
398  MatrixXd predicted_measurement = meanFromSigmaPoints(predicted_observation_sigma_points, graft_state_.rows(), lambda);
399  MatrixXd predicted_measurement_uncertainty = covarianceFromSigmaPoints(predicted_observation_sigma_points, predicted_measurement, measurement_noise, graft_state_.rows(), alpha_, beta_, lambda);
400  MatrixXd cross_covariance = crossCovariance(observation_sigma_points, predicted_mean, predicted_observation_sigma_points, predicted_measurement, alpha_, beta_, lambda);
401  MatrixXd K = cross_covariance * predicted_measurement_uncertainty.partialPivLu().inverse();
402  graft_state_ = predicted_mean + K*(z - predicted_measurement);
403  graft_state_.block(3, 0, 4, 1) = unitQuaternion(graft_state_.block(3, 0, 4, 1));
404 
405  graft_covariance_ = predicted_covariance - K*predicted_measurement_uncertainty*K.transpose();
406 
408  return dt;
409 }
410 
412  topics_ = topics;
413 }
414 
415 void GraftUKFAbsolute::setInitialCovariance(std::vector<double>& P){
416  graft_covariance_.setZero();
417  size_t diagonal_size = std::sqrt(graft_covariance_.size());
418  if(P.size() == graft_covariance_.size()){ // Full matrix
419  for(size_t i = 0; i < P.size(); i++){
420  graft_covariance_(i) = P[i];
421  }
422  } else if(P.size() == diagonal_size){ // Diagonal matrix
423  for(size_t i = 0; i < P.size(); i++){
424  graft_covariance_(i*(diagonal_size+1)) = P[i];
425  }
426  } else { // Not specified correctly
427  ROS_ERROR("initial_covariance is size %zu, expected %zu.\nUsing 0.1*Identity.\nThis probably won't work well.", P.size(), graft_covariance_.size());
428  graft_covariance_.setIdentity();
430  }
431 }
432 
433 void GraftUKFAbsolute::setProcessNoise(std::vector<double>& Q){
434  Q_.setZero();
435  size_t diagonal_size = std::sqrt(Q_.size());
436  if(Q.size() == Q_.size()){ // Full process nosie matrix
437  for(size_t i = 0; i < Q.size(); i++){
438  Q_(i) = Q[i];
439  }
440  } else if(Q.size() == diagonal_size){ // Diagonal matrix
441  for(size_t i = 0; i < Q.size(); i++){
442  Q_(i*(diagonal_size+1)) = Q[i];
443  }
444  } else { // Not specified correctly
445  ROS_ERROR("process_noise parameter is size %zu, expected %zu.\nUsing 0.1*Identity.\nThis probably won't work well.", Q.size(), Q_.size());
446  Q_.setIdentity();
447  Q_ = 0.1 * Q_;
448  }
449 }
450 
451 void GraftUKFAbsolute::setAlpha(const double alpha){
452  alpha_ = alpha;
453 }
454 
455 void GraftUKFAbsolute::setKappa(const double kappa){
456  kappa_ = kappa;
457 }
458 
459 void GraftUKFAbsolute::setBeta(const double beta){
460  beta_ = beta;
461 }
GraftUKFAbsolute::beta_
double beta_
Definition: GraftUKFAbsolute.h:90
covarianceFromSigmaPoints
MatrixXd covarianceFromSigmaPoints(std::vector< MatrixXd > &sigma_points, MatrixXd &mean, MatrixXd process_noise, double n, double alpha, double beta, double lambda)
Definition: GraftUKFAbsolute.cpp:93
GraftUKFAbsolute::GraftUKFAbsolute
GraftUKFAbsolute()
Definition: GraftUKFAbsolute.cpp:37
GraftUKFAbsolute::f
MatrixXd f(MatrixXd x, double dt)
Definition: GraftUKFAbsolute.cpp:170
boost::shared_ptr
GraftUKFAbsolute::setAlpha
void setAlpha(const double alpha)
Definition: GraftUKFAbsolute.cpp:451
GraftUKFAbsolute::setBeta
void setBeta(const double beta)
Definition: GraftUKFAbsolute.cpp:459
s
XmlRpcServer s
GraftUKFAbsolute::setTopics
void setTopics(std::vector< boost::shared_ptr< GraftSensor > > &topics)
Definition: GraftUKFAbsolute.cpp:411
tf::quaternionMsgToTF
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
TimeBase< Time, Duration >::toSec
double toSec() const
GraftUKFAbsolute::graft_state_
Matrix< double, SIZE, 1 > graft_state_
Definition: GraftUKFAbsolute.h:80
GraftUKFAbsolute::setProcessNoise
void setProcessNoise(std::vector< double > &Q)
Definition: GraftUKFAbsolute.cpp:433
GraftUKFAbsolute::getMessageFromState
graft::GraftStatePtr getMessageFromState()
Definition: GraftUKFAbsolute.cpp:214
GraftUKFAbsolute::~GraftUKFAbsolute
~GraftUKFAbsolute()
Definition: GraftUKFAbsolute.cpp:45
matrixSqrt
MatrixXd matrixSqrt(MatrixXd matrix)
Definition: GraftUKFAbsolute.cpp:56
console.h
addElementToColumnMatrix
MatrixXd addElementToColumnMatrix(const MatrixXd &mat, const double &element)
Definition: GraftUKFAbsolute.cpp:246
stateMsgFromMatrix
graft::GraftState::ConstPtr stateMsgFromMatrix(const MatrixXd &state)
Definition: GraftUKFAbsolute.cpp:188
updatedQuaternion
Matrix< double, 4, 1 > updatedQuaternion(const Matrix< double, 4, 1 > &q, const double wx, const double wy, const double wz, double dt)
Definition: GraftUKFAbsolute.cpp:128
generateSigmaPoints
std::vector< MatrixXd > generateSigmaPoints(MatrixXd state, MatrixXd covariance, double lambda)
Definition: GraftUKFAbsolute.cpp:61
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
GraftUKFAbsolute::topics_
std::vector< boost::shared_ptr< GraftSensor > > topics_
Definition: GraftUKFAbsolute.h:93
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: GraftUKFAbsolute.cpp:103
addElementToVector
VectorXd addElementToVector(const VectorXd &vec, const double &element)
Definition: GraftUKFAbsolute.cpp:240
GraftUKFAbsolute::last_update_time_
ros::Time last_update_time_
Definition: GraftUKFAbsolute.h:86
ROS_WARN
#define ROS_WARN(...)
GraftUKFAbsolute::Q_
Matrix< double, SIZE, SIZE > Q_
Definition: GraftUKFAbsolute.h:84
tf::Transform
clearMessages
void clearMessages(std::vector< boost::shared_ptr< GraftSensor > > &topics)
Definition: GraftUKFAbsolute.cpp:364
unitQuaternion
Matrix< double, 4, 1 > unitQuaternion(const Matrix< double, 4, 1 > &q)
Definition: GraftUKFAbsolute.cpp:123
GraftUKFAbsolute::setInitialCovariance
void setInitialCovariance(std::vector< double > &P)
Definition: GraftUKFAbsolute.cpp:415
ros::Time
GraftUKFAbsolute::predictAndUpdate
double predictAndUpdate()
Definition: GraftUKFAbsolute.cpp:370
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: GraftUKFAbsolute.cpp:258
ROS_ERROR
#define ROS_ERROR(...)
GraftUKFAbsolute::predict_sigma_points
std::vector< MatrixXd > predict_sigma_points(std::vector< MatrixXd > &sigma_points, double dt)
Definition: GraftUKFAbsolute.cpp:206
verticalConcatenate
MatrixXd verticalConcatenate(MatrixXd &m, MatrixXd &n)
Definition: GraftUKFAbsolute.cpp:49
GraftUKFAbsolute::setKappa
void setKappa(const double kappa)
Definition: GraftUKFAbsolute.cpp:455
SIZE
#define SIZE
Definition: GraftUKFAbsolute.h:47
GraftUKFAbsolute::graft_covariance_
Matrix< double, SIZE, SIZE > graft_covariance_
Definition: GraftUKFAbsolute.h:82
transformVelocitites
MatrixXd transformVelocitites(const MatrixXd vel, const MatrixXd quaternion)
Definition: GraftUKFAbsolute.cpp:150
GraftUKFAbsolute::graft_control_
Matrix< double, SIZE, 1 > graft_control_
Definition: GraftUKFAbsolute.h:81
GraftUKFAbsolute::kappa_
double kappa_
Definition: GraftUKFAbsolute.h:91
quaternionUpdateMatrix
Matrix< double, 4, 4 > quaternionUpdateMatrix(const double wx, const double wy, const double wz)
Definition: GraftUKFAbsolute.cpp:114
tf::Quaternion
GraftUKFAbsolute::alpha_
double alpha_
Definition: GraftUKFAbsolute.h:89
ros::Time::now
static Time now()
GraftUKFAbsolute.h


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