Skip to content

Commit

Permalink
nav_sat_fix_origin variable refactor
Browse files Browse the repository at this point in the history
  • Loading branch information
meliketanrikulu committed Jun 10, 2022
1 parent a12da56 commit 67b8795
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
4 changes: 2 additions & 2 deletions sensing/gnss_poser/include/gnss_poser/convert.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,14 +59,14 @@ double EllipsoidHeight2OrthometricHeight(
}
GNSSStat NavSatFix2LocalCartesian(
const sensor_msgs::msg::NavSatFix & nav_sat_fix_msg,
sensor_msgs::msg::NavSatFix nav_sat_fix_origin, const rclcpp::Logger & logger)
sensor_msgs::msg::NavSatFix nav_sat_fix_origin_, const rclcpp::Logger & logger)
{
GNSSStat local_cartesian;
local_cartesian.coordinate_system = CoordinateSystem::LOCAL_CARTESIAN;

try {
GeographicLib::LocalCartesian localCartesian_origin(
nav_sat_fix_origin.latitude, nav_sat_fix_origin.longitude, nav_sat_fix_origin.altitude);
nav_sat_fix_origin_.latitude, nav_sat_fix_origin_.longitude, nav_sat_fix_origin_.altitude);
localCartesian_origin.Forward(
nav_sat_fix_msg.latitude, nav_sat_fix_msg.longitude, nav_sat_fix_msg.altitude,
local_cartesian.x, local_cartesian.y, local_cartesian.z);
Expand Down
8 changes: 4 additions & 4 deletions sensing/gnss_poser/src/gnss_poser_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,9 @@ GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
declare_parameter("coordinate_system", static_cast<int>(CoordinateSystem::MGRS));
coordinate_system_ = static_cast<CoordinateSystem>(coordinate_system);

nav_sat_fix_origin.latitude = declare_parameter("latitude", 0.0);
nav_sat_fix_origin.longitude = declare_parameter("longitude", 0.0);
nav_sat_fix_origin.altitude = declare_parameter("altitude", 0.0);
nav_sat_fix_origin_.latitude = declare_parameter("latitude", 0.0);
nav_sat_fix_origin_.longitude = declare_parameter("longitude", 0.0);
nav_sat_fix_origin_.altitude = declare_parameter("altitude", 0.0);

int buff_epoch = declare_parameter("buff_epoch", 1);
position_buffer_.set_capacity(buff_epoch);
Expand Down Expand Up @@ -171,7 +171,7 @@ GNSSStat GNSSPoser::convert(
} else if (coordinate_system == CoordinateSystem::PLANE) {
gnss_stat = NavSatFix2PLANE(nav_sat_fix_msg, plane_zone_, this->get_logger());
} else if (coordinate_system == CoordinateSystem::LOCAL_CARTESIAN) {
gnss_stat = NavSatFix2LocalCartesian(nav_sat_fix_msg, nav_sat_fix_origin, this->get_logger());
gnss_stat = NavSatFix2LocalCartesian(nav_sat_fix_msg, nav_sat_fix_origin_, this->get_logger());
} else {
RCLCPP_ERROR_STREAM_THROTTLE(
this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(),
Expand Down

0 comments on commit 67b8795

Please sign in to comment.