Skip to content

Commit dc67f82

Browse files
authored
fix: misc-throw-by-value-catch-by-reference (#338)
Signed-off-by: kobayu858 <[email protected]>
1 parent f8f275b commit dc67f82

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

eagleye_core/coordinate/src/convertheight.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ double ConvertHeight::convert2altitude()
4848
GeographicLib::Geoid egm2008("egm2008-1");
4949
converted_height = egm2008.ConvertHeight(_latitude, _longitude, _height, GeographicLib::Geoid::ELLIPSOIDTOGEOID);
5050
}
51-
catch (const GeographicLib::GeographicErr err)
51+
catch (const GeographicLib::GeographicErr& err)
5252
{
5353
std::cerr << "\033[31;1mError: Failed to convert height from Ellipsoid to Altitude. " << err.what() << std::endl;
5454
exit(4);
@@ -64,7 +64,7 @@ double ConvertHeight::convert2ellipsoid()
6464
GeographicLib::Geoid egm2008("egm2008-1");
6565
converted_height = egm2008.ConvertHeight(_latitude, _longitude, _height, GeographicLib::Geoid::GEOIDTOELLIPSOID);
6666
}
67-
catch (const GeographicLib::GeographicErr err)
67+
catch (const GeographicLib::GeographicErr& err)
6868
{
6969
std::cerr << "\033[31;1mError: Failed to convert height from Ellipsoid to Altitude. " << err.what() << std::endl;
7070
exit(4);

0 commit comments

Comments
 (0)