diff --git a/sensing/gnss_poser/CMakeLists.txt b/sensing/gnss_poser/CMakeLists.txt
index 167f2c51337ce..775cde514945f 100644
--- a/sensing/gnss_poser/CMakeLists.txt
+++ b/sensing/gnss_poser/CMakeLists.txt
@@ -34,5 +34,6 @@ rclcpp_components_register_node(gnss_poser_node
)
ament_auto_package(INSTALL_TO_SHARE
+ config
launch
)
diff --git a/sensing/gnss_poser/config/gnss_poser.param.yaml b/sensing/gnss_poser/config/gnss_poser.param.yaml
new file mode 100644
index 0000000000000..30be98bba8cf1
--- /dev/null
+++ b/sensing/gnss_poser/config/gnss_poser.param.yaml
@@ -0,0 +1,9 @@
+/**:
+ ros__parameters:
+ base_frame: base_link
+ gnss_base_frame: gnss_base_link
+ gnss_frame: gnss
+ map_frame: map
+ buff_epoch: 1
+ use_gnss_ins_orientation: true
+ gnss_pose_pub_method: 0
diff --git a/sensing/gnss_poser/launch/gnss_poser.launch.xml b/sensing/gnss_poser/launch/gnss_poser.launch.xml
index 60e952c6845f4..d9b850e6995ae 100755
--- a/sensing/gnss_poser/launch/gnss_poser.launch.xml
+++ b/sensing/gnss_poser/launch/gnss_poser.launch.xml
@@ -1,5 +1,7 @@
+
+
@@ -7,15 +9,6 @@
-
-
-
-
-
-
-
-
-
@@ -23,13 +16,6 @@
-
-
-
-
-
-
-
-
+
diff --git a/sensing/gnss_poser/src/gnss_poser_core.cpp b/sensing/gnss_poser/src/gnss_poser_core.cpp
index 1ae8bce2ed7f2..599a017bffed7 100644
--- a/sensing/gnss_poser/src/gnss_poser_core.cpp
+++ b/sensing/gnss_poser/src/gnss_poser_core.cpp
@@ -30,14 +30,14 @@ GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
: rclcpp::Node("gnss_poser", node_options),
tf2_listener_(tf2_buffer_),
tf2_broadcaster_(*this),
- base_frame_(declare_parameter("base_frame", "base_link")),
- gnss_frame_(declare_parameter("gnss_frame", "gnss")),
- gnss_base_frame_(declare_parameter("gnss_base_frame", "gnss_base_link")),
- map_frame_(declare_parameter("map_frame", "map")),
- use_gnss_ins_orientation_(declare_parameter("use_gnss_ins_orientation", true)),
+ base_frame_(declare_parameter("base_frame")),
+ gnss_frame_(declare_parameter("gnss_frame")),
+ gnss_base_frame_(declare_parameter("gnss_base_frame")),
+ map_frame_(declare_parameter("map_frame")),
+ use_gnss_ins_orientation_(declare_parameter("use_gnss_ins_orientation")),
msg_gnss_ins_orientation_stamped_(
std::make_shared()),
- gnss_pose_pub_method(declare_parameter("gnss_pose_pub_method", 0))
+ gnss_pose_pub_method(declare_parameter("gnss_pose_pub_method"))
{
// Subscribe to map_projector_info topic
const auto adaptor = component_interface_utils::NodeAdaptor(this);
@@ -45,7 +45,7 @@ GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
sub_map_projector_info_,
[this](const MapProjectorInfo::Message::ConstSharedPtr msg) { callbackMapProjectorInfo(msg); });
- int buff_epoch = declare_parameter("buff_epoch", 1);
+ int buff_epoch = declare_parameter("buff_epoch");
position_buffer_.set_capacity(buff_epoch);
nav_sat_fix_sub_ = create_subscription(