Skip to content

Commit 50bada0

Browse files
author
Ryohei Sasaki
committed
[feature]support geoid2024beta
1 parent f241e83 commit 50bada0

File tree

2 files changed

+6
-3
lines changed

2 files changed

+6
-3
lines changed

eagleye_util/fix2pose/launch/fix2pose.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@
1010
<!-- 0 : No convert 1 : ellipsoid -> altitude 2 : altitude -> ellipsoid -->
1111
<arg name="convert_height_num" default="0"/>
1212

13-
<!-- 0 : EGM2008-1 1 : GSIGE2011 Ver2.1 -->
13+
<!-- 0 : EGM2008-1 1 : GSIGE2011 Ver2.1 2 : GSIGE2011beta-->
1414
<param name="geoid_type" value="0"/>
1515

1616
<!-- Parameters for tf to publish -->

eagleye_util/fix2pose/src/fix2pose.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -57,8 +57,7 @@ static geometry_msgs::PoseWithCovarianceStamped _pose_with_covariance;
5757

5858
static std::string _parent_frame_id, _child_frame_id, _base_link_frame_id, _gnss_frame_id;
5959

60-
std::string geoid_file_path = ros::package::getPath("llh_converter") + "/data/gsigeo2011_ver2_1.asc";
61-
llh_converter::LLHConverter _lc(geoid_file_path);
60+
llh_converter::LLHConverter _lc;
6261
llh_converter::LLHParam _llh_param;
6362

6463
bool _fix_only_publish = false;
@@ -280,6 +279,10 @@ int main(int argc, char** argv)
280279
{
281280
_llh_param.geoid_type = llh_converter::GeoidType::GSIGEO2011;
282281
}
282+
else if(geoid_type == 2)
283+
{
284+
height_converter_.setGeoidType(llh_converter::GeoidType::GSIGEO2024);
285+
}
283286
else
284287
{
285288
ROS_ERROR("GeoidType is not valid");

0 commit comments

Comments
 (0)