From ec2b0861e4ada5f09ffb3acd01a5688a6f8763c8 Mon Sep 17 00:00:00 2001 From: Tom Wallis Date: Wed, 1 Jan 2025 13:39:58 -0800 Subject: [PATCH] Set use_stamped to default to true --- src/twist_marker.cpp | 4 ++-- src/twist_mux.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/twist_marker.cpp b/src/twist_marker.cpp index e693f8e..2ee45d1 100644 --- a/src/twist_marker.cpp +++ b/src/twist_marker.cpp @@ -108,12 +108,12 @@ class TwistMarkerPublisher : public rclcpp::Node { std::string frame_id; double scale; - bool use_stamped; + bool use_stamped = true; double z; this->declare_parameter("frame_id", "base_footprint"); this->declare_parameter("scale", 1.0); - this->declare_parameter("use_stamped", false); + this->declare_parameter("use_stamped", true); this->declare_parameter("vertical_position", 2.0); this->get_parameter("frame_id", frame_id); diff --git a/src/twist_mux.cpp b/src/twist_mux.cpp index c9c343e..ed61ca1 100644 --- a/src/twist_mux.cpp +++ b/src/twist_mux.cpp @@ -78,7 +78,7 @@ TwistMux::TwistMux() void TwistMux::init() { // Get use stamped parameter - bool use_stamped = false; + bool use_stamped = true; this->declare_parameter("use_stamped", use_stamped); auto nh = std::shared_ptr(this, [](rclcpp::Node *) {});