Skip to content

Commit e34bd86

Browse files
committed
Fix ros2 component topics
Emit gps/navsat fix messages on timer tick.
1 parent fc78281 commit e34bd86

File tree

1 file changed

+13
-2
lines changed

1 file changed

+13
-2
lines changed

gpsd_client/src/client.cpp

Lines changed: 13 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,8 +5,11 @@
55
#include <sensor_msgs/msg/nav_sat_status.hpp>
66
#include <libgpsmm.h>
77

8+
#include <chrono>
89
#include <cmath>
910

11+
using namespace std::chrono_literals;
12+
1013
namespace gpsd_client
1114
{
1215
class GPSDClientComponent : public rclcpp::Node
@@ -18,7 +21,12 @@ namespace gpsd_client
1821
use_gps_time_(true),
1922
check_fix_by_variance_(true),
2023
frame_id_("gps")
21-
{}
24+
{
25+
timer_ = create_wall_timer(
26+
1s, std::bind(&GPSDClientComponent::step, this));
27+
start();
28+
RCLCPP_INFO(this->get_logger(), "Instantiated.");
29+
}
2230

2331
bool start()
2432
{
@@ -58,7 +66,7 @@ namespace gpsd_client
5866
return false;
5967
}
6068

61-
RCLCPP_INFO(this->get_logger(), "GPSd opened");
69+
RCLCPP_DEBUG(this->get_logger(), "GPSd opened");
6270
return true;
6371
}
6472

@@ -207,6 +215,7 @@ namespace gpsd_client
207215

208216
fix.status = status;
209217

218+
RCLCPP_INFO(this->get_logger(), "Publishing gps fix...");
210219
gps_fix_pub_->publish(fix);
211220
}
212221

@@ -271,6 +280,7 @@ namespace gpsd_client
271280

272281
fix->position_covariance_type = sensor_msgs::msg::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
273282

283+
RCLCPP_DEBUG(this->get_logger(), "Publishing navsatfix...");
274284
navsatfix_pub_->publish(std::move(fix));
275285
}
276286

@@ -282,6 +292,7 @@ namespace gpsd_client
282292
bool use_gps_time_;
283293
bool check_fix_by_variance_;
284294
std::string frame_id_;
295+
rclcpp::TimerBase::SharedPtr timer_;
285296
};
286297
}
287298

0 commit comments

Comments
 (0)