Skip to content

Commit

Permalink
feat(global nav): add reset method
Browse files Browse the repository at this point in the history
  • Loading branch information
GuillaumeLaine committed Oct 1, 2024
1 parent c75a5f5 commit c62f586
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,16 @@ class GlobalPositionMeasurementInterface : public PositionMeasurementInterfaceBa
*/
void update(const GlobalPositionMeasurement & global_position_measurement) const;

/**
* @brief Notify the FMU that the global position estimate has been reset.
*
* Increments the reset counter for horizontal position (latitude and longitude) to signal the EKF
* of a discontinuity in external position data (e.g., loss of tracking or reinitialization). Future measurement
* updates will contain the incremented counter. This helps the EKF adjust and maintain consistent state estimation,
* and accept new measurements after a gap or inconsistency in updates.
*/
inline void reset() {++_lat_lon_reset_counter;}

private:
/**
* @brief Check that at least one measurement value is defined.
Expand All @@ -85,6 +95,7 @@ class GlobalPositionMeasurementInterface : public PositionMeasurementInterfaceBa

rclcpp::Publisher<px4_msgs::msg::VehicleGlobalPosition>::SharedPtr _aux_global_position_pub;

uint8_t _lat_lon_reset_counter{0}; /** Counter for reset events on horizontal position coordinates */
// uint8_t _altitude_frame;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ void GlobalPositionMeasurementInterface::update(

// Populate aux global position
VehicleGlobalPosition aux_global_position;
aux_global_position.lat_lon_reset_counter = _lat_lon_reset_counter;

aux_global_position.timestamp_sample =
global_position_measurement.timestamp_sample.nanoseconds() *
Expand Down

0 comments on commit c62f586

Please sign in to comment.