Skip to content

Commit

Permalink
ci(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] authored and meliketanrikulu committed Jul 7, 2022
1 parent 20e84fc commit 67c04b0
Showing 1 changed file with 6 additions and 3 deletions.
9 changes: 6 additions & 3 deletions sensing/gnss_poser/src/gnss_poser_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,9 +139,12 @@ void GNSSPoser::callbackNavSatFix(
canGetCovariance(*nav_sat_fix_msg_ptr) ? nav_sat_fix_msg_ptr->position_covariance[4] : 10.0;
gnss_base_pose_cov_msg.pose.covariance[6 * 2 + 2] =
canGetCovariance(*nav_sat_fix_msg_ptr) ? nav_sat_fix_msg_ptr->position_covariance[8] : 10.0;
gnss_base_pose_cov_msg.pose.covariance[6 * 3 + 3] = orientation_msg_ != nullptr ? std::pow(orientation_msg_->orientation.rmse_rotation_x, 2) : 0.1;
gnss_base_pose_cov_msg.pose.covariance[6 * 4 + 4] = orientation_msg_ != nullptr ? std::pow(orientation_msg_->orientation.rmse_rotation_y, 2) : 0.1;
gnss_base_pose_cov_msg.pose.covariance[6 * 5 + 5] = orientation_msg_ != nullptr ? std::pow(orientation_msg_->orientation.rmse_rotation_z, 2) : 1.0;
gnss_base_pose_cov_msg.pose.covariance[6 * 3 + 3] =
orientation_msg_ != nullptr ? std::pow(orientation_msg_->orientation.rmse_rotation_x, 2) : 0.1;
gnss_base_pose_cov_msg.pose.covariance[6 * 4 + 4] =
orientation_msg_ != nullptr ? std::pow(orientation_msg_->orientation.rmse_rotation_y, 2) : 0.1;
gnss_base_pose_cov_msg.pose.covariance[6 * 5 + 5] =
orientation_msg_ != nullptr ? std::pow(orientation_msg_->orientation.rmse_rotation_z, 2) : 1.0;
pose_cov_pub_->publish(gnss_base_pose_cov_msg);

// broadcast map to gnss_base_link
Expand Down

0 comments on commit 67c04b0

Please sign in to comment.