File tree Expand file tree Collapse file tree 1 file changed +11
-1
lines changed Expand file tree Collapse file tree 1 file changed +11
-1
lines changed Original file line number Diff line number Diff line change 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+
1013namespace gpsd_client
1114{
1215 class GPSDClientComponent : public rclcpp ::Node
@@ -18,7 +21,11 @@ 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 (1s, std::bind (&GPSDClientComponent::step, this ));
26+ start ();
27+ RCLCPP_INFO (this ->get_logger (), " Instantiated." );
28+ }
2229
2330 bool start ()
2431 {
@@ -207,6 +214,7 @@ namespace gpsd_client
207214
208215 fix.status = status;
209216
217+ RCLCPP_DEBUG (this ->get_logger (), " Publishing gps fix..." );
210218 gps_fix_pub_->publish (fix);
211219 }
212220
@@ -271,6 +279,7 @@ namespace gpsd_client
271279
272280 fix->position_covariance_type = sensor_msgs::msg::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
273281
282+ RCLCPP_DEBUG (this ->get_logger (), " Publishing navsatfix..." );
274283 navsatfix_pub_->publish (std::move (fix));
275284 }
276285
@@ -282,6 +291,7 @@ namespace gpsd_client
282291 bool use_gps_time_;
283292 bool check_fix_by_variance_;
284293 std::string frame_id_;
294+ rclcpp::TimerBase::SharedPtr timer_;
285295 };
286296}
287297
You can’t perform that action at this time.
0 commit comments