GraftUKFVelocity.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/GraftUKFVelocity.h>
35  #include <ros/console.h>
36 
38  graft_state_.setZero();
39  graft_control_.setZero();
40  graft_covariance_.setIdentity();
41  Q_.setZero();
42  }
43 
45 
46 }
47 
48 MatrixXd verticalConcatenate(MatrixXd& m, MatrixXd& n){
49  MatrixXd out;
50  out.resize(m.rows()+n.rows(), m.cols());
51  out << m,n;
52  return out;
53 }
54 
55 MatrixXd matrixSqrt(MatrixXd matrix){
56  // Use LLT Cholesky decomposiion to create stable Matrix Sqrt
57  return Eigen::LLT<Eigen::MatrixXd>(matrix).matrixL();
58 }
59 
60 std::vector<MatrixXd > generateSigmaPoints(MatrixXd state, MatrixXd covariance, double lambda){
61  std::vector<MatrixXd > out;
62 
63  double gamma = std::sqrt((state.rows()+lambda));
64  MatrixXd sig_sqrt = gamma*matrixSqrt(covariance);
65 
66  // i = 0, push back state as is
67  out.push_back(state);
68 
69  // i = 1,...,n
70  for(size_t i = 1; i <= state.rows(); i++){
71  out.push_back(state + sig_sqrt.col(i-1));
72  }
73 
74  // i = n + 1,...,2n
75  for(size_t i = state.rows() + 1; i <= 2*state.rows(); i++){
76  out.push_back(state - sig_sqrt.col(i-(state.rows()+1)));
77  }
78  return out;
79 }
80 
81 MatrixXd meanFromSigmaPoints(std::vector<MatrixXd >& sigma_points, double n, double lambda){
82  double weight_zero = lambda / (n + lambda);
83  MatrixXd out = weight_zero * sigma_points[0];
84  double weight_i = 1.0/(2*(n + lambda));
85  for(size_t i = 1; i <= 2*n; i++){
86  out = out + weight_i * sigma_points[i];
87  }
88  return out;
89 }
90 
92 MatrixXd covarianceFromSigmaPoints(std::vector<MatrixXd >& sigma_points, MatrixXd& mean, MatrixXd process_noise, double n, double alpha, double beta, double lambda){
93  double cov_weight_zero = lambda / (n + lambda) + (1 - alpha*alpha + beta);
94  MatrixXd out = cov_weight_zero * (sigma_points[0] - mean) * (sigma_points[0] - mean).transpose();
95  double weight_i = 1.0/(2*(n + lambda));
96  for(size_t i = 1; i <= 2*n; i++){
97  out = out + weight_i * (sigma_points[i] - mean) * (sigma_points[i] - mean).transpose();
98  }
99  return out+process_noise;
100 }
101 
102 MatrixXd crossCovariance(std::vector<MatrixXd >& sigma_points, MatrixXd& mean, std::vector<MatrixXd >& meas_sigma_points, MatrixXd& meas_mean, double alpha, double beta, double lambda){
103  double n = sigma_points[0].rows();
104  double cov_weight_zero = lambda / (n + lambda) + (1 - alpha*alpha + beta);
105  MatrixXd out = cov_weight_zero * (sigma_points[0] - mean) * (meas_sigma_points[0] - meas_mean).transpose();
106  double weight_i = 1.0/(2*(n + lambda));
107  for(size_t i = 1; i <= 2*n; i++){
108  out = out + weight_i * (sigma_points[i] - mean) * (meas_sigma_points[i] - meas_mean).transpose();
109  }
110  return out;
111 }
112 
113 
114 MatrixXd GraftUKFVelocity::f(MatrixXd x, double dt){
115  Matrix<double, SIZE, 1> out;
116  out.setZero();
117  out(0) = x(0);
118  out(1) = x(1);
119  return out;
120 }
121 
122 graft::GraftState::ConstPtr stateMsgFromMatrix(const MatrixXd& state){
123  graft::GraftState::Ptr out(new graft::GraftState());
124  out->twist.linear.x = state(0);
125  out->twist.linear.y = state(1);
126  out->twist.angular.z = state(2);
127  return out;
128 }
129 
130 std::vector<MatrixXd > GraftUKFVelocity::predict_sigma_points(std::vector<MatrixXd >& sigma_points, double dt){
131  std::vector<MatrixXd > out;
132  for(size_t i = 0; i < sigma_points.size(); i++){
133  out.push_back(f(sigma_points[i], dt));
134  }
135  return out;
136 }
137 
140 }
141 
142 graft::GraftStatePtr GraftUKFVelocity::getMessageFromState(Matrix<double, SIZE, 1>& state, Matrix<double, SIZE, SIZE>& covariance){
143  graft::GraftStatePtr msg(new graft::GraftState());
144  msg->twist.linear.x = state(0);
145  msg->twist.linear.y = state(1);
146  msg->twist.angular.z = state(2);
147 
148  for(size_t i = 0; i < SIZE*SIZE; i++){
149  msg->covariance[i] = covariance(i);
150  }
151  return msg;
152 }
153 
154 VectorXd addElementToVector(const VectorXd& vec, const double& element){
155  VectorXd out(vec.size() + 1);
156  out << vec, element;
157  return out;
158 }
159 
160 MatrixXd addElementToColumnMatrix(const MatrixXd& mat, const double& element){
161  MatrixXd out(mat.rows() + 1, 1);
162  MatrixXd small(1, 1);
163  small(0,0) = element;
164  if(mat.rows() == 0){
165  return small;
166  }
167  out << mat, small;
168  return out;
169 }
170 
171 // Returns measurement vector
172 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){
173  VectorXd actual_measurement;
174  output_measurement_sigmas.clear();
175  VectorXd innovation_covariance_diagonal;
176  innovation_covariance_diagonal.resize(0);
177  // Convert the predicted_sigma_points into messages
178  std::vector<graft::GraftState::ConstPtr> predicted_sigma_msgs;
179  for(size_t i = 0; i < predicted_sigma_points.size(); i++){
180  predicted_sigma_msgs.push_back(stateMsgFromMatrix(predicted_sigma_points[i]));
181  output_measurement_sigmas.push_back(MatrixXd());
182  }
183 
184 
185  // For each topic
186  for(size_t i = 0; i < topics.size(); i++){
187  // Get the measurement msg and covariance
188  graft::GraftSensorResidual::ConstPtr meas = topics[i]->z();
189  // Get the predicted measurements
190  std::vector<graft::GraftSensorResidual::ConstPtr> residuals_msgs;
191  for(size_t j = 0; j < predicted_sigma_msgs.size(); j++){
192  residuals_msgs.push_back(topics[i]->h(*predicted_sigma_msgs[j]));
193  }
194  // Assemble outputs for this topic
195  if(meas == NULL){ // Timeout or not received or invalid, skip
196  continue;
197  }
198  // Linear Velocity X
199  if(meas->twist_covariance[0] > 1e-20){
200  actual_measurement = addElementToVector(actual_measurement, meas->twist.linear.x);
201  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[0]);
202  for(size_t j = 0; j < residuals_msgs.size(); j++){
203  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.linear.x);
204  }
205  }
206  // Linear Velocity Y
207  if(meas->twist_covariance[7] > 1e-20){
208  actual_measurement = addElementToVector(actual_measurement, meas->twist.linear.y);
209  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[7]);
210  for(size_t j = 0; j < residuals_msgs.size(); j++){
211  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.linear.y);
212  }
213  }
214  // Angular Velocity Z
215  if(meas->twist_covariance[35] > 1e-20){
216  actual_measurement = addElementToVector(actual_measurement, meas->twist.angular.z);
217  innovation_covariance_diagonal = addElementToVector(innovation_covariance_diagonal, meas->twist_covariance[35]);
218  for(size_t j = 0; j < residuals_msgs.size(); j++){
219  output_measurement_sigmas[j] = addElementToColumnMatrix(output_measurement_sigmas[j], residuals_msgs[j]->twist.angular.z);
220  }
221  }
222  }
223 
224  // Convert covariance vector to matrix
225  output_innovation_covariance = innovation_covariance_diagonal.asDiagonal();
226 
227  return actual_measurement;
228 }
229 
230 void clearMessages(std::vector<boost::shared_ptr<GraftSensor> >& topics){
231  for(size_t i = 0; i < topics.size(); i++){
232  topics[i]->clearMessage();
233  }
234 }
235 
237  if(topics_.size() == 0 || topics_[0] == NULL){
238  return 0;
239  }
241  double dt = (t - last_update_time_).toSec();
242  if(last_update_time_.toSec() < 0.0001){ // No previous updates
243  ROS_WARN("Negative dt - odom");
244  last_update_time_ = t;
245  return 0.0;
246  }
247  last_update_time_ = t;
248 
249  // Prediction
250  double lambda = alpha_*alpha_*(SIZE + kappa_) - SIZE;
251  std::vector<MatrixXd > previous_sigma_points = generateSigmaPoints(graft_state_, graft_covariance_, lambda);
252  std::vector<MatrixXd > predicted_sigma_points = predict_sigma_points(previous_sigma_points, 0.0);
253  MatrixXd predicted_mean = meanFromSigmaPoints(predicted_sigma_points, graft_state_.rows(), lambda);
254  MatrixXd predicted_covariance = covarianceFromSigmaPoints(predicted_sigma_points, predicted_mean, Q_, graft_state_.rows(), alpha_, beta_, lambda);
255 
256  // Update
257  std::vector<MatrixXd> observation_sigma_points = generateSigmaPoints(predicted_mean, predicted_covariance, lambda);
258  std::vector<MatrixXd> predicted_observation_sigma_points;
259  MatrixXd measurement_noise;
260  MatrixXd z = getMeasurements(topics_, observation_sigma_points, predicted_observation_sigma_points, measurement_noise);
261  if(z.size() == 0){ // No measurements
262  return 0.0;
263  }
264  MatrixXd predicted_measurement = meanFromSigmaPoints(predicted_observation_sigma_points, graft_state_.rows(), lambda);
265  MatrixXd predicted_measurement_uncertainty = covarianceFromSigmaPoints(predicted_observation_sigma_points, predicted_measurement, measurement_noise, graft_state_.rows(), alpha_, beta_, lambda);
266  MatrixXd cross_covariance = crossCovariance(observation_sigma_points, predicted_mean, predicted_observation_sigma_points, predicted_measurement, alpha_, beta_, lambda);
267  MatrixXd K = cross_covariance * predicted_measurement_uncertainty.partialPivLu().inverse();
268  graft_state_ = predicted_mean + K*(z - predicted_measurement);
269  graft_covariance_ = predicted_covariance - K*predicted_measurement_uncertainty*K.transpose();
270 
272  return dt;
273 }
274 
276  topics_ = topics;
277 }
278 
279 void GraftUKFVelocity::setInitialCovariance(std::vector<double>& P){
280  graft_covariance_.setZero();
281  size_t diagonal_size = std::sqrt(graft_covariance_.size());
282  if(P.size() == graft_covariance_.size()){ // Full matrix
283  for(size_t i = 0; i < P.size(); i++){
284  graft_covariance_(i) = P[i];
285  }
286  } else if(P.size() == diagonal_size){ // Diagonal matrix
287  for(size_t i = 0; i < P.size(); i++){
288  graft_covariance_(i*(diagonal_size+1)) = P[i];
289  }
290  } else { // Not specified correctly
291  ROS_ERROR("initial_covariance is size %zu, expected %zu.\nUsing 0.1*Identity.\nThis probably won't work well.", P.size(), graft_covariance_.size());
292  graft_covariance_.setIdentity();
294  }
295 }
296 
297 void GraftUKFVelocity::setProcessNoise(std::vector<double>& Q){
298  Q_.setZero();
299  size_t diagonal_size = std::sqrt(Q_.size());
300  if(Q.size() == Q_.size()){ // Full process nosie matrix
301  for(size_t i = 0; i < Q.size(); i++){
302  Q_(i) = Q[i];
303  }
304  } else if(Q.size() == diagonal_size){ // Diagonal matrix
305  for(size_t i = 0; i < Q.size(); i++){
306  Q_(i*(diagonal_size+1)) = Q[i];
307  }
308  } else { // Not specified correctly
309  ROS_ERROR("process_noise parameter is size %zu, expected %zu.\nUsing 0.1*Identity.\nThis probably won't work well.", Q.size(), Q_.size());
310  Q_.setIdentity();
311  Q_ = 0.1 * Q_;
312  }
313 }
314 
315 void GraftUKFVelocity::setAlpha(const double alpha){
316  alpha_ = alpha;
317 }
318 
319 void GraftUKFVelocity::setKappa(const double kappa){
320  kappa_ = kappa;
321 }
322 
323 void GraftUKFVelocity::setBeta(const double beta){
324  beta_ = beta;
325 }
GraftUKFVelocity::GraftUKFVelocity
GraftUKFVelocity()
Definition: GraftUKFVelocity.cpp:37
GraftUKFVelocity::setKappa
void setKappa(const double kappa)
Definition: GraftUKFVelocity.cpp:319
GraftUKFVelocity::graft_state_
Matrix< double, SIZE, 1 > graft_state_
Definition: GraftUKFVelocity.h:80
GraftUKFVelocity::last_update_time_
ros::Time last_update_time_
Definition: GraftUKFVelocity.h:86
verticalConcatenate
MatrixXd verticalConcatenate(MatrixXd &m, MatrixXd &n)
Definition: GraftUKFVelocity.cpp:48
addElementToVector
VectorXd addElementToVector(const VectorXd &vec, const double &element)
Definition: GraftUKFVelocity.cpp:154
generateSigmaPoints
std::vector< MatrixXd > generateSigmaPoints(MatrixXd state, MatrixXd covariance, double lambda)
Definition: GraftUKFVelocity.cpp:60
GraftUKFVelocity::setAlpha
void setAlpha(const double alpha)
Definition: GraftUKFVelocity.cpp:315
GraftUKFVelocity::setBeta
void setBeta(const double beta)
Definition: GraftUKFVelocity.cpp:323
boost::shared_ptr
GraftUKFVelocity::~GraftUKFVelocity
~GraftUKFVelocity()
Definition: GraftUKFVelocity.cpp:44
GraftUKFVelocity::alpha_
double alpha_
Definition: GraftUKFVelocity.h:89
GraftUKFVelocity::beta_
double beta_
Definition: GraftUKFVelocity.h:90
GraftUKFVelocity::f
MatrixXd f(MatrixXd x, double dt)
Definition: GraftUKFVelocity.cpp:114
TimeBase< Time, Duration >::toSec
double toSec() const
GraftUKFVelocity.h
GraftUKFVelocity::setInitialCovariance
void setInitialCovariance(std::vector< double > &P)
Definition: GraftUKFVelocity.cpp:279
console.h
GraftUKFVelocity::topics_
std::vector< boost::shared_ptr< GraftSensor > > topics_
Definition: GraftUKFVelocity.h:93
matrixSqrt
MatrixXd matrixSqrt(MatrixXd matrix)
Definition: GraftUKFVelocity.cpp:55
GraftUKFVelocity::kappa_
double kappa_
Definition: GraftUKFVelocity.h:91
GraftUKFVelocity::graft_control_
Matrix< double, SIZE, 1 > graft_control_
Definition: GraftUKFVelocity.h:81
GraftUKFVelocity::setTopics
void setTopics(std::vector< boost::shared_ptr< GraftSensor > > &topics)
Definition: GraftUKFVelocity.cpp:275
ROS_WARN
#define ROS_WARN(...)
stateMsgFromMatrix
graft::GraftState::ConstPtr stateMsgFromMatrix(const MatrixXd &state)
Definition: GraftUKFVelocity.cpp:122
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: GraftUKFVelocity.cpp:172
GraftUKFVelocity::graft_covariance_
Matrix< double, SIZE, SIZE > graft_covariance_
Definition: GraftUKFVelocity.h:82
addElementToColumnMatrix
MatrixXd addElementToColumnMatrix(const MatrixXd &mat, const double &element)
Definition: GraftUKFVelocity.cpp:160
GraftUKFVelocity::predictAndUpdate
double predictAndUpdate()
Definition: GraftUKFVelocity.cpp:236
ros::Time
ROS_ERROR
#define ROS_ERROR(...)
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: GraftUKFVelocity.cpp:102
GraftUKFVelocity::getMessageFromState
graft::GraftStatePtr getMessageFromState()
Definition: GraftUKFVelocity.cpp:138
SIZE
#define SIZE
Definition: GraftUKFAbsolute.h:47
GraftUKFVelocity::Q_
Matrix< double, SIZE, SIZE > Q_
Definition: GraftUKFVelocity.h:84
covarianceFromSigmaPoints
MatrixXd covarianceFromSigmaPoints(std::vector< MatrixXd > &sigma_points, MatrixXd &mean, MatrixXd process_noise, double n, double alpha, double beta, double lambda)
Definition: GraftUKFVelocity.cpp:92
GraftUKFVelocity::predict_sigma_points
std::vector< MatrixXd > predict_sigma_points(std::vector< MatrixXd > &sigma_points, double dt)
Definition: GraftUKFVelocity.cpp:130
clearMessages
void clearMessages(std::vector< boost::shared_ptr< GraftSensor > > &topics)
Definition: GraftUKFVelocity.cpp:230
GraftUKFVelocity::setProcessNoise
void setProcessNoise(std::vector< double > &Q)
Definition: GraftUKFVelocity.cpp:297
ros::Time::now
static Time now()


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