Skip to content

Commit

Permalink
fix: ref position relative to the vessel's center
Browse files Browse the repository at this point in the history
and avoid using null values in converter
  • Loading branch information
eduardacoppo committed Jan 28, 2025
1 parent 4c8e3b4 commit 9d1e750
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 5 deletions.
12 changes: 9 additions & 3 deletions src/AIS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,13 +110,19 @@ ais_base::VesselInformation AIS::getVesselInformation(ais::message_05 const& mes
string call_sign = message.get_callsign();
first_not_space = call_sign.find_last_not_of(" ");
info.call_sign = call_sign.substr(0, first_not_space + 1);
info.length = message.get_to_bow() + message.get_to_stern();
info.width = message.get_to_port() + message.get_to_starboard();
auto get_to_stern = message.get_to_stern();
auto get_to_starboard = message.get_to_starboard();
float length = message.get_to_bow() + get_to_stern;
float width = message.get_to_port() + get_to_starboard;
info.length = length;
info.width = width;
info.draft = static_cast<float>(message.get_draught()) / 10;
info.ship_type = static_cast<ais_base::ShipType>(message.get_shiptype());
info.epfd_fix = static_cast<ais_base::EPFDFixType>(message.get_epfd_fix());
info.reference_position =
Eigen::Vector3d(message.get_to_stern(), message.get_to_starboard(), 0);
Eigen::Vector3d(static_cast<double>(get_to_stern - length / 2.0),
static_cast<double>(get_to_starboard - width / 2.0),
0);

info.ensureEnumsValid();
return info;
Expand Down
4 changes: 2 additions & 2 deletions test/test_AIS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ struct AISTest : public ::testing::Test, public iodrivers_base::Fixture<Driver>

gps_base::UTMConverter createUTMConverter()
{
gps_base::UTMConversionParameters parameters = {Eigen::Vector3d(0, 0, 0),
gps_base::UTMConversionParameters parameters = {Eigen::Vector3d(1, 1, 0),
11,
true};
gps_base::UTMConverter converter(parameters);
Expand Down Expand Up @@ -190,7 +190,7 @@ TEST_F(AISTest, it_converts_marnav_message05_into_a_VesselInformation)
ASSERT_EQ(ais_base::SHIP_TYPE_CARGO, info.ship_type);
ASSERT_EQ(15, info.length);
ASSERT_EQ(6, info.width);
ASSERT_EQ(base::Vector3d(10, 4, 0), info.reference_position);
ASSERT_EQ(base::Vector3d(2.5, 1, 0), info.reference_position);
ASSERT_EQ(ais_base::EPFD_COMBINED_GPS_GLONASS, info.epfd_fix);
ASSERT_NEAR(0.7, info.draft, 1e-2);
}
Expand Down

0 comments on commit 9d1e750

Please sign in to comment.