diff --git a/geodesy/CHANGELOG.rst b/geodesy/CHANGELOG.rst index ac50631..d5ee034 100644 --- a/geodesy/CHANGELOG.rst +++ b/geodesy/CHANGELOG.rst @@ -1,6 +1,9 @@ Change history ============== +0.5.3 (2018-03-27) +------------------ + 0.5.2 (2017-04-15) ------------------ diff --git a/geodesy/CMakeLists.txt b/geodesy/CMakeLists.txt index f110d51..5a8d4d3 100644 --- a/geodesy/CMakeLists.txt +++ b/geodesy/CMakeLists.txt @@ -1,56 +1,41 @@ -# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(geodesy) -find_package(catkin REQUIRED - COMPONENTS - angles - geographic_msgs - geometry_msgs - sensor_msgs - tf - unique_id - uuid_msgs) +find_package(ament_cmake REQUIRED) +find_package(angles REQUIRED) +find_package(geographic_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(unique_identifier_msgs REQUIRED) -include_directories(include ${catkin_INCLUDE_DIRS}) -catkin_python_setup() +include_directories( + include +) -# what other packages will need to use this one -catkin_package(CATKIN_DEPENDS - geographic_msgs - geometry_msgs - sensor_msgs - tf - unique_id - uuid_msgs - INCLUDE_DIRS include - LIBRARIES geoconv) +set(dependencies + angles + geographic_msgs + geometry_msgs + sensor_msgs + unique_identifier_msgs +) + +ament_python_install_package(${PROJECT_NAME} PACKAGE_DIR src/${PROJECT_NAME}) # build C++ coordinate conversion library -add_library(geoconv src/conv/utm_conversions.cpp) -target_link_libraries(geoconv ${catkin_LIBRARIES}) -add_dependencies(geoconv ${catkin_EXPORTED_TARGETS}) +add_library(geoconv STATIC src/conv/utm_conversions.cpp) +ament_target_dependencies(geoconv + ${dependencies} +) install(DIRECTORY include/${PROJECT_NAME}/ - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) + DESTINATION include/${PROJECT_NAME}/) install(TARGETS geoconv - RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) - -# unit tests -if (CATKIN_ENABLE_TESTING) - - catkin_add_gtest(test_wgs84 tests/test_wgs84.cpp) - target_link_libraries(test_wgs84 ${catkin_LIBRARIES}) - add_dependencies(test_wgs84 ${catkin_EXPORTED_TARGETS}) - - catkin_add_gtest(test_utm tests/test_utm.cpp) - target_link_libraries(test_utm geoconv ${catkin_LIBRARIES}) - add_dependencies(test_utm ${catkin_EXPORTED_TARGETS}) - - catkin_add_nosetests(tests/test_bounding_box.py) - catkin_add_nosetests(tests/test_props.py) - catkin_add_nosetests(tests/test_utm.py) - catkin_add_nosetests(tests/test_wu_point.py) + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION lib/${PROJECT_NAME} +) -endif (CATKIN_ENABLE_TESTING) +ament_export_dependencies(${dependencies}) +ament_export_include_directories(include) +ament_export_libraries(geoconv) +ament_package() diff --git a/geodesy/include/geodesy/utm.h b/geodesy/include/geodesy/utm.h index 1f3d197..8396069 100644 --- a/geodesy/include/geodesy/utm.h +++ b/geodesy/include/geodesy/utm.h @@ -43,11 +43,11 @@ #include #include -#include - #include -#include -#include +#include "geographic_msgs/msg/geo_point.hpp" +#include "geometry_msgs/msg/point.hpp" +#include "geographic_msgs/msg/geo_pose.hpp" +#include "geometry_msgs/msg/pose.hpp" /** @file @@ -101,7 +101,7 @@ class UTMPoint band(that.band) {} - UTMPoint(const geographic_msgs::GeoPoint &pt); + UTMPoint(const geographic_msgs::msg::GeoPoint &pt); /** Create a flattened 2-D grid point. */ UTMPoint(double _easting, double _northing, uint8_t _zone, char _band): @@ -149,36 +149,36 @@ class UTMPose {} /** Create from a WGS 84 geodetic pose. */ - UTMPose(const geographic_msgs::GeoPose &pose): + UTMPose(const geographic_msgs::msg::GeoPose &pose): position(pose.position), orientation(pose.orientation) {} /** Create from a UTMPoint and a quaternion. */ UTMPose(UTMPoint pt, - const geometry_msgs::Quaternion &q): + const geometry_msgs::msg::Quaternion &q): position(pt), orientation(q) {} /** Create from a WGS 84 geodetic point and a quaternion. */ - UTMPose(const geographic_msgs::GeoPoint &pt, - const geometry_msgs::Quaternion &q): + UTMPose(const geographic_msgs::msg::GeoPoint &pt, + const geometry_msgs::msg::Quaternion &q): position(pt), orientation(q) {} // data members UTMPoint position; - geometry_msgs::Quaternion orientation; + geometry_msgs::msg::Quaternion orientation; }; // class UTMPose // conversion function prototypes -void fromMsg(const geographic_msgs::GeoPoint &from, UTMPoint &to); -void fromMsg(const geographic_msgs::GeoPose &from, UTMPose &to); -geographic_msgs::GeoPoint toMsg(const UTMPoint &from); -geographic_msgs::GeoPose toMsg(const UTMPose &from); +void fromMsg(const geographic_msgs::msg::GeoPoint &from, UTMPoint &to); +void fromMsg(const geographic_msgs::msg::GeoPose &from, UTMPose &to); +geographic_msgs::msg::GeoPoint toMsg(const UTMPoint &from); +geographic_msgs::msg::GeoPose toMsg(const UTMPose &from); /** @return true if no altitude specified. */ static inline bool is2D(const UTMPoint &pt) @@ -203,7 +203,7 @@ bool isValid(const UTMPose &pose); */ static inline void normalize(UTMPoint &pt) { - geographic_msgs::GeoPoint ll(toMsg(pt)); + geographic_msgs::msg::GeoPoint ll(toMsg(pt)); normalize(ll); fromMsg(ll, pt); } @@ -241,9 +241,9 @@ static inline bool sameGridZone(const UTMPose &pose1, const UTMPose &pose2) } /** @return a geometry Point corresponding to a UTM point. */ -static inline geometry_msgs::Point toGeometry(const UTMPoint &from) +static inline geometry_msgs::msg::Point toGeometry(const UTMPoint &from) { - geometry_msgs::Point to; + geometry_msgs::msg::Point to; to.x = from.easting; to.y = from.northing; to.z = from.altitude; @@ -251,9 +251,9 @@ static inline geometry_msgs::Point toGeometry(const UTMPoint &from) } /** @return a geometry Pose corresponding to a UTM pose. */ -static inline geometry_msgs::Pose toGeometry(const UTMPose &from) +static inline geometry_msgs::msg::Pose toGeometry(const UTMPose &from) { - geometry_msgs::Pose to; + geometry_msgs::msg::Pose to; to.position = toGeometry(from.position); to.orientation = from.orientation; return to; diff --git a/geodesy/include/geodesy/wgs84.h b/geodesy/include/geodesy/wgs84.h index 7290b1e..cce7d1c 100644 --- a/geodesy/include/geodesy/wgs84.h +++ b/geodesy/include/geodesy/wgs84.h @@ -40,10 +40,11 @@ #include #include -#include -#include -#include -#include +#include "geographic_msgs/msg/geo_point.hpp" +#include "geographic_msgs/msg/geo_pose.hpp" +#include "sensor_msgs/msg/nav_sat_fix.hpp" + +#define TF_QUATERNION_TOLERANCE 0.1 /** @file @@ -82,8 +83,8 @@ namespace geodesy * @param from WGS 84 point message. * @param to another point. */ - static inline void fromMsg(const geographic_msgs::GeoPoint &from, - geographic_msgs::GeoPoint &to) + static inline void fromMsg(const geographic_msgs::msg::GeoPoint &from, + geographic_msgs::msg::GeoPoint &to) { convert(from, to); } @@ -93,26 +94,26 @@ namespace geodesy * @param from WGS 84 pose message. * @param to another pose. */ - static inline void fromMsg(const geographic_msgs::GeoPose &from, - geographic_msgs::GeoPose &to) + static inline void fromMsg(const geographic_msgs::msg::GeoPose &from, + geographic_msgs::msg::GeoPose &to) { convert(from, to); } /** @return true if no altitude specified. */ - static inline bool is2D(const geographic_msgs::GeoPoint &pt) + static inline bool is2D(const geographic_msgs::msg::GeoPoint &pt) { return (pt.altitude != pt.altitude); } /** @return true if pose has no altitude. */ - static inline bool is2D(const geographic_msgs::GeoPose &pose) + static inline bool is2D(const geographic_msgs::msg::GeoPose &pose) { return is2D(pose.position); } /** @return true if point is valid. */ - static inline bool isValid(const geographic_msgs::GeoPoint &pt) + static inline bool isValid(const geographic_msgs::msg::GeoPoint &pt) { if (pt.latitude < -90.0 || pt.latitude > 90.0) return false; @@ -124,14 +125,14 @@ namespace geodesy } /** @return true if pose is valid. */ - static inline bool isValid(const geographic_msgs::GeoPose &pose) + static inline bool isValid(const geographic_msgs::msg::GeoPose &pose) { // check that orientation quaternion is normalized double len2 = (pose.orientation.x * pose.orientation.x + pose.orientation.y * pose.orientation.y + pose.orientation.z * pose.orientation.z + pose.orientation.w * pose.orientation.w); - if (fabs(len2 - 1.0) > tf::QUATERNION_TOLERANCE) + if (fabs(len2 - 1.0) > TF_QUATERNION_TOLERANCE) return false; return isValid(pose.position); @@ -144,7 +145,7 @@ namespace geodesy * Normalizes the longitude to [-180, 180). * Clamps latitude to [-90, 90]. */ - static inline void normalize(geographic_msgs::GeoPoint &pt) + static inline void normalize(geographic_msgs::msg::GeoPoint &pt) { pt.longitude = (fmod(fmod((pt.longitude + 180.0), 360.0) + 360.0, 360.0) - 180.0); @@ -152,9 +153,9 @@ namespace geodesy } /** @return a 2D WGS 84 geodetic point message. */ - static inline geographic_msgs::GeoPoint toMsg(double lat, double lon) + static inline geographic_msgs::msg::GeoPoint toMsg(double lat, double lon) { - geographic_msgs::GeoPoint pt; + geographic_msgs::msg::GeoPoint pt; pt.latitude = lat; pt.longitude = lon; pt.altitude = std::numeric_limits::quiet_NaN(); @@ -162,10 +163,10 @@ namespace geodesy } /** @return a 3D WGS 84 geodetic point message. */ - static inline geographic_msgs::GeoPoint + static inline geographic_msgs::msg::GeoPoint toMsg(double lat, double lon, double alt) { - geographic_msgs::GeoPoint pt; + geographic_msgs::msg::GeoPoint pt; pt.latitude = lat; pt.longitude = lon; pt.altitude = alt; @@ -173,10 +174,10 @@ namespace geodesy } /** @return a WGS 84 geodetic point message from a NavSatFix. */ - static inline geographic_msgs::GeoPoint - toMsg(const sensor_msgs::NavSatFix &fix) + static inline geographic_msgs::msg::GeoPoint + toMsg(const sensor_msgs::msg::NavSatFix &fix) { - geographic_msgs::GeoPoint pt; + geographic_msgs::msg::GeoPoint pt; pt.latitude = fix.latitude; pt.longitude = fix.longitude; pt.altitude = fix.altitude; @@ -184,8 +185,8 @@ namespace geodesy } /** @return a WGS 84 geodetic point message from another. */ - static inline geographic_msgs::GeoPoint - toMsg(const geographic_msgs::GeoPoint &from) + static inline geographic_msgs::msg::GeoPoint + toMsg(const geographic_msgs::msg::GeoPoint &from) { return from; } @@ -193,11 +194,11 @@ namespace geodesy /** @return a WGS 84 geodetic pose message from a point and a * quaternion. */ - static inline geographic_msgs::GeoPose - toMsg(const geographic_msgs::GeoPoint &pt, - const geometry_msgs::Quaternion &q) + static inline geographic_msgs::msg::GeoPose + toMsg(const geographic_msgs::msg::GeoPoint &pt, + const geometry_msgs::msg::Quaternion &q) { - geographic_msgs::GeoPose pose; + geographic_msgs::msg::GeoPose pose; pose.position = pt; pose.orientation = q; return pose; @@ -206,19 +207,19 @@ namespace geodesy /** @return a WGS 84 geodetic pose message from a NavSatFix and a * quaternion. */ - static inline geographic_msgs::GeoPose - toMsg(const sensor_msgs::NavSatFix &fix, - const geometry_msgs::Quaternion &q) + static inline geographic_msgs::msg::GeoPose + toMsg(const sensor_msgs::msg::NavSatFix &fix, + const geometry_msgs::msg::Quaternion &q) { - geographic_msgs::GeoPose pose; + geographic_msgs::msg::GeoPose pose; pose.position = toMsg(fix); pose.orientation = q; return pose; } /** @return a WGS 84 geodetic pose message from another. */ - static inline geographic_msgs::GeoPose - toMsg(const geographic_msgs::GeoPose &from) + static inline geographic_msgs::msg::GeoPose + toMsg(const geographic_msgs::msg::GeoPose &from) { return from; } diff --git a/geodesy/package.xml b/geodesy/package.xml index 85210ad..602adc4 100644 --- a/geodesy/package.xml +++ b/geodesy/package.xml @@ -1,11 +1,13 @@ - - + + + geodesy - 0.5.2 + 1.0.0 Python and C++ interfaces for manipulating geodetic coordinates. Jack O'Quin + Steve Macenski Jack O'Quin BSD @@ -13,23 +15,14 @@ https://github.com/ros-geographic-info/geographic_info/issues https://github.com/ros-geographic-info/geographic_info.git - catkin - - angles - geographic_msgs - geometry_msgs - sensor_msgs - tf - unique_id - uuid_msgs + ament_cmake - geographic_msgs - geometry_msgs - python-pyproj - tf - sensor_msgs - unique_id - uuid_msgs + angles + geographic_msgs + geometry_msgs + sensor_msgs + unique_identifier_msgs + python-pyproj rosunit @@ -38,6 +31,7 @@ python-catkin-pkg + ament_cmake diff --git a/geodesy/src/conv/utm_conversions.cpp b/geodesy/src/conv/utm_conversions.cpp index 8b94f2e..1084192 100644 --- a/geodesy/src/conv/utm_conversions.cpp +++ b/geodesy/src/conv/utm_conversions.cpp @@ -35,8 +35,7 @@ *********************************************************************/ //#include -#include -#include +#include "angles/angles.h" #include /** @file @@ -72,7 +71,6 @@ namespace geodesy #define UTM_E6 (UTM_E4*UTM_E2) // e^6 #define UTM_EP2 (UTM_E2/(1-UTM_E2)) // e'^2 - /** * Determine the correct UTM band letter for the given latitude. * (Does not currently handle polar (UPS) zones: A, B, Y, Z). @@ -116,7 +114,7 @@ static char UTMBand(double Lat, double Lon) * @param from WGS 84 point message. * @return UTM point. */ -geographic_msgs::GeoPoint toMsg(const UTMPoint &from) +geographic_msgs::msg::GeoPoint toMsg(const UTMPoint &from) { //remove 500,000 meter offset for longitude double x = from.easting - 500000.0; @@ -157,7 +155,7 @@ geographic_msgs::GeoPoint toMsg(const UTMPoint &from) D = x/(N1*k0); // function result - geographic_msgs::GeoPoint to; + geographic_msgs::msg::GeoPoint to; to.altitude = from.altitude; to.latitude = phi1Rad - ((N1*tan(phi1Rad)/R1) @@ -184,7 +182,7 @@ geographic_msgs::GeoPoint toMsg(const UTMPoint &from) * @param from WGS 84 point message. * @param to UTM point. */ -void fromMsg(const geographic_msgs::GeoPoint &from, UTMPoint &to) +void fromMsg(const geographic_msgs::msg::GeoPoint &from, UTMPoint &to) { double Lat = from.latitude; double Long = from.longitude; @@ -280,7 +278,7 @@ bool isValid(const UTMPoint &pt) } /** Create UTM point from WGS 84 geodetic point. */ -UTMPoint::UTMPoint(const geographic_msgs::GeoPoint &pt) +UTMPoint::UTMPoint(const geographic_msgs::msg::GeoPoint &pt) { fromMsg(pt, *this); } @@ -292,7 +290,7 @@ UTMPoint::UTMPoint(const geographic_msgs::GeoPoint &pt) * * @todo define the orientation transformation properly */ -void fromMsg(const geographic_msgs::GeoPose &from, UTMPose &to) +void fromMsg(const geographic_msgs::msg::GeoPose &from, UTMPose &to) { fromMsg(from.position, to.position); to.orientation = from.orientation; @@ -309,7 +307,7 @@ bool isValid(const UTMPose &pose) + pose.orientation.y * pose.orientation.y + pose.orientation.z * pose.orientation.z + pose.orientation.w * pose.orientation.w); - return fabs(len2 - 1.0) <= tf::QUATERNION_TOLERANCE; + return fabs(len2 - 1.0) <= TF_QUATERNION_TOLERANCE; } } // end namespace geodesy diff --git a/geographic_info/CHANGELOG.rst b/geographic_info/CHANGELOG.rst index a30bc24..e7f5cb8 100644 --- a/geographic_info/CHANGELOG.rst +++ b/geographic_info/CHANGELOG.rst @@ -1,6 +1,9 @@ Change history ============== +0.5.3 (2018-03-27) +------------------ + 0.5.2 (2017-04-15) ------------------ diff --git a/geographic_info/CMakeLists.txt b/geographic_info/CMakeLists.txt index 002ec45..2f1fede 100644 --- a/geographic_info/CMakeLists.txt +++ b/geographic_info/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) project(geographic_info) -find_package(catkin REQUIRED) -catkin_metapackage() +find_package(ament_cmake REQUIRED) +ament_package() diff --git a/geographic_info/package.xml b/geographic_info/package.xml index a6004a9..2a013e9 100644 --- a/geographic_info/package.xml +++ b/geographic_info/package.xml @@ -1,7 +1,8 @@ - - + + + geographic_info - 0.5.2 + 1.0.0 Geographic information metapackage. @@ -9,19 +10,16 @@ dependencies. Jack O'Quin + Steve Macenski Jack O'Quin BSD http://wiki.ros.org/geographic_info https://github.com/ros-geographic-info/geographic_info https://github.com/ros-geographic-info/geographic_info/issues - catkin - - geodesy - geographic_msgs + ament_cmake - - - + geodesy + geographic_msgs diff --git a/geographic_msgs/CHANGELOG.rst b/geographic_msgs/CHANGELOG.rst index 6a7aeb8..0b721f4 100644 --- a/geographic_msgs/CHANGELOG.rst +++ b/geographic_msgs/CHANGELOG.rst @@ -1,6 +1,11 @@ Change history ============== +0.5.3 (2018-03-27) +------------------ + +* Add additional information to ``GetGeoPath`` service response. + 0.5.2 (2017-04-15) ------------------ diff --git a/geographic_msgs/CMakeLists.txt b/geographic_msgs/CMakeLists.txt index ac7dfab..ced076c 100644 --- a/geographic_msgs/CMakeLists.txt +++ b/geographic_msgs/CMakeLists.txt @@ -1,22 +1,17 @@ cmake_minimum_required(VERSION 3.5) project(geographic_msgs) -# Add support for C++11 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 11) -endif() - find_package(ament_cmake REQUIRED) +find_package(unique_identifier_msgs REQUIRED) find_package(std_msgs REQUIRED) find_package(geometry_msgs REQUIRED) -find_package(uuid_msgs REQUIRED) -find_package(rosidl_default_generators REQUIRED) find_package(builtin_interfaces REQUIRED) +find_package(rosidl_default_generators REQUIRED) -rosidl_generate_interfaces(${PROJECT_NAME} +rosidl_generate_interfaces(${PROJECT_NAME} "msg/BoundingBox.msg" - "msg/GeographicMapChanges.msg" - "msg/GeographicMap.msg" + "msg/GeographicMapChanges.msg" + "msg/GeographicMap.msg" "msg/GeoPath.msg" "msg/GeoPoint.msg" "msg/GeoPointStamped.msg" @@ -32,33 +27,9 @@ rosidl_generate_interfaces(${PROJECT_NAME} "srv/GetGeoPath.srv" "srv/GetRoutePlan.srv" "srv/UpdateGeographicMap.srv" - DEPENDENCIES - builtin_interfaces - std_msgs - geometry_msgs - uuid_msgs + DEPENDENCIES unique_identifier_msgs geometry_msgs std_msgs builtin_interfaces ) -set(INCLUDE_DIRS ${ament_cmake_INCLUDE_DIRS} ${std_msgs_INCLUDE_DIRS} - ${geometry_msgs_INCLUDE_DIRS} ${uuid_msgs_INCLUDE_DIRS} - ${rosidl_default_generators_INCLUDE_DIRS}) -include_directories(${INCLUDE_DIRS}) - -set(LIBRARY_DIRS ${ament_cmake_LIBRARY_DIRS} ${std_msgs_LIBRARY_DIRS} - ${geometry_msgs_LIBRARY_DIRS} ${uuid_msgs_LIBRARY_DIRS} - ${rosidl_default_generators_LIBRARY_DIRS}) - -link_directories(${LIBRARY_DIRS}) - -set(LIBS ${ament_cmake_LIBRARIES} ${std_msgs_LIBRARIES} - ${geometry_msgs_LIBRARIES} ${uuid_msgs_LIBRARIES} - ${rosidl_default_generators_LIBRARIES}) - -ament_export_dependencies(ament_cmake) -ament_export_dependencies(std_msgs) -ament_export_dependencies(geometry_msgs) -ament_export_dependencies(uuid_msgs) -ament_export_dependencies(rosidl_default_generators) -ament_export_include_directories(${INCLUDE_DIRS}) +ament_export_dependencies(rosidl_default_runtime) ament_package() diff --git a/geographic_msgs/msg/GeographicMap.msg b/geographic_msgs/msg/GeographicMap.msg index 73a3cbd..4bc3e41 100644 --- a/geographic_msgs/msg/GeographicMap.msg +++ b/geographic_msgs/msg/GeographicMap.msg @@ -3,7 +3,7 @@ std_msgs/Header header # stamp specifies time # frame_id (normally /map) -uuid_msgs/UniqueID id # identifier for this map +unique_identifier_msgs/UUID id # identifier for this map BoundingBox bounds # 2D bounding box containing map WayPoint[] points # way-points diff --git a/geographic_msgs/msg/GeographicMapChanges.msg b/geographic_msgs/msg/GeographicMapChanges.msg index 2917492..1591586 100644 --- a/geographic_msgs/msg/GeographicMapChanges.msg +++ b/geographic_msgs/msg/GeographicMapChanges.msg @@ -4,4 +4,4 @@ std_msgs/Header header # stamp specifies time of change # frame_id (normally /map) GeographicMap diffs # new and changed points and features -uuid_msgs/UniqueID[] deletes # deleted map components +unique_identifier_msgs/UUID[] deletes # deleted map components diff --git a/geographic_msgs/msg/MapFeature.msg b/geographic_msgs/msg/MapFeature.msg index 49e040b..a2d5831 100644 --- a/geographic_msgs/msg/MapFeature.msg +++ b/geographic_msgs/msg/MapFeature.msg @@ -6,6 +6,6 @@ # # Feature lists may also contain other feature lists as members. -uuid_msgs/UniqueID id # Unique feature identifier -uuid_msgs/UniqueID[] components # Sequence of feature components +unique_identifier_msgs/UUID id # Unique feature identifier +unique_identifier_msgs/UUID[] components # Sequence of feature components KeyValue[] props # Key/value properties for this feature diff --git a/geographic_msgs/msg/RouteNetwork.msg b/geographic_msgs/msg/RouteNetwork.msg index e2cd30c..598622f 100644 --- a/geographic_msgs/msg/RouteNetwork.msg +++ b/geographic_msgs/msg/RouteNetwork.msg @@ -7,7 +7,7 @@ std_msgs/Header header -uuid_msgs/UniqueID id # This route network identifier +unique_identifier_msgs/UUID id # This route network identifier BoundingBox bounds # 2D bounding box for network WayPoint[] points # Way points in this network diff --git a/geographic_msgs/msg/RoutePath.msg b/geographic_msgs/msg/RoutePath.msg index 5631125..3655dfd 100644 --- a/geographic_msgs/msg/RoutePath.msg +++ b/geographic_msgs/msg/RoutePath.msg @@ -6,6 +6,6 @@ std_msgs/Header header -uuid_msgs/UniqueID network # Route network containing this path -uuid_msgs/UniqueID[] segments # Sequence of RouteSegment IDs +unique_identifier_msgs/UUID network # Route network containing this path +unique_identifier_msgs/UUID[] segments # Sequence of RouteSegment IDs KeyValue[] props # Key/value properties diff --git a/geographic_msgs/msg/RouteSegment.msg b/geographic_msgs/msg/RouteSegment.msg index 9b802d1..aaecf7b 100644 --- a/geographic_msgs/msg/RouteSegment.msg +++ b/geographic_msgs/msg/RouteSegment.msg @@ -4,9 +4,9 @@ # known path from one way point to another. If the path is two-way, # there will be another RouteSegment with "start" and "end" reversed. -uuid_msgs/UniqueID id # Unique identifier for this segment +unique_identifier_msgs/UUID id # Unique identifier for this segment -uuid_msgs/UniqueID start # beginning way point of segment -uuid_msgs/UniqueID end # ending way point of segment +unique_identifier_msgs/UUID start # beginning way point of segment +unique_identifier_msgs/UUID end # ending way point of segment KeyValue[] props # segment properties diff --git a/geographic_msgs/msg/WayPoint.msg b/geographic_msgs/msg/WayPoint.msg index 2f216d5..76dd8ca 100644 --- a/geographic_msgs/msg/WayPoint.msg +++ b/geographic_msgs/msg/WayPoint.msg @@ -1,5 +1,5 @@ # Way-point element for a geographic map. -uuid_msgs/UniqueID id # Unique way-point identifier +unique_identifier_msgs/UUID id # Unique way-point identifier GeoPoint position # Position relative to WGS 84 ellipsoid KeyValue[] props # Key/value properties for this point diff --git a/geographic_msgs/package.xml b/geographic_msgs/package.xml index a1d3a69..e92a52f 100644 --- a/geographic_msgs/package.xml +++ b/geographic_msgs/package.xml @@ -1,12 +1,14 @@ - + + geographic_msgs - 0.5.2 + 1.0.0 ROS messages for Geographic Information Systems. Jack O'Quin + Steve Macenski Jack O'Quin BSD @@ -16,20 +18,16 @@ ament_cmake - geometry_msgs - std_msgs - uuid_msgs + rosidl_default_generators + rosidl_default_runtime - message_runtime - geometry_msgs - std_msgs - uuid_msgs + geometry_msgs + std_msgs + unique_identifier_msgs rosidl_interface_packages - rosidl_default_generators - rosidl_default_runtime - ament_cmake + diff --git a/geographic_msgs/srv/GetGeoPath.srv b/geographic_msgs/srv/GetGeoPath.srv index 94c2a01..43cbb19 100644 --- a/geographic_msgs/srv/GetGeoPath.srv +++ b/geographic_msgs/srv/GetGeoPath.srv @@ -11,7 +11,7 @@ string status # more details geographic_msgs/GeoPath plan # path to follow -uuid_msgs/UniqueID network # the uuid of the RouteNetwork -uuid_msgs/UniqueID start_seg # the uuid of the starting RouteSegment -uuid_msgs/UniqueID goal_seg # the uuid of the ending RouteSegment +unique_identifier_msgs/UUID network # the uuid of the RouteNetwork +unique_identifier_msgs/UUID start_seg # the uuid of the starting RouteSegment +unique_identifier_msgs/UUID goal_seg # the uuid of the ending RouteSegment float64 distance # the length of the plan diff --git a/geographic_msgs/srv/GetRoutePlan.srv b/geographic_msgs/srv/GetRoutePlan.srv index f1bb88f..31abde9 100644 --- a/geographic_msgs/srv/GetRoutePlan.srv +++ b/geographic_msgs/srv/GetRoutePlan.srv @@ -2,9 +2,9 @@ # # Similar to nav_msgs/GetPlan, but constrained to use the route network. -uuid_msgs/UniqueID network # route network to use -uuid_msgs/UniqueID start # starting way point -uuid_msgs/UniqueID goal # goal way point +unique_identifier_msgs/UUID network # route network to use +unique_identifier_msgs/UUID start # starting way point +unique_identifier_msgs/UUID goal # goal way point ---