Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(gnss_poser): rework parameters #5140

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions sensing/gnss_poser/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,5 +34,6 @@ rclcpp_components_register_node(gnss_poser_node
)

ament_auto_package(INSTALL_TO_SHARE
config
launch
)
9 changes: 9 additions & 0 deletions sensing/gnss_poser/config/gnss_poser.param.yaml
Original file line number Diff line number Diff line change
@@ -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
20 changes: 3 additions & 17 deletions sensing/gnss_poser/launch/gnss_poser.launch.xml
Original file line number Diff line number Diff line change
@@ -1,35 +1,21 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="param_file" default="$(find-pkg-share gnss_poser)/config/gnss_poser.param.yaml"/>

<arg name="input_topic_fix" default="/fix"/>
<arg name="input_topic_orientation" default="/autoware_orientation"/>

<arg name="output_topic_gnss_pose" default="gnss_pose"/>
<arg name="output_topic_gnss_pose_cov" default="gnss_pose_cov"/>
<arg name="output_topic_gnss_fixed" default="gnss_fixed"/>

<arg name="base_frame" default="base_link"/>
<arg name="gnss_base_frame" default="gnss_base_link"/>
<arg name="gnss_frame" default="gnss"/>
<arg name="map_frame" default="map"/>

<arg name="buff_epoch" default="1"/>
<arg name="use_gnss_ins_orientation" default="true"/>
<arg name="gnss_pose_pub_method" default="0" description="0: Instant Value 1: Average Value 2: Median Value"/>

<node pkg="gnss_poser" exec="gnss_poser" name="gnss_poser" output="screen">
<remap from="fix" to="$(var input_topic_fix)"/>
<remap from="autoware_orientation" to="$(var input_topic_orientation)"/>
<remap from="gnss_pose" to="$(var output_topic_gnss_pose)"/>
<remap from="gnss_pose_cov" to="$(var output_topic_gnss_pose_cov)"/>
<remap from="gnss_fixed" to="$(var output_topic_gnss_fixed)"/>

<param name="base_frame" value="$(var base_frame)"/>
<param name="gnss_base_frame" value="$(var gnss_base_frame)"/>
<param name="gnss_frame" value="$(var gnss_frame)"/>
<param name="map_frame" value="$(var map_frame)"/>

<param name="buff_epoch" value="$(var buff_epoch)"/>
<param name="use_gnss_ins_orientation" value="$(var use_gnss_ins_orientation)"/>
<param name="gnss_pose_pub_method" value="$(var gnss_pose_pub_method)"/>
<param from="$(var param_file)"/>
</node>
</launch>
14 changes: 7 additions & 7 deletions sensing/gnss_poser/src/gnss_poser_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,22 +30,22 @@ 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<std::string>("base_frame")),
gnss_frame_(declare_parameter<std::string>("gnss_frame")),
gnss_base_frame_(declare_parameter<std::string>("gnss_base_frame")),
map_frame_(declare_parameter<std::string>("map_frame")),
use_gnss_ins_orientation_(declare_parameter<bool>("use_gnss_ins_orientation")),
msg_gnss_ins_orientation_stamped_(
std::make_shared<autoware_sensing_msgs::msg::GnssInsOrientationStamped>()),
gnss_pose_pub_method(declare_parameter<int>("gnss_pose_pub_method", 0))
gnss_pose_pub_method(declare_parameter<int>("gnss_pose_pub_method"))
{
// Subscribe to map_projector_info topic
const auto adaptor = component_interface_utils::NodeAdaptor(this);
adaptor.init_sub(
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<int>("buff_epoch");
position_buffer_.set_capacity(buff_epoch);

nav_sat_fix_sub_ = create_subscription<sensor_msgs::msg::NavSatFix>(
Expand Down