51 out.resize(m.rows()+n.rows(), m.cols());
58 return Eigen::LLT<Eigen::MatrixXd>(matrix).matrixL();
62 std::vector<MatrixXd > out;
64 double gamma = std::sqrt((state.rows()+lambda));
65 MatrixXd sig_sqrt = gamma*
matrixSqrt(covariance);
71 for(
size_t i = 1; i <= state.rows(); i++){
72 out.push_back(state + sig_sqrt.col(i-1));
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)));
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];
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();
100 return out+process_noise;
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();
115 Matrix<double, 4, 4> out;
116 out << 0, wx, wy, wz,
124 double q_mag = std::sqrt(q(0)*q(0) + q(1)*q(1) + q(2)*q(2) + q(3)*q(3));
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);
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;
136 double correction_factor = 1 - 1.0/2.0*
s*
s + 1.0/24.0*
s*
s*
s*
s + k * dt * err;
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);
140 MatrixXd
update = update_factor*quaterion_update_matrix;
141 out = (correction-
update)*q;
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;
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);
160 tf::Vector3 vel_vector(vel(0), vel(1), vel(2));
161 tf::Vector3 transformed = tft*vel_vector;
163 out(0) = transformed.getX();
164 out(1) = transformed.getY();
165 out(2) = transformed.getZ();
171 Matrix<double, SIZE, 1> out;
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;
175 out(1) = x(1)+rotated_linear_velocity(1)*dt;
176 out(2) = x(2)+rotated_linear_velocity(2)*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;
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);
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));
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);
234 for(
size_t i = 0; i <
SIZE*
SIZE; i++){
235 msg->covariance[i] = covariance(i);
241 VectorXd out(vec.size() + 1);
247 MatrixXd out(mat.rows() + 1, 1);
248 MatrixXd small(1, 1);
249 small(0,0) = element;
259 VectorXd actual_measurement;
260 output_measurement_sigmas.clear();
261 VectorXd innovation_covariance_diagonal;
262 innovation_covariance_diagonal.resize(0);
264 std::vector<graft::GraftState::ConstPtr> predicted_sigma_msgs;
265 for(
size_t i = 0; i < predicted_sigma_points.size(); i++){
267 output_measurement_sigmas.push_back(MatrixXd());
272 for(
size_t i = 0; i < topics.size(); i++){
274 graft::GraftSensorResidual::ConstPtr meas = topics[i]->z();
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]));
285 if(meas->pose_covariance[0] > 1e-20){
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);
293 if(meas->pose_covariance[7] > 1e-20){
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);
301 if(meas->pose_covariance[14] > 1e-20){
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);
309 if(meas->twist_covariance[0] > 1e-20){
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);
317 if(meas->twist_covariance[7] > 1e-20){
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);
325 if(meas->twist_covariance[14] > 1e-20){
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);
333 if(meas->twist_covariance[21] > 1e-20){
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);
341 if(meas->twist_covariance[28] > 1e-20){
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);
349 if(meas->twist_covariance[35] > 1e-20){
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);
359 output_innovation_covariance = innovation_covariance_diagonal.asDiagonal();
361 return actual_measurement;
365 for(
size_t i = 0; i < topics.size(); i++){
366 topics[i]->clearMessage();
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);
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);
398 MatrixXd predicted_measurement = meanFromSigmaPoints(predicted_observation_sigma_points,
graft_state_.rows(), 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);
405 graft_covariance_ = predicted_covariance - K*predicted_measurement_uncertainty*K.transpose();
419 for(
size_t i = 0; i < P.size(); i++){
422 }
else if(P.size() == diagonal_size){
423 for(
size_t i = 0; i < P.size(); i++){
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());
435 size_t diagonal_size = std::sqrt(
Q_.size());
436 if(Q.size() ==
Q_.size()){
437 for(
size_t i = 0; i < Q.size(); i++){
440 }
else if(Q.size() == diagonal_size){
441 for(
size_t i = 0; i < Q.size(); i++){
442 Q_(i*(diagonal_size+1)) = Q[i];
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());