diff --git a/include/mrs_uav_state_estimators/estimators/correction.h b/include/mrs_uav_state_estimators/estimators/correction.h index 00a2695..3954c09 100644 --- a/include/mrs_uav_state_estimators/estimators/correction.h +++ b/include/mrs_uav_state_estimators/estimators/correction.h @@ -49,9 +49,10 @@ typedef enum { LATERAL, ALTITUDE, - HEADING + HEADING, + LATALT, } EstimatorType_t; -const int n_EstimatorType_t = 3; +const int n_EstimatorType_t = 4; typedef enum { @@ -1062,6 +1063,68 @@ std::optional::measurement_t> Correctionheader; + header.frame_id = transform_from_frame_; + auto res = getInFrame(msg->pose.pose.position, header, transform_to_frame_); + if (res) { + measurement_t measurement; + measurement(0) = res.value().x; + measurement(1) = res.value().y; + measurement(2) = res.value().z; + return measurement; + } else { + ROS_WARN_THROTTLE(1.0, "[%s]: could not transform vel from odom", ros::this_node::getName().c_str()); + return {}; + } + + } else { + measurement(0) = msg->pose.pose.position.x; + measurement(1) = msg->pose.pose.position.y; + measurement(2) = msg->pose.pose.position.z; + } + return measurement; + break; + } + + case StateId_t::VELOCITY: { + if (is_in_body_frame_) { + std_msgs::Header header = msg->header; + header.frame_id = ch_->frames.ns_fcu; // message in odometry is published in body frame + auto res = getVecInFrame(msg->twist.twist.linear, header, ns_frame_id_ + "_att_only"); + if (res) { + measurement_t measurement; + measurement = res.value(); + return measurement; + } else { + ROS_WARN_THROTTLE(1.0, "[%s]: could not transform vel from odom", ros::this_node::getName().c_str()); + return {}; + } + } else { + measurement_t measurement; + measurement(0) = msg->twist.twist.linear.x; + measurement(1) = msg->twist.twist.linear.y; + measurement(2) = msg->twist.twist.linear.z; + return measurement; + } + break; + } + + default: { + ROS_ERROR_THROTTLE(1.0, "[%s]: unhandled case in getCorrectionFromOdometry() switch", getPrintName().c_str()); + return {}; + } + } + break; + } } ROS_ERROR("[%s]: FIXME: should not be possible to get into this part of code", getPrintName().c_str()); @@ -1165,6 +1228,29 @@ std::optional::measurement_t> Correctionpose.position.x; + measurement(1) = msg->pose.position.y; + measurement(2) = msg->pose.position.z; + return measurement; + break; + } + + default: { + ROS_ERROR_THROTTLE(1.0, "[%s]: unhandled case in getCorrectionFromPoseStamped() switch", getPrintName().c_str()); + return {}; + } + } + break; + } + } ROS_ERROR("[%s]: FIXME: should not be possible to get into this part of code", getPrintName().c_str()); @@ -1297,7 +1383,7 @@ std::optional::measurement_t> Correctionlinear_acceleration, msg->header); if (res) { measurement_t measurement; - measurement = res.value(); + measurement = res.value(); measurement(0) -= gravity_norm_; return measurement; } else { @@ -1349,6 +1435,41 @@ std::optional::measurement_t> Correctionlinear_acceleration, msg->header, ns_frame_id_ + "_att_only"); + if (res) { + measurement_t measurement; + measurement = res.value(); + return measurement; + } else { + ROS_WARN_THROTTLE(1.0, "[%s]: Could not obtain IMU acceleration in frame: %s", getPrintName().c_str(), (ns_frame_id_ + "_att_only").c_str()); + return {}; + } + } else { + measurement_t measurement; + measurement(0) = msg->linear_acceleration.x; + measurement(1) = msg->linear_acceleration.y; + measurement(2) = msg->linear_acceleration.z; + return measurement; + } + break; + } + + default: { + ROS_ERROR_THROTTLE(1.0, "[%s]: unhandled case in getCorrectionFromImu() switch", getPrintName().c_str()); + return {}; + } + } + break; + } + } ROS_ERROR("[%s]: FIXME: should not be possible to get into this part of code", getPrintName().c_str()); return {}; @@ -1466,6 +1587,27 @@ std::optional::measurement_t> Correction::measurement_t> Correction::measurement_t> Correction::measurement_t> Correction::measurement_t> Correction::measurement_t> Correctionpoint.x; + measurement(1) = msg->point.y; + measurement(2) = msg->point.z; + return measurement; + break; + } + + default: { + ROS_ERROR_THROTTLE(1.0, "[%s]: unhandled case in getCorrectionFromPoint() switch", getPrintName().c_str()); return {}; } } @@ -1792,7 +2001,7 @@ std::optional::measurement_t> Correction::measurement_t> Correctionvector, msg->header, ns_frame_id_ + "_att_only"); + if (res) { + measurement_t measurement; + measurement = res.value(); + return measurement; + } else { + return {}; + } + break; + } + + default: { + ROS_ERROR_THROTTLE(1.0, "[%s]: unhandled case in getCorrectionFromVector() switch", getPrintName().c_str()); + return {}; + } + } + break; + } + } ROS_ERROR("[%s]: FIXME: should not be possible to get into this part of code", getPrintName().c_str()); @@ -2049,7 +2284,7 @@ std::optional::measurement_t> Correction std::optional Correction::transformVecToFrame(const geometry_msgs::Vector3& vec_in, const std_msgs::Header& source_header, const std::string target_frame) { @@ -2078,6 +2313,9 @@ std::optional::measurement_t> Correction