diff --git a/include/mrs_uav_state_estimators/estimators/correction.h b/include/mrs_uav_state_estimators/estimators/correction.h index b3414de..ec59593 100644 --- a/include/mrs_uav_state_estimators/estimators/correction.h +++ b/include/mrs_uav_state_estimators/estimators/correction.h @@ -155,6 +155,8 @@ class Correction { mrs_lib::SubscribeHandler sh_quat_; measurement_t prev_hdg_measurement_; bool got_first_hdg_measurement_ = false; + bool init_hdg_in_zero_ = false; + double first_hdg_measurement_ = 0.0; mrs_lib::SubscribeHandler sh_imu_; std::optional getCorrectionFromImu(const sensor_msgs::ImuConstPtr msg); @@ -376,6 +378,11 @@ Correction::Correction(ros::NodeHandle& nh, const std::string& e sh_orientation_ = mrs_lib::SubscribeHandler(shopts, orientation_topic_); } + if (est_type_ == EstimatorType_t::HEADING) { + ph->param_loader->loadParam("init_hdg_in_zero", init_hdg_in_zero_, false); + } + + // | --------------- initialize publish handlers -------------- | if (ch_->debug_topics.correction) { @@ -876,7 +883,7 @@ std::optional::measurement_t> Correction attitude; if (transform_to_frame_enabled_) { @@ -885,15 +892,17 @@ std::optional::measurement_t> Correctionpose.pose.orientation); // obtain heading from orientation - attitude = std::make_unique(R_odom * R_from_to); + attitude = std::make_unique(R_to_from * R_odom); + } else { attitude = std::make_unique(msg->pose.pose.orientation); } @@ -901,10 +910,17 @@ std::optional::measurement_t> CorrectiongetHeading(); + + // subtract initial heading to start with zero heading + if (init_hdg_in_zero_ && got_first_hdg_measurement_) { + measurement(StateId_t::POSITION) = measurement(StateId_t::POSITION) - first_hdg_measurement_; + } + // unwrap heading wrt previous measurement if (got_first_hdg_measurement_) { - measurement(StateId_t::POSITION) = mrs_lib::geometry::radians::unwrap(measurement(POSITION), prev_hdg_measurement_(POSITION)); + measurement(StateId_t::POSITION) = mrs_lib::geometry::radians::unwrap(measurement(StateId_t::POSITION), prev_hdg_measurement_(StateId_t::POSITION)); } else { + first_hdg_measurement_ = measurement(StateId_t::POSITION); got_first_hdg_measurement_ = true; } prev_hdg_measurement_ = measurement; @@ -1677,11 +1693,11 @@ std::optional::measurement_t> Correction std::optional Correction::getInFrame(const geometry_msgs::Point& pt_in, const std_msgs::Header& source_header, - const std::string target_frame) { + const std::string target_frame) { geometry_msgs::PointStamped pt; pt.header = source_header; - pt.point = pt_in; + pt.point = pt_in; geometry_msgs::PointStamped transformed_pt; auto res = ch_->transformer->transformSingle(pt, target_frame);