Skip to content

Commit

Permalink
changed wall time to ros time for calculating of passthrough odom rate
Browse files Browse the repository at this point in the history
  • Loading branch information
Matej Petrlik committed Jan 2, 2025
1 parent 2eca095 commit 79fd7f1
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class Passthrough : public mrs_uav_managers::StateEstimator {
ros::Timer timer_check_passthrough_odom_hz_;
void timerCheckPassthroughOdomHz(const ros::TimerEvent &event);
std::atomic<int> counter_odom_msgs_ = 0;
ros::WallTime t_check_hz_last_;
ros::Time t_check_hz_last_;
double prev_avg_hz_ = 0;
bool kickoff_ = false;

Expand Down
4 changes: 2 additions & 2 deletions src/estimators/state/passthrough.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ void Passthrough::initialize(ros::NodeHandle &parent_nh, const std::shared_ptr<C
sh_passthrough_odom_ = mrs_lib::SubscribeHandler<nav_msgs::Odometry>(shopts, msg_topic_, &Passthrough::callbackPassthroughOdom, this);

// | ------------------ timers initialization ----------------- |
t_check_hz_last_ = ros::WallTime::now();
t_check_hz_last_ = ros::Time::now();
prev_avg_hz_ = 0;
timer_check_passthrough_odom_hz_ = nh.createTimer(ros::Rate(1.0), &Passthrough::timerCheckPassthroughOdomHz, this);

Expand Down Expand Up @@ -156,7 +156,7 @@ void Passthrough::timerCheckPassthroughOdomHz([[maybe_unused]] const ros::TimerE

// calculate average rate of messages
if (counter_odom_msgs_ > 0) {
ros::WallTime t_now = ros::WallTime::now();
ros::Time t_now = ros::Time::now();
double dt = (t_now - t_check_hz_last_).toSec();
double avg_hz = counter_odom_msgs_ / dt;
t_check_hz_last_ = t_now;
Expand Down

0 comments on commit 79fd7f1

Please sign in to comment.