Skip to content

Commit

Permalink
Add GeoPoint Validation (#56)
Browse files Browse the repository at this point in the history
* Add GeoPoint Validation

* Add ament_lint_common
* Fix linter violations

Signed-off-by: Ryan Friedman <[email protected]>

* Downgrade CMake to 3.13, remove GNUInstallDirs, Add licenses

Signed-off-by: Ryan Friedman <[email protected]>

* Match upstream common_interfaces implementation

Signed-off-by: Ryan Friedman <[email protected]>

* Change case to match ROS convention

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Ryan Friedman <[email protected]>

* Fix licensing problems

* Only run the linters we need
* Disable ament_copyright by not using ament_lint_common

Signed-off-by: Ryan Friedman <[email protected]>

---------

Signed-off-by: Ryan Friedman <[email protected]>
Co-authored-by: Ryan Friedman <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
3 people authored Feb 28, 2024
1 parent 1137998 commit 2a0ae99
Show file tree
Hide file tree
Showing 8 changed files with 161 additions and 8 deletions.
35 changes: 33 additions & 2 deletions geographic_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,9 +1,8 @@
cmake_minimum_required(VERSION 3.5)
project(geographic_msgs)

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
Expand Down Expand Up @@ -40,6 +39,38 @@ rosidl_generate_interfaces(${PROJECT_NAME}
DEPENDENCIES unique_identifier_msgs geometry_msgs std_msgs builtin_interfaces
)

rosidl_get_typesupport_target(cpp_typesupport_target "${PROJECT_NAME}" rosidl_typesupport_cpp)

if(TARGET "${cpp_typesupport_target}")
add_library(${PROJECT_NAME}::cpp_typesupport_target ALIAS ${cpp_typesupport_target})
add_library(validation INTERFACE)
add_library(${PROJECT_NAME}::validation ALIAS validation)
add_subdirectory(include)
target_link_libraries(validation INTERFACE ${PROJECT_NAME}::cpp_typesupport_target)

install(
TARGETS validation
EXPORT export_${PROJECT_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
RUNTIME DESTINATION bin
)

install(
DIRECTORY include/
DESTINATION include/${PROJECT_NAME}
FILES_MATCHING PATTERN "*.hpp"
)

ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
endif()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
add_subdirectory(test)
endif()

install(
FILES geographic_msgs_mapping_rule.yaml
DESTINATION share/${PROJECT_NAME}
Expand Down
5 changes: 5 additions & 0 deletions geographic_msgs/include/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
target_include_directories(validation
INTERFACE
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}>
$<INSTALL_INTERFACE:include>
)
18 changes: 18 additions & 0 deletions geographic_msgs/include/geographic_msgs/validation.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
// Copyright 2024 Ryan Friedman
#pragma once
#include <geographic_msgs/msg/geo_point.hpp>

namespace geographic_msgs
{

//! @brief Return whether a GeoPoint has latitude and longitude within expected bounds.
[[nodiscard]] inline static bool horizontalPositionValid(const geographic_msgs::msg::GeoPoint point)
{
auto const lat_valid = point.latitude <= 90.0 && point.latitude >= -90.0;
auto const lng_valid = point.longitude <= 180.0 && point.longitude >= -180.0;

return lat_valid && lng_valid;
}


} // namespace geographic_msgs
7 changes: 5 additions & 2 deletions geographic_msgs/mainpage.dox
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,11 @@
\mainpage
\htmlinclude manifest.html

This package provides ROS messages for Geographic Information.
This package provides ROS messages for Geographic Information.

It has no nodes, utilities, scripts or C++ API.
It includes a simple validation library to validate messages have values within
the documented bounds.

It has no nodes or scripts.

*/
6 changes: 3 additions & 3 deletions geographic_msgs/msg/GeoPoint.msg
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
# Geographic point, using the WGS 84 reference ellipsoid.

# Latitude [degrees]. Positive is north of equator; negative is south
# (-90 <= latitude <= +90).
# (-90.0 <= latitude <= +90.0).
float64 latitude

# Longitude [degrees]. Positive is east of prime meridian; negative is
# west (-180 <= longitude <= +180). At the poles, latitude is -90 or
# +90, and longitude is irrelevant, but must be in range.
# west (-180.0 <= longitude <= +180.0). At the poles, latitude is -90.0 or
# +90.0, and longitude is irrelevant, but must be in range.
float64 longitude

# Altitude [m]. Positive is above the WGS 84 ellipsoid (NaN if unspecified).
Expand Down
15 changes: 14 additions & 1 deletion geographic_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
</description>
<maintainer email="[email protected]">Jack O'Quin</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<author>Jack O'Quin</author>
<license>BSD</license>

<url>http://wiki.ros.org/geographic_msgs</url>
Expand All @@ -25,6 +24,20 @@
<depend>std_msgs</depend>
<depend>unique_identifier_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<!--
Skip using ament_lint_auto because ament_lint_copyright does not support "BSD" license.
https://robotics.stackexchange.com/questions/109592/how-to-use-ament-lint-commons-ament-copyright-on-a-bsd-licensed-package-such
For now, the C++, CMake, and XML linters are enabled.
-->
<test_depend>ament_cmake_cppcheck</test_depend>
<test_depend>ament_cmake_cpplint</test_depend>
<test_depend>ament_cmake_lint_cmake</test_depend>
<test_depend>ament_cmake_uncrustify</test_depend>
<test_depend>ament_cmake_xmllint</test_depend>


<member_of_group>rosidl_interface_packages</member_of_group>
<export>
<build_type>ament_cmake</build_type>
Expand Down
5 changes: 5 additions & 0 deletions geographic_msgs/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
if(TARGET "${cpp_typesupport_target}")
find_package(ament_cmake_gtest CONFIG REQUIRED)
ament_add_gtest(validation_test test_validation.cpp)
target_link_libraries(validation_test ${PROJECT_NAME}::validation)
endif()
78 changes: 78 additions & 0 deletions geographic_msgs/test/test_validation.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
// Copyright 2024 Ryan Friedman

#include <gtest/gtest.h>
#include <geographic_msgs/msg/geo_point.hpp>
#include <geographic_msgs/validation.hpp>


TEST(ElevationServerCore, ValidPoints)
{
geographic_msgs::msg::GeoPoint point;
point.latitude = 1.0;
point.longitude = 10.0;
EXPECT_TRUE(geographic_msgs::horizontalPositionValid(point));
}

TEST(ElevationServerCore, TooFarNorth)
{
geographic_msgs::msg::GeoPoint point;
point.latitude = 90.01;
point.longitude = 0.0;
EXPECT_FALSE(geographic_msgs::horizontalPositionValid(point));
}

TEST(ElevationServerCore, TooFarSouth)
{
geographic_msgs::msg::GeoPoint point;
point.latitude = -90.01;
point.longitude = 0.0;
EXPECT_FALSE(geographic_msgs::horizontalPositionValid(point));
}

TEST(ElevationServerCore, TooFarWest)
{
geographic_msgs::msg::GeoPoint point;
point.latitude = 0.0;
point.longitude = -180.1;
EXPECT_FALSE(geographic_msgs::horizontalPositionValid(point));
}

TEST(ElevationServerCore, TooFarEast)
{
geographic_msgs::msg::GeoPoint point;
point.latitude = 0.0;
point.longitude = 180.1;
EXPECT_FALSE(geographic_msgs::horizontalPositionValid(point));
}

TEST(ElevationServerCore, NorthPole)
{
geographic_msgs::msg::GeoPoint point;
point.latitude = 90.0;
point.longitude = 42.0;
EXPECT_TRUE(geographic_msgs::horizontalPositionValid(point));
}

TEST(ElevationServerCore, SouthPole)
{
geographic_msgs::msg::GeoPoint point;
point.latitude = -90.0;
point.longitude = 42.0;
EXPECT_TRUE(geographic_msgs::horizontalPositionValid(point));
}

TEST(ElevationServerCore, NorthPoleInvalidLng)
{
geographic_msgs::msg::GeoPoint point;
point.latitude = 90.0;
point.longitude = 999.0;
EXPECT_FALSE(geographic_msgs::horizontalPositionValid(point));
}

TEST(ElevationServerCore, SouthPoleInvalidLng)
{
geographic_msgs::msg::GeoPoint point;
point.latitude = -90.0;
point.longitude = -999.0;
EXPECT_FALSE(geographic_msgs::horizontalPositionValid(point));
}

0 comments on commit 2a0ae99

Please sign in to comment.