From 234936457d6af313eb3385645d9722b7b739c99b Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 8 Nov 2021 12:00:57 -0800 Subject: [PATCH 01/28] add enable_orientation to 1.6 spec (#686) Signed-off-by: Ian Chen --- sdf/1.6/imu.sdf | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/sdf/1.6/imu.sdf b/sdf/1.6/imu.sdf index 4bc082174..756cc80d9 100644 --- a/sdf/1.6/imu.sdf +++ b/sdf/1.6/imu.sdf @@ -118,4 +118,8 @@ + + Some IMU sensors rely on external filters to produce orientation estimates. True to generate and output orientation data, false to disable orientation data generation. + + From 0c6e7ad5a9e9c6a7472278a1192681a550032fb8 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 29 Nov 2021 10:37:20 -0800 Subject: [PATCH 02/28] Backport cmake/test fixes to sdf6 (#761) * Fix cmake warning about newlines * Find python3 in cmake, fix warning (#328) Signed-off-by: Steve Peters --- Changelog.md | 130 ++++++++++++------------ cmake/SearchForStuff.cmake | 2 +- include/sdf/CMakeLists.txt | 3 +- test/integration/element_memory_leak.cc | 2 +- 4 files changed, 68 insertions(+), 69 deletions(-) diff --git a/Changelog.md b/Changelog.md index 47af0b3cd..b92f53b65 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,6 +1,6 @@ -## SDFormat 6.0 +## libsdformat 6.0 -### SDFormat 6.3.1 (2021-07-06) +### libsdformat 6.3.1 (2021-07-06) 1. Fix flattening logic for nested model names * [Pull request 597](https://github.com/osrf/sdformat/pull/597) @@ -8,7 +8,7 @@ 1. Translate poses of nested models inside other nested models * [Pull request 596](https://github.com/osrf/sdformat/pull/596) -### SDFormat 6.3.0 (2021-06-21) +### libsdformat 6.3.0 (2021-06-21) 1. Move recursiveSameTypeUniqueNames from ign.cc to parser.cc and make public. * [Pull request 580](https://github.com/osrf/sdformat/pull/580) @@ -16,7 +16,7 @@ 1. Parse rpyOffset as radians * [Pull request 497](https://github.com/osrf/sdformat/pull/497) -1. Parse urdf files to sdf 1.5 instead of 1.4 to avoid `use_parent_model_frame`. +1. Parse urdf files to SDFormat 1.5 instead of 1.4 to avoid `use_parent_model_frame`. * [BitBucket pull request 575](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/575) 1. Set camera intrinsics axis skew (s) default value to 0 @@ -34,7 +34,7 @@ 1. Converter: remove all matching elements specified by `` tag. * [BitBucket pull request 551](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/551) -### SDFormat 6.2.0 (2019-01-17) +### libsdformat 6.2.0 (2019-01-17) 1. Add geometry for sonar collision shape * [BitBucket pull request 495](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/495) @@ -46,15 +46,15 @@ * [BitBucket pull request 466](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/466) -### SDFormat 6.1.0 (2018-10-04) +### libsdformat 6.1.0 (2018-10-04) 1. Add collision\_detector to dart physics config * [BitBucket pull request 440](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/440) -1. Fix Windows support for SDFormat6 +1. Fix Windows support for libsdformat6 * [BitBucket pull request 401](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/401) -1. root.sdf: default sdf version 1.6 +1. root.sdf: default SDFormat version 1.6 * [BitBucket pull request 425](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/425) 1. parser\_urdf: print value of highstop instead of pointer address @@ -64,7 +64,7 @@ * [BitBucket pull request 402](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/402) -### SDFormat 6.0.0 (2018-01-25) +### libsdformat 6.0.0 (2018-01-25) 1. SDF DOM: Added a document object model. * [BitBucket pull request 387](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/387) @@ -97,69 +97,69 @@ 1. Deprecated sdf::Color, and switch to use ignition::math::Color * [BitBucket pull request 330](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/330) -## SDFormat 5.x +## libsdformat 5.x -### SDFormat 5.x.x (2017-xx-xx) +### libsdformat 5.x.x (2017-xx-xx) -### SDFormat 5.3.0 (2017-11-13) +### libsdformat 5.3.0 (2017-11-13) 1. Added wrapper around root SDF for an SDF element - * [BitBucket pull request 378](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/378) - * [BitBucket pull request 372](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/372) + * [BitBucket pull request 378](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/378) + * [BitBucket pull request 372](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/372) 1. Add ODE parallelization parameters: threaded islands and position correction - * [BitBucket pull request 380](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/380) + * [BitBucket pull request 380](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/380) 1. surface.sdf: expand documentation of friction and slip coefficients - * [BitBucket pull request 343](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/343) + * [BitBucket pull request 343](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/343) 1. Add preserveFixedJoint option to the URDF parser - * [BitBucket pull request 352](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/352) + * [BitBucket pull request 352](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/352) 1. Add light as child of link - * [BitBucket pull request 373](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/373) + * [BitBucket pull request 373](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/373) -### SDFormat 5.2.0 (2017-08-03) +### libsdformat 5.2.0 (2017-08-03) 1. Added a block for DART-specific physics properties. * [BitBucket pull request 369](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/369) 1. Fix parser to read plugin child elements within an `` - * [BitBucket pull request 350](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/350) + * [BitBucket pull request 350](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/350) -1. Choosing models with more recent sdf version with `` tag - * [BitBucket pull request 291](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/291) +1. Choosing models with more recent SDFormat version with `` tag + * [BitBucket pull request 291](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/291) * [Issue 123](https://github.com/osrf/sdformat/issues/123) 1. Added `` to 1.6 surface contact parameters - * [BitBucket pull request 318](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/318) + * [BitBucket pull request 318](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/318) 1. Support light insertion in state - * [BitBucket pull request 325](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/325) + * [BitBucket pull request 325](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/325) 1. Case insensitive boolean strings - * [BitBucket pull request 322](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/322) + * [BitBucket pull request 322](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/322) 1. Enable coverage testing - * [BitBucket pull request 317](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/317) + * [BitBucket pull request 317](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/317) 1. Add `friction_model` parameter to ode solver - * [BitBucket pull request 294](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/294) - * [Gazebo pull request 1522](https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-request/1522) + * [BitBucket pull request 294](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/294) + * [Gazebo pull request 1522](https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-requests/1522) 1. Add cmake `@PKG_NAME@_LIBRARY_DIRS` variable to cmake config file - * [BitBucket pull request 292](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-request/292) + * [BitBucket pull request 292](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/292) -### SDFormat 5.1.0 (2017-02-22) +### libsdformat 5.1.0 (2017-02-22) 1. Fixed `sdf::convertFile` and `sdf::convertString` always converting to latest version * [BitBucket pull request 320](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/320) -1. Added back the ability to set sdf version at runtime +1. Added back the ability to set SDFormat version at runtime * [BitBucket pull request 307](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/307) -### SDFormat 5.0.0 (2017-01-25) +### libsdformat 5.0.0 (2017-01-25) -1. Removed SDFormat 4 deprecations +1. Removed libsdformat 4 deprecations * [BitBucket pull request 295](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/295) 1. Added an example @@ -182,11 +182,11 @@ 1. Simplifier way of retrieving a value from SDF using Get * [BitBucket pull request 285](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/285) -## SDFormat 4.0 +## libsdformat 4.0 -### SDFormat 4.x.x (2017-xx-xx) +### libsdformat 4.x.x (2017-xx-xx) -### SDFormat 4.4.0 (2017-10-26) +### libsdformat 4.4.0 (2017-10-26) 1. Add ODE parallelization parameters: threaded islands and position correction * [BitBucket pull request 380](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/380) @@ -200,7 +200,7 @@ 1. Add light as child of link * [BitBucket pull request 373](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/373) -### SDFormat 4.3.2 (2017-07-19) +### libsdformat 4.3.2 (2017-07-19) 1. Add documentation for `Element::GetFirstElement()` and `Element::GetNextElement()` * [BitBucket pull request 341](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/341) @@ -208,15 +208,15 @@ 1. Fix parser to read plugin child elements within an `` * [BitBucket pull request 350](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/350) -### SDFormat 4.3.1 (2017-03-24) +### libsdformat 4.3.1 (2017-03-24) 1. Fix segmentation Fault in `sdf::getBestSupportedModelVersion` * [BitBucket pull request 327](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/327) * [Issue 152](https://github.com/osrf/sdformat/issues/152) -### SDFormat 4.3.0 (2017-03-20) +### libsdformat 4.3.0 (2017-03-20) -1. Choosing models with more recent sdf version with `` tag +1. Choosing models with more recent SDFormat version with `` tag * [BitBucket pull request 291](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/291) * [Issue 123](https://github.com/osrf/sdformat/issues/123) @@ -245,7 +245,7 @@ 1. Add cmake `@PKG_NAME@_LIBRARY_DIRS` variable to cmake config file * [BitBucket pull request 292](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/292) -### SDFormat 4.2.0 (2016-10-10) +### libsdformat 4.2.0 (2016-10-10) 1. Added tag to specify ODE friction model. * [BitBucket pull request 294](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/294) @@ -256,7 +256,7 @@ 1. Added IMU orientation specification to SDF. * [BitBucket pull request 284](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/284) -### SDFormat 4.1.1 (2016-07-08) +### libsdformat 4.1.1 (2016-07-08) 1. Added documentation and animation to `` element. * [BitBucket pull request 280](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/280) @@ -264,7 +264,7 @@ 1. Added tag to specify initial joint position * [BitBucket pull request 279](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/279) -### SDFormat 4.1.0 (2016-04-01) +### libsdformat 4.1.0 (2016-04-01) 1. Added SDF conversion functions to parser including sdf::convertFile and sdf::convertString. * [BitBucket pull request 266](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/266) @@ -272,7 +272,7 @@ 1. Added an upload script * [BitBucket pull request 256](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/256) -### SDFormat 4.0.0 (2015-01-12) +### libsdformat 4.0.0 (2015-01-12) 1. Boost pointers and boost::function in the public API have been replaced by their std::equivalents (C++11 standard) @@ -296,18 +296,18 @@ * [BitBucket pull request 243](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/243) * [BitBucket pull request 199](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/199) -## SDFormat 3.0 +## libsdformat 3.0 -### SDFormat 3.X.X (201X-XX-XX) +### libsdformat 3.X.X (201X-XX-XX) 1. Improve precision of floating point parameters * [BitBucket pull request 273](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/273) * [BitBucket pull request 276](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/276) -### SDFormat 3.7.0 (2015-11-20) +### libsdformat 3.7.0 (2015-11-20) 1. Add spring pass through for sdf3 - * [Design document](https://github.com/osrf/gazebo_design/pull-requests/23) + * [Design document](https://osrf-migration.github.io/osrf-others-gh-pages/#!/osrf/gazebo_design/pull-requests/23) * [BitBucket pull request 242](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/242) 1. Support frame specification in SDF @@ -316,7 +316,7 @@ 1. Remove boost from SDFExtension * [BitBucket pull request 229](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/229) -### SDFormat 3.6.0 (2015-10-27) +### libsdformat 3.6.0 (2015-10-27) 1. Add light state * [BitBucket pull request 227](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/227) @@ -325,21 +325,21 @@ 1. Fix links in API documentation * [BitBucket pull request 231](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/231) -### SDFormat 3.5.0 (2015-10-07) +### libsdformat 3.5.0 (2015-10-07) 1. Camera lens description (Replaces #213) * [BitBucket pull request 215](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/215) 1. Fix shared pointer reference loop in Element and memory leak (#104) * [BitBucket pull request 230](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/230) -### SDFormat 3.4.0 (2015-10-05) +### libsdformat 3.4.0 (2015-10-05) 1. Support nested model states * [BitBucket pull request 223](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/223) 1. Cleaner way to set SDF_PATH for tests * [BitBucket pull request 226](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/226) -### SDFormat 3.3.0 (2015-09-15) +### libsdformat 3.3.0 (2015-09-15) 1. Windows Boost linking errors * [BitBucket pull request 206](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/206) @@ -350,7 +350,7 @@ 1. Torsional friction default surface radius not infinity * [BitBucket pull request 217](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/217) -### SDFormat 3.2.2 (2015-08-24) +### libsdformat 3.2.2 (2015-08-24) 1. Added battery element (contribution from Olivier Crave) * [BitBucket pull request #204](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/204) @@ -359,17 +359,17 @@ 1. Allow Visual Studio 2015 * [BitBucket pull request #208](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/208) -### SDFormat 3.1.1 (2015-08-03) +### libsdformat 3.1.1 (2015-08-03) 1. Fix tinyxml linking error * [BitBucket pull request #209](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/209) -### SDFormat 3.1.0 (2015-08-02) +### libsdformat 3.1.0 (2015-08-02) 1. Added logical camera sensor to SDF * [BitBucket pull request #207](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/207) -### SDFormat 3.0.0 (2015-07-24) +### libsdformat 3.0.0 (2015-07-24) 1. Added battery to SDF * [BitBucket pull request 204](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/204) @@ -409,7 +409,7 @@ * [BitBucket pull request 147](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/147) * [Issue 60](https://github.com/osrf/sdformat/issues/60) -## SDFormat 2.x +## libsdformat 2.x 1. rename cfm_damping --> implicit_spring_damper * [BitBucket pull request 59](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/59) @@ -421,7 +421,7 @@ * [BitBucket pull request 64](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/64) 1. `` element used by DEM heightmaps * [BitBucket pull request 67](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/67) -1. Do not export urdf symbols in sdformat 1.4 +1. Do not export urdf symbols in SDFormat 1.4 * [BitBucket pull request 75](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/75) 1. adding deformable properties per issue #32 * [BitBucket pull request 78](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/78) @@ -436,7 +436,7 @@ * [Gazebo issue 494](https://github.com/osrf/gazebo/issues/494) 1. Implement SDF_PROTOCOL_VERSION (issue #51) * [BitBucket pull request 90](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/90) -1. Port sdformat to compile on Windows (MSVC) +1. Port libsdformat to compile on Windows (MSVC) * [BitBucket pull request 101](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/101) 1. Separate material properties in material.sdf * [BitBucket pull request 104](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/104) @@ -462,7 +462,7 @@ * [BitBucket pull request 127](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/127) 1. Backport magnetometer * [BitBucket pull request 128](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/128) -1. Add flag for MOI rescaling to sdf 1.4 +1. Add flag for MOI rescaling to SDFormat 1.4 * [BitBucket pull request 121](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/121) 1. Parse urdf joint friction parameters, add corresponding test * [BitBucket pull request 129](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/129) @@ -487,9 +487,9 @@ 1. Backport fix for latin locales (pull request #147) * [BitBucket pull request 150](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/150) -## SDFormat 1.4 +## libsdformat 1.4 -### SDFormat 1.4.8 (2013-09-06) +### libsdformat 1.4.8 (2013-09-06) 1. Fix inertia transformations when reducing fixed joints in URDF * [BitBucket pull request 48](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/48/fix-for-issue-22-reducing-inertia-across/diff) @@ -499,12 +499,12 @@ * [BitBucket pull request 46](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/46/convert-a-few-more-sdfwarns-to-sdflog-fix/diff) * [Commit](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/commits/b15d5a1ecc57abee6691618d02d59bbc3d1b84dc) -### SDFormat 1.4.7 (2013-08-22) +### libsdformat 1.4.7 (2013-08-22) 1. Direct console messages to std_err * [BitBucket pull request 44](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/44/fix-19-direct-all-messages-to-std_err) -### SDFormat 1.4.6 (2013-08-20) +### libsdformat 1.4.6 (2013-08-20) 1. Add tags for GPS sensor and sensor noise * [BitBucket pull request 36](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/36/gps-sensor-sensor-noise-and-spherical) @@ -522,7 +522,7 @@ * [BitBucket pull request 38](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/38/add-provide_feedback-for-bullet-joint) 1. Various bug, style and test fixes -### SDFormat 1.4.5 (2013-07-23) +### libsdformat 1.4.5 (2013-07-23) 1. Deprecated Gazebo's internal SDF code 1. Use templatized Get functions for retrieving values from SDF files diff --git a/cmake/SearchForStuff.cmake b/cmake/SearchForStuff.cmake index c2a0ee452..7b594f374 100644 --- a/cmake/SearchForStuff.cmake +++ b/cmake/SearchForStuff.cmake @@ -98,7 +98,7 @@ endif() ################################################ # Find the Python interpreter for running the # check_test_ran.py script -find_package(PythonInterp QUIET) +find_package(PythonInterp 3 QUIET) ################################################ # Find psutil python package for memory tests diff --git a/include/sdf/CMakeLists.txt b/include/sdf/CMakeLists.txt index 7b4b7c6cf..af600de9c 100644 --- a/include/sdf/CMakeLists.txt +++ b/include/sdf/CMakeLists.txt @@ -18,8 +18,7 @@ set (headers set (sdf_headers "" CACHE INTERNAL "SDF headers" FORCE) foreach (hdr ${headers}) - APPEND_TO_CACHED_STRING(sdf_headers - "SDF Headers" "#include \n") + set(sdf_headers "${sdf_headers}#include \n") endforeach() configure_file (${CMAKE_CURRENT_SOURCE_DIR}/sdf.hh.in ${CMAKE_CURRENT_BINARY_DIR}/sdf.hh) diff --git a/test/integration/element_memory_leak.cc b/test/integration/element_memory_leak.cc index f85c49786..aee5f7b8e 100644 --- a/test/integration/element_memory_leak.cc +++ b/test/integration/element_memory_leak.cc @@ -71,7 +71,7 @@ const std::string sdfString( const std::string getMemInfoPath = sdf::filesystem::append(PROJECT_SOURCE_PATH, "tools", "get_mem_info.py"); -const std::string pythonMeminfo("python " + getMemInfoPath); +const std::string pythonMeminfo("python3 " + getMemInfoPath); int getMemoryUsage() { From 3b385c989cb1afd9fdaf844835a1ea52a77b8355 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Mon, 6 Dec 2021 10:34:24 -0800 Subject: [PATCH 03/28] Added ToElement conversion for physics and atmosphere (#771) * Added ToElement conversion for physics and atmosphere Signed-off-by: Nate Koenig * spelling Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- include/sdf/Atmosphere.hh | 5 +++++ include/sdf/Physics.hh | 17 +++++++++++++++++ src/Atmosphere.cc | 15 +++++++++++++++ src/Atmosphere_TEST.cc | 23 +++++++++++++++++++++++ src/Physics.cc | 38 ++++++++++++++++++++++++++++++++++++++ src/Physics_TEST.cc | 26 ++++++++++++++++++++++++++ 6 files changed, 124 insertions(+) diff --git a/include/sdf/Atmosphere.hh b/include/sdf/Atmosphere.hh index 3cee963ba..aaa9d5683 100644 --- a/include/sdf/Atmosphere.hh +++ b/include/sdf/Atmosphere.hh @@ -95,6 +95,11 @@ namespace sdf /// \return True if this instance equals the given atmosphere. public: bool operator==(const Atmosphere &_atmosphere); + /// \brief Create and return an SDF element filled with data from this + /// atmosphere. + /// \return SDF element pointer with updated atmosphere values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Physics.hh b/include/sdf/Physics.hh index 58331113b..c065cad66 100644 --- a/include/sdf/Physics.hh +++ b/include/sdf/Physics.hh @@ -102,6 +102,23 @@ namespace sdf /// \param[in] _factor The target real time factor. public: void SetRealTimeFactor(const double _factor); + /// \brief Get the maximum number of contacts allowed between two + /// entities. This value can be overridden by a max_contacts element in a + /// collision element. + /// \return Maximum number of contacts. + public: int MaxContacts() const; + + /// \brief Set the maximum number of contacts allowed between two + /// entities. This value can be overridden by a max_contacts element in a + /// collision element. + /// \param[in] _maxContacts Maximum number of contacts. + public: void SetMaxContacts(int _maxContacts); + + /// \brief Create and return an SDF element filled with data from this + /// physics. + /// \return SDF element pointer with updated physics values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/src/Atmosphere.cc b/src/Atmosphere.cc index ffe284387..36ca6d96a 100644 --- a/src/Atmosphere.cc +++ b/src/Atmosphere.cc @@ -18,6 +18,7 @@ #include #include #include "sdf/Atmosphere.hh" +#include "sdf/parser.hh" using namespace sdf; @@ -144,3 +145,17 @@ bool Atmosphere::operator==(const Atmosphere &_atmosphere) ignition::math::equal(this->dataPtr->pressure, _atmosphere.dataPtr->pressure); } + +///////////////////////////////////////////////// +sdf::ElementPtr Atmosphere::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("atmosphere.sdf", elem); + + elem->GetAttribute("type")->Set("adiabatic"); + elem->GetElement("temperature")->Set(this->Temperature().Kelvin()); + elem->GetElement("pressure")->Set(this->Pressure()); + elem->GetElement("temperature_gradient")->Set(this->TemperatureGradient()); + + return elem; +} diff --git a/src/Atmosphere_TEST.cc b/src/Atmosphere_TEST.cc index eb9d6636b..37d11de3b 100644 --- a/src/Atmosphere_TEST.cc +++ b/src/Atmosphere_TEST.cc @@ -16,6 +16,7 @@ */ #include +#include #include #include "sdf/World.hh" @@ -130,3 +131,25 @@ TEST(DOMAtmosphere, CopyAssignmentAfterMove) EXPECT_DOUBLE_EQ(200.0, atmosphere1.Temperature().Kelvin()); EXPECT_DOUBLE_EQ(100.0, atmosphere2.Temperature().Kelvin()); } + +///////////////////////////////////////////////// +TEST(DOMAtmosphere, ToElement) +{ + sdf::Atmosphere atmosphere; + atmosphere.SetType(sdf::AtmosphereType::ADIABATIC); + atmosphere.SetTemperature(ignition::math::Temperature(123)); + atmosphere.SetTemperatureGradient(1.34); + atmosphere.SetPressure(2.65); + + sdf::ElementPtr elem = atmosphere.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Atmosphere atmosphere2; + atmosphere2.Load(elem); + + // verify values after loading the element back + EXPECT_EQ(atmosphere.Temperature(), atmosphere2.Temperature()); + EXPECT_DOUBLE_EQ(atmosphere.TemperatureGradient(), + atmosphere2.TemperatureGradient()); + EXPECT_DOUBLE_EQ(atmosphere.Pressure(), atmosphere2.Pressure()); +} diff --git a/src/Physics.cc b/src/Physics.cc index 480b85407..643e9329a 100644 --- a/src/Physics.cc +++ b/src/Physics.cc @@ -16,6 +16,7 @@ */ #include +#include "sdf/parser.hh" #include "sdf/Physics.hh" #include "Utils.hh" @@ -41,6 +42,9 @@ class sdf::Physics::Implementation /// \brief Desired realtime factor. public: double rtf {1.0}; + + /// \brief Maximum number of contacts allowed between two entities. + public: int maxContacts{20}; }; ///////////////////////////////////////////////// @@ -113,6 +117,9 @@ Errors Physics::Load(sdf::ElementPtr _sdf) } this->dataPtr->rtf = doublePair.first; + this->dataPtr->maxContacts = + _sdf->Get("max_contacts", this->dataPtr->maxContacts).first; + return errors; } @@ -181,3 +188,34 @@ void Physics::SetRealTimeFactor(const double _factor) { this->dataPtr->rtf = _factor; } + +///////////////////////////////////////////////// +int Physics::MaxContacts() const +{ + return this->dataPtr->maxContacts; +} + +///////////////////////////////////////////////// +void Physics::SetMaxContacts(int _maxContacts) +{ + this->dataPtr->maxContacts = _maxContacts; +} + +///////////////////////////////////////////////// +sdf::ElementPtr Physics::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("physics.sdf", elem); + + elem->GetAttribute("name")->Set(this->Name()); + elem->GetAttribute("default")->Set(this->IsDefault()); + elem->GetAttribute("type")->Set(this->EngineType()); + + elem->GetElement("max_step_size")->Set(this->MaxStepSize()); + elem->GetElement("real_time_factor")->Set(this->RealTimeFactor()); + elem->GetElement("max_contacts")->Set(this->MaxContacts()); + + /// \todo(nkoenig) Support engine specific parameters. + + return elem; +} diff --git a/src/Physics_TEST.cc b/src/Physics_TEST.cc index c02fcbc21..43bf95fa0 100644 --- a/src/Physics_TEST.cc +++ b/src/Physics_TEST.cc @@ -105,3 +105,29 @@ TEST(DOMPhysics, CopyAssignmentAfterMove) EXPECT_EQ("physics2", physics1.Name()); EXPECT_EQ("physics1", physics2.Name()); } + +///////////////////////////////////////////////// +TEST(DOMPhysics, ToElement) +{ + sdf::Physics physics; + physics.SetName("my-bullet-engine"); + physics.SetDefault(true); + physics.SetEngineType("bullet"); + physics.SetMaxStepSize(0.1); + physics.SetRealTimeFactor(20.4); + physics.SetMaxContacts(42); + + sdf::ElementPtr elem = physics.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Physics physics2; + physics2.Load(elem); + + // verify values after loading the element back + EXPECT_EQ(physics.Name(), physics2.Name()); + EXPECT_EQ(physics.IsDefault(), physics2.IsDefault()); + EXPECT_EQ(physics.EngineType(), physics2.EngineType()); + EXPECT_DOUBLE_EQ(physics.MaxStepSize(), physics2.MaxStepSize()); + EXPECT_DOUBLE_EQ(physics.RealTimeFactor(), physics2.RealTimeFactor()); + EXPECT_EQ(physics.MaxContacts(), physics2.MaxContacts()); +} From 520b74fbf2390246e4547c0ec782ab582c78eeba Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Mon, 6 Dec 2021 11:33:48 -0800 Subject: [PATCH 04/28] Aded ToElement conversion for shapes (#772) * Aded ToElement conversion for shapes Signed-off-by: Nate Koenig * doxygen Signed-off-by: Ian Chen Co-authored-by: Nate Koenig Co-authored-by: Ian Chen --- include/sdf/Box.hh | 5 ++++ include/sdf/Capsule.hh | 5 ++++ include/sdf/Cylinder.hh | 5 ++++ include/sdf/Ellipsoid.hh | 5 ++++ include/sdf/Heightmap.hh | 9 ++++++-- include/sdf/Mesh.hh | 5 ++++ include/sdf/Plane.hh | 5 ++++ include/sdf/Sphere.hh | 5 ++++ src/Box.cc | 13 +++++++++++ src/Box_TEST.cc | 16 +++++++++++++ src/Capsule.cc | 16 +++++++++++++ src/Capsule_TEST.cc | 18 +++++++++++++++ src/Cylinder.cc | 16 +++++++++++++ src/Cylinder_TEST.cc | 18 +++++++++++++++ src/Ellipsoid.cc | 13 +++++++++++ src/Ellipsoid_TEST.cc | 16 +++++++++++++ src/Heightmap.cc | 47 +++++++++++++++++++++++++++++++++++++ src/Heightmap_TEST.cc | 50 ++++++++++++++++++++++++++++++++++++++++ src/Mesh.cc | 30 ++++++++++++++++++++++++ src/Mesh_TEST.cc | 22 ++++++++++++++++++ src/Plane.cc | 16 +++++++++++++ src/Plane_TEST.cc | 18 +++++++++++++++ src/Sphere.cc | 13 +++++++++++ src/Sphere_TEST.cc | 16 +++++++++++++ 24 files changed, 380 insertions(+), 2 deletions(-) diff --git a/include/sdf/Box.hh b/include/sdf/Box.hh index 9ac7fa219..2ba1ee9fa 100644 --- a/include/sdf/Box.hh +++ b/include/sdf/Box.hh @@ -65,6 +65,11 @@ namespace sdf /// \return A reference to an ignition::math::Boxd object. public: ignition::math::Boxd &Shape(); + /// \brief Create and return an SDF element filled with data from this + /// box. + /// \return SDF element pointer with updated box values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Capsule.hh b/include/sdf/Capsule.hh index 76a91f077..56ffbe6b3 100644 --- a/include/sdf/Capsule.hh +++ b/include/sdf/Capsule.hh @@ -72,6 +72,11 @@ namespace sdf /// \return A reference to an ignition::math::Capsuled object. public: ignition::math::Capsuled &Shape(); + /// \brief Create and return an SDF element filled with data from this + /// capsule. + /// \return SDF element pointer with updated capsule values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Cylinder.hh b/include/sdf/Cylinder.hh index 9a48b59a5..606399b21 100644 --- a/include/sdf/Cylinder.hh +++ b/include/sdf/Cylinder.hh @@ -72,6 +72,11 @@ namespace sdf /// \return A reference to an ignition::math::Cylinderd object. public: ignition::math::Cylinderd &Shape(); + /// \brief Create and return an SDF element filled with data from this + /// cylinder. + /// \return SDF element pointer with updated cylinder values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Ellipsoid.hh b/include/sdf/Ellipsoid.hh index fadd4ed81..fa18e9eed 100644 --- a/include/sdf/Ellipsoid.hh +++ b/include/sdf/Ellipsoid.hh @@ -64,6 +64,11 @@ namespace sdf /// \return A reference to an ignition::math::Ellipsoidd object. public: ignition::math::Ellipsoidd &Shape(); + /// \brief Create and return an SDF element filled with data from this + /// ellipsoid. + /// \return SDF element pointer with updated ellipsoid values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Heightmap.hh b/include/sdf/Heightmap.hh index 11a664b56..a08a1706d 100644 --- a/include/sdf/Heightmap.hh +++ b/include/sdf/Heightmap.hh @@ -47,8 +47,8 @@ namespace sdf public: double Size() const; /// \brief Set the size of the texture in meters. - /// \param[in] _uri The size of the texture in meters. - public: void SetSize(double _uri); + /// \param[in] _size The size of the texture in meters. + public: void SetSize(double _size); /// \brief Get the heightmap texture's diffuse map. /// \return The diffuse map of the heightmap texture. @@ -214,6 +214,11 @@ namespace sdf /// not been called. public: sdf::ElementPtr Element() const; + /// \brief Create and return an SDF element filled with data from this + /// heightmap. + /// \return SDF element pointer with updated heightmap values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Mesh.hh b/include/sdf/Mesh.hh index b75349200..7636534d3 100644 --- a/include/sdf/Mesh.hh +++ b/include/sdf/Mesh.hh @@ -97,6 +97,11 @@ namespace sdf /// not been called. public: sdf::ElementPtr Element() const; + /// \brief Create and return an SDF element filled with data from this + /// mesh. + /// \return SDF element pointer with updated mesh values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Plane.hh b/include/sdf/Plane.hh index c0ea5a4d7..e02de22e1 100644 --- a/include/sdf/Plane.hh +++ b/include/sdf/Plane.hh @@ -80,6 +80,11 @@ namespace sdf /// \return A reference to an ignition::math::Planed object. public: ignition::math::Planed &Shape(); + /// \brief Create and return an SDF element filled with data from this + /// plane. + /// \return SDF element pointer with updated plane values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Sphere.hh b/include/sdf/Sphere.hh index 10d91b897..42f8da4c5 100644 --- a/include/sdf/Sphere.hh +++ b/include/sdf/Sphere.hh @@ -65,6 +65,11 @@ namespace sdf /// not been called. public: sdf::ElementPtr Element() const; + /// \brief Create and return an SDF element filled with data from this + /// sphere. + /// \return SDF element pointer with updated sphere values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/src/Box.cc b/src/Box.cc index 90ceb26e3..6c029dac0 100644 --- a/src/Box.cc +++ b/src/Box.cc @@ -16,6 +16,7 @@ */ #include #include "sdf/Box.hh" +#include "sdf/parser.hh" using namespace sdf; @@ -112,3 +113,15 @@ ignition::math::Boxd &Box::Shape() { return this->dataPtr->box; } + +///////////////////////////////////////////////// +sdf::ElementPtr Box::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("box_shape.sdf", elem); + + sdf::ElementPtr sizeElem = elem->GetElement("size"); + sizeElem->Set(this->Size()); + + return elem; +} diff --git a/src/Box_TEST.cc b/src/Box_TEST.cc index b77bd23a7..762d0a0b9 100644 --- a/src/Box_TEST.cc +++ b/src/Box_TEST.cc @@ -143,3 +143,19 @@ TEST(DOMBox, Shape) box.Shape().SetSize(ignition::math::Vector3d(1, 2, 3)); EXPECT_EQ(ignition::math::Vector3d(1, 2, 3), box.Size()); } + +///////////////////////////////////////////////// +TEST(DOMBox, ToElement) +{ + sdf::Box box; + + box.SetSize(ignition::math::Vector3d(1, 2, 3)); + + sdf::ElementPtr elem = box.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Box box2; + box2.Load(elem); + + EXPECT_EQ(box.Size(), box2.Size()); +} diff --git a/src/Capsule.cc b/src/Capsule.cc index 507cbe0c4..a99159d69 100644 --- a/src/Capsule.cc +++ b/src/Capsule.cc @@ -16,6 +16,7 @@ */ #include #include "sdf/Capsule.hh" +#include "sdf/parser.hh" using namespace sdf; @@ -134,3 +135,18 @@ ignition::math::Capsuled &Capsule::Shape() { return this->dataPtr->capsule; } + +///////////////////////////////////////////////// +sdf::ElementPtr Capsule::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("capsule_shape.sdf", elem); + + sdf::ElementPtr radiusElem = elem->GetElement("radius"); + radiusElem->Set(this->Radius()); + + sdf::ElementPtr lengthElem = elem->GetElement("length"); + lengthElem->Set(this->Length()); + + return elem; +} diff --git a/src/Capsule_TEST.cc b/src/Capsule_TEST.cc index 20b55c644..9c66d9797 100644 --- a/src/Capsule_TEST.cc +++ b/src/Capsule_TEST.cc @@ -179,3 +179,21 @@ TEST(DOMCapsule, Shape) EXPECT_DOUBLE_EQ(0.123, capsule.Radius()); EXPECT_DOUBLE_EQ(0.456, capsule.Length()); } + +///////////////////////////////////////////////// +TEST(DOMCapsule, ToElement) +{ + sdf::Capsule capsule; + + capsule.SetRadius(1.2); + capsule.SetLength(0.5); + + sdf::ElementPtr elem = capsule.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Capsule capsule2; + capsule2.Load(elem); + + EXPECT_DOUBLE_EQ(capsule.Radius(), capsule2.Radius()); + EXPECT_DOUBLE_EQ(capsule.Length(), capsule2.Length()); +} diff --git a/src/Cylinder.cc b/src/Cylinder.cc index c04de1592..681ea8440 100644 --- a/src/Cylinder.cc +++ b/src/Cylinder.cc @@ -16,6 +16,7 @@ */ #include #include "sdf/Cylinder.hh" +#include "sdf/parser.hh" using namespace sdf; @@ -134,3 +135,18 @@ ignition::math::Cylinderd &Cylinder::Shape() { return this->dataPtr->cylinder; } + +///////////////////////////////////////////////// +sdf::ElementPtr Cylinder::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("cylinder_shape.sdf", elem); + + sdf::ElementPtr radiusElem = elem->GetElement("radius"); + radiusElem->Set(this->Radius()); + + sdf::ElementPtr lengthElem = elem->GetElement("length"); + lengthElem->Set(this->Length()); + + return elem; +} diff --git a/src/Cylinder_TEST.cc b/src/Cylinder_TEST.cc index 741dc77d4..7493f6f8b 100644 --- a/src/Cylinder_TEST.cc +++ b/src/Cylinder_TEST.cc @@ -175,3 +175,21 @@ TEST(DOMCylinder, Shape) EXPECT_DOUBLE_EQ(0.123, cylinder.Radius()); EXPECT_DOUBLE_EQ(0.456, cylinder.Length()); } + +///////////////////////////////////////////////// +TEST(DOMCylinder, ToElement) +{ + sdf::Cylinder cylinder; + + cylinder.SetRadius(1.2); + cylinder.SetLength(0.5); + + sdf::ElementPtr elem = cylinder.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Cylinder cylinder2; + cylinder2.Load(elem); + + EXPECT_DOUBLE_EQ(cylinder.Radius(), cylinder2.Radius()); + EXPECT_DOUBLE_EQ(cylinder.Length(), cylinder2.Length()); +} diff --git a/src/Ellipsoid.cc b/src/Ellipsoid.cc index 694b9a1e1..8ef41b49a 100644 --- a/src/Ellipsoid.cc +++ b/src/Ellipsoid.cc @@ -16,6 +16,7 @@ */ #include #include "sdf/Ellipsoid.hh" +#include "sdf/parser.hh" using namespace sdf; @@ -113,3 +114,15 @@ ignition::math::Ellipsoidd &Ellipsoid::Shape() { return this->dataPtr->ellipsoid; } + +///////////////////////////////////////////////// +sdf::ElementPtr Ellipsoid::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("ellipsoid_shape.sdf", elem); + + sdf::ElementPtr radiiElem = elem->GetElement("radii"); + radiiElem->Set(this->Radii()); + + return elem; +} diff --git a/src/Ellipsoid_TEST.cc b/src/Ellipsoid_TEST.cc index 8a4bf4138..d05556f68 100644 --- a/src/Ellipsoid_TEST.cc +++ b/src/Ellipsoid_TEST.cc @@ -139,3 +139,19 @@ TEST(DOMEllipsoid, Shape) ellipsoid.Shape().SetRadii(expectedRadii); EXPECT_EQ(expectedRadii, ellipsoid.Radii()); } + +///////////////////////////////////////////////// +TEST(DOMEllipsoid, ToElement) +{ + sdf::Ellipsoid ellipsoid; + + ellipsoid.SetRadii(ignition::math::Vector3d(0.1, 1.2, 3.4)); + + sdf::ElementPtr elem = ellipsoid.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Ellipsoid ellipsoid2; + ellipsoid2.Load(elem); + + EXPECT_EQ(ellipsoid.Radii(), ellipsoid2.Radii()); +} diff --git a/src/Heightmap.cc b/src/Heightmap.cc index 8d018730f..9583192f1 100644 --- a/src/Heightmap.cc +++ b/src/Heightmap.cc @@ -19,6 +19,7 @@ #include "Utils.hh" #include "sdf/Heightmap.hh" +#include "sdf/parser.hh" using namespace sdf; @@ -459,3 +460,49 @@ void Heightmap::AddBlend(const HeightmapBlend &_blend) { this->dataPtr->blends.push_back(_blend); } + +///////////////////////////////////////////////// +sdf::ElementPtr Heightmap::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("heightmap_shape.sdf", elem); + + // Uri + sdf::ElementPtr uriElem = elem->GetElement("uri"); + uriElem->Set(this->Uri()); + + // Size + sdf::ElementPtr sizeElem = elem->GetElement("size"); + sizeElem->Set(this->Size()); + + // Position + sdf::ElementPtr posElem = elem->GetElement("pos"); + posElem->Set(this->Position()); + + // Terrain paging + sdf::ElementPtr pagingElem = elem->GetElement("use_terrain_paging"); + pagingElem->Set(this->UseTerrainPaging()); + + // Sampling + sdf::ElementPtr samplingElem = elem->GetElement("sampling"); + samplingElem->Set(this->Sampling()); + + // Textures + for (const HeightmapTexture &tex : this->dataPtr->textures) + { + sdf::ElementPtr texElem = elem->AddElement("texture"); + texElem->GetElement("size")->Set(tex.Size()); + texElem->GetElement("diffuse")->Set(tex.Diffuse()); + texElem->GetElement("normal")->Set(tex.Normal()); + } + + // Blends + for (const HeightmapBlend &blend : this->dataPtr->blends) + { + sdf::ElementPtr blendElem = elem->AddElement("blend"); + blendElem->GetElement("min_height")->Set(blend.MinHeight()); + blendElem->GetElement("fade_dist")->Set(blend.FadeDistance()); + } + + return elem; +} diff --git a/src/Heightmap_TEST.cc b/src/Heightmap_TEST.cc index 4cd1b1dc9..fe45184a9 100644 --- a/src/Heightmap_TEST.cc +++ b/src/Heightmap_TEST.cc @@ -406,3 +406,53 @@ TEST(DOMHeightmap, LoadErrors) "missing a ")); EXPECT_NE(nullptr, heightmapBlend.Element()); } + +///////////////////////////////////////////////// +TEST(DOMHeightmap, ToElement) +{ + sdf::Heightmap heightmap; + + heightmap.SetUri("https://test-uri.org"); + heightmap.SetSize(ignition::math::Vector3d(1, 2, 3)); + heightmap.SetPosition(ignition::math::Vector3d(4, 5, 6)); + heightmap.SetUseTerrainPaging(true); + heightmap.SetSampling(2); + + sdf::HeightmapTexture texture; + texture.SetSize(1.2); + texture.SetDiffuse("diffuse_map"); + texture.SetNormal("normal_map"); + heightmap.AddTexture(texture); + + sdf::HeightmapBlend blend; + blend.SetMinHeight(1.2); + blend.SetFadeDistance(3.4); + heightmap.AddBlend(blend); + + sdf::ElementPtr elem = heightmap.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Heightmap heightmap2; + heightmap2.Load(elem); + + EXPECT_EQ(heightmap.Uri(), heightmap2.Uri()); + EXPECT_EQ(heightmap.Size(), heightmap2.Size()); + EXPECT_EQ(heightmap.Position(), heightmap2.Position()); + EXPECT_EQ(heightmap.UseTerrainPaging(), heightmap2.UseTerrainPaging()); + EXPECT_EQ(heightmap.Sampling(), heightmap2.Sampling()); + EXPECT_EQ(heightmap.TextureCount(), heightmap2.TextureCount()); + ASSERT_EQ(1u, heightmap2.TextureCount()); + EXPECT_DOUBLE_EQ(heightmap.TextureByIndex(0)->Size(), + heightmap2.TextureByIndex(0)->Size()); + EXPECT_EQ(heightmap.TextureByIndex(0)->Diffuse(), + heightmap2.TextureByIndex(0)->Diffuse()); + EXPECT_EQ(heightmap.TextureByIndex(0)->Normal(), + heightmap2.TextureByIndex(0)->Normal()); + + EXPECT_EQ(heightmap.BlendCount(), heightmap2.BlendCount()); + ASSERT_EQ(1u, heightmap2.BlendCount()); + EXPECT_DOUBLE_EQ(heightmap.BlendByIndex(0)->MinHeight(), + heightmap2.BlendByIndex(0)->MinHeight()); + EXPECT_DOUBLE_EQ(heightmap.BlendByIndex(0)->FadeDistance(), + heightmap2.BlendByIndex(0)->FadeDistance()); +} diff --git a/src/Mesh.cc b/src/Mesh.cc index 553623c3f..b517b98c0 100644 --- a/src/Mesh.cc +++ b/src/Mesh.cc @@ -14,6 +14,7 @@ * limitations under the License. * */ +#include "sdf/parser.hh" #include "sdf/Mesh.hh" using namespace sdf; @@ -176,3 +177,32 @@ void Mesh::SetCenterSubmesh(const bool _center) { this->dataPtr->centerSubmesh = _center; } + +///////////////////////////////////////////////// +sdf::ElementPtr Mesh::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("mesh_shape.sdf", elem); + + // Uri + sdf::ElementPtr uriElem = elem->GetElement("uri"); + uriElem->Set(this->Uri()); + + // Submesh + if (!this->dataPtr->submesh.empty()) + { + sdf::ElementPtr subMeshElem = elem->GetElement("submesh"); + + sdf::ElementPtr subMeshNameElem = subMeshElem->GetElement("name"); + subMeshNameElem->Set(this->dataPtr->submesh); + + sdf::ElementPtr subMeshCenterElem = subMeshElem->GetElement("center"); + subMeshCenterElem->Set(this->dataPtr->centerSubmesh); + } + + // Scale + sdf::ElementPtr scaleElem = elem->GetElement("scale"); + scaleElem->Set(this->Scale()); + + return elem; +} diff --git a/src/Mesh_TEST.cc b/src/Mesh_TEST.cc index 41ecfe2c6..12a448a42 100644 --- a/src/Mesh_TEST.cc +++ b/src/Mesh_TEST.cc @@ -179,3 +179,25 @@ TEST(DOMMesh, Load) EXPECT_NE(std::string::npos, errors[0].Message().find("missing a ")); EXPECT_NE(nullptr, mesh.Element()); } + +///////////////////////////////////////////////// +TEST(DOMMesh, ToElement) +{ + sdf::Mesh mesh; + + mesh.SetUri("mesh-uri"); + mesh.SetScale(ignition::math::Vector3d(1, 2, 3)); + mesh.SetSubmesh("submesh"); + mesh.SetCenterSubmesh(false); + + sdf::ElementPtr elem = mesh.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Mesh mesh2; + mesh2.Load(elem); + + EXPECT_EQ(mesh.Uri(), mesh2.Uri()); + EXPECT_EQ(mesh.Scale(), mesh2.Scale()); + EXPECT_EQ(mesh.Submesh(), mesh2.Submesh()); + EXPECT_EQ(mesh.CenterSubmesh(), mesh2.CenterSubmesh()); +} diff --git a/src/Plane.cc b/src/Plane.cc index a24542080..408f72161 100644 --- a/src/Plane.cc +++ b/src/Plane.cc @@ -16,6 +16,7 @@ */ #include #include +#include "sdf/parser.hh" #include "sdf/Plane.hh" using namespace sdf; @@ -150,3 +151,18 @@ ignition::math::Planed &Plane::Shape() { return this->dataPtr->plane; } + +///////////////////////////////////////////////// +sdf::ElementPtr Plane::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("plane_shape.sdf", elem); + + sdf::ElementPtr normalElem = elem->GetElement("normal"); + normalElem->Set(this->Normal()); + + sdf::ElementPtr sizeElem = elem->GetElement("size"); + sizeElem->Set(this->Size()); + + return elem; +} diff --git a/src/Plane_TEST.cc b/src/Plane_TEST.cc index 97fd5f780..04aa0be11 100644 --- a/src/Plane_TEST.cc +++ b/src/Plane_TEST.cc @@ -167,3 +167,21 @@ TEST(DOMPlane, Shape) plane.Shape().Offset()); EXPECT_EQ(ignition::math::Vector2d(1, 2), plane.Size()); } + +///////////////////////////////////////////////// +TEST(DOMPlane, ToElement) +{ + sdf::Plane plane; + + plane.SetNormal(ignition::math::Vector3d(0, 1, 0)); + plane.SetSize(ignition::math::Vector2d(2, 4)); + + sdf::ElementPtr elem = plane.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Plane plane2; + plane2.Load(elem); + + EXPECT_EQ(plane.Normal(), plane2.Normal()); + EXPECT_EQ(plane.Size(), plane2.Size()); +} diff --git a/src/Sphere.cc b/src/Sphere.cc index e1c8ad3ed..df666c58b 100644 --- a/src/Sphere.cc +++ b/src/Sphere.cc @@ -14,6 +14,7 @@ * limitations under the License. * */ +#include "sdf/parser.hh" #include "sdf/Sphere.hh" using namespace sdf; @@ -111,3 +112,15 @@ sdf::ElementPtr Sphere::Element() const { return this->dataPtr->sdf; } + +///////////////////////////////////////////////// +sdf::ElementPtr Sphere::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("sphere_shape.sdf", elem); + + sdf::ElementPtr radiusElem = elem->GetElement("radius"); + radiusElem->Set(this->Radius()); + + return elem; +} diff --git a/src/Sphere_TEST.cc b/src/Sphere_TEST.cc index 107ccac36..5e8d0407d 100644 --- a/src/Sphere_TEST.cc +++ b/src/Sphere_TEST.cc @@ -133,3 +133,19 @@ TEST(DOMSphere, Shape) sphere.Shape().SetRadius(0.123); EXPECT_DOUBLE_EQ(0.123, sphere.Radius()); } + +///////////////////////////////////////////////// +TEST(DOMSphere, ToElement) +{ + sdf::Sphere sphere; + + sphere.SetRadius(1.2); + + sdf::ElementPtr elem = sphere.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Sphere sphere2; + sphere2.Load(elem); + + EXPECT_DOUBLE_EQ(sphere.Radius(), sphere2.Radius()); +} From 8de1eb6fd49da8434e01fd94af26f8d7c452acd4 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Tue, 7 Dec 2021 17:02:10 -0800 Subject: [PATCH 05/28] Material toelement (#775) * Working on material DOM ToElement Signed-off-by: Nate Koenig * Update material ToElement Signed-off-by: Nate Koenig * Use floats Signed-off-by: Nate Koenig * Fix build Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- include/sdf/Material.hh | 12 ++++- src/Material.cc | 107 +++++++++++++++++++++++++++++++++++- src/Material_TEST.cc | 116 ++++++++++++++++++++++++++++++++++++++++ 3 files changed, 232 insertions(+), 3 deletions(-) diff --git a/include/sdf/Material.hh b/include/sdf/Material.hh index 0e1b3b8f1..68760de4f 100644 --- a/include/sdf/Material.hh +++ b/include/sdf/Material.hh @@ -103,12 +103,15 @@ namespace sdf /// \param[in] _color Emissive color. public: void SetEmissive(const ignition::math::Color &_color); - /// \brief Get render order + /// \brief Get render order for coplanar polygons. The higher value will + /// be rendered on top of the other coplanar polygons. The default value + /// is zero. /// \return Render order public: float RenderOrder() const; - /// \brief Set render order + /// \brief Set render order. /// \param[in] _renderOrder render order + /// \sa float RenderOrder() const public: void SetRenderOrder(const float _renderOrder); /// \brief Get whether dynamic lighting is enabled. The default @@ -190,6 +193,11 @@ namespace sdf /// \paramp[in] _filePath Full path to the file on disk. public: void SetFilePath(const std::string &_filePath); + /// \brief Create and return an SDF element filled with data from this + /// material. + /// \return SDF element pointer with updated material values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/src/Material.cc b/src/Material.cc index d4459801b..5c050c10a 100644 --- a/src/Material.cc +++ b/src/Material.cc @@ -19,9 +19,10 @@ #include #include -#include "sdf/Types.hh" #include "sdf/Material.hh" +#include "sdf/parser.hh" #include "sdf/Pbr.hh" +#include "sdf/Types.hh" #include "Utils.hh" using namespace sdf; @@ -358,3 +359,107 @@ void Material::SetFilePath(const std::string &_filePath) { this->dataPtr->filePath = _filePath; } + +///////////////////////////////////////////////// +sdf::ElementPtr Material::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("material.sdf", elem); + + elem->GetElement("ambient")->Set(this->Ambient()); + elem->GetElement("diffuse")->Set(this->Diffuse()); + elem->GetElement("specular")->Set(this->Specular()); + elem->GetElement("emissive")->Set(this->Emissive()); + elem->GetElement("render_order")->Set(this->RenderOrder()); + elem->GetElement("lighting")->Set(this->Lighting()); + elem->GetElement("double_sided")->Set(this->DoubleSided()); + + // Script, if set + if (!this->ScriptName().empty() && !this->ScriptUri().empty()) + { + sdf::ElementPtr scriptElem = elem->GetElement("script"); + scriptElem->GetElement("uri")->Set(this->ScriptUri()); + scriptElem->GetElement("name")->Set(this->ScriptName()); + } + + // Shader properties + sdf::ElementPtr shaderElem = elem->GetElement("shader"); + switch (this->dataPtr->shader) + { + default: + case ShaderType::PIXEL: + shaderElem->GetAttribute("type")->Set("pixel"); + break; + case ShaderType::VERTEX: + shaderElem->GetAttribute("type")->Set("vertex"); + break; + case ShaderType::NORMAL_MAP_OBJECTSPACE: + shaderElem->GetAttribute("type")->Set("normal_map_object_space"); + break; + case ShaderType::NORMAL_MAP_TANGENTSPACE: + shaderElem->GetAttribute("type")->Set("normal_map_tangent_space"); + break; + } + if (!this->NormalMap().empty()) + shaderElem->GetElement("normal_map")->Set(this->NormalMap()); + + // PBR material + if (this->dataPtr->pbr) + { + const PbrWorkflow *workflow = this->dataPtr->pbr->Workflow( + PbrWorkflowType::METAL); + sdf::ElementPtr pbrElem = elem->GetElement("pbr"); + if (workflow && workflow->Type() == PbrWorkflowType::METAL) + { + sdf::ElementPtr metalElem = pbrElem->GetElement("metal"); + metalElem->GetElement("albedo_map")->Set(workflow->AlbedoMap()); + metalElem->GetElement("roughness_map")->Set(workflow->RoughnessMap()); + metalElem->GetElement("roughness")->Set(workflow->Roughness()); + metalElem->GetElement("metalness_map")->Set(workflow->MetalnessMap()); + metalElem->GetElement("metalness")->Set(workflow->Metalness()); + metalElem->GetElement("ambient_occlusion_map")->Set( + workflow->AmbientOcclusionMap()); + sdf::ElementPtr normalElem = metalElem->GetElement("normal_map"); + if (workflow->NormalMapType() == NormalMapSpace::TANGENT) + normalElem->GetAttribute("type")->Set("tangent"); + else + normalElem->GetAttribute("type")->Set("object"); + normalElem->Set(workflow->NormalMap()); + + metalElem->GetElement("emissive_map")->Set(workflow->EmissiveMap()); + + sdf::ElementPtr lightElem = metalElem->GetElement("light_map"); + lightElem->GetAttribute("uv_set")->Set(workflow->LightMapTexCoordSet()); + lightElem->Set(workflow->LightMap()); + } + + workflow = this->dataPtr->pbr->Workflow(PbrWorkflowType::SPECULAR); + if (workflow && workflow->Type() == PbrWorkflowType::SPECULAR) + { + sdf::ElementPtr specularElem = pbrElem->GetElement("specular"); + specularElem->GetElement("albedo_map")->Set(workflow->AlbedoMap()); + specularElem->GetElement("specular_map")->Set(workflow->SpecularMap()); + specularElem->GetElement("environment_map")->Set( + workflow->EnvironmentMap()); + specularElem->GetElement("ambient_occlusion_map")->Set( + workflow->AmbientOcclusionMap()); + specularElem->GetElement("emissive_map")->Set(workflow->EmissiveMap()); + specularElem->GetElement("glossiness_map")->Set( + workflow->GlossinessMap()); + specularElem->GetElement("glossiness")->Set(workflow->Glossiness()); + + sdf::ElementPtr normalElem = specularElem->GetElement("normal_map"); + if (workflow->NormalMapType() == NormalMapSpace::TANGENT) + normalElem->GetAttribute("type")->Set("tangent"); + else + normalElem->GetAttribute("type")->Set("object"); + normalElem->Set(workflow->NormalMap()); + + sdf::ElementPtr lightElem = specularElem->GetElement("light_map"); + lightElem->GetAttribute("uv_set")->Set(workflow->LightMapTexCoordSet()); + lightElem->Set(workflow->LightMap()); + } + } + + return elem; +} diff --git a/src/Material_TEST.cc b/src/Material_TEST.cc index 115a56849..c67c4a81a 100644 --- a/src/Material_TEST.cc +++ b/src/Material_TEST.cc @@ -289,3 +289,119 @@ TEST(DOMMaterial, InvalidSdf) sdf::Errors errors = material.Load(elem); EXPECT_EQ(sdf::ErrorCode::ELEMENT_INCORRECT_TYPE, errors[0].Code()); } + +///////////////////////////////////////////////// +TEST(DOMMaterial, ToElement) +{ + sdf::Material material; + + material.SetAmbient(ignition::math::Color(0.1f, 0.2f, 0.3f, 1.0f)); + material.SetDiffuse(ignition::math::Color(0.4f, 0.5f, 0.6f, 0.5f)); + material.SetSpecular(ignition::math::Color(0.6f, 0.4f, 0.8f, 0.8f)); + material.SetEmissive(ignition::math::Color(0.2f, 0.7f, 0.9f, 0.1f)); + + material.SetRenderOrder(0.5); + material.SetLighting(false); + material.SetDoubleSided(true); + material.SetScriptUri("my-uri"); + material.SetScriptName("my-script-name"); + material.SetShader(sdf::ShaderType::VERTEX); + material.SetNormalMap("my-normal-map"); + + sdf::PbrWorkflow workflow; + workflow.SetAlbedoMap("albedo"); + workflow.SetNormalMap("normal"); + workflow.SetEnvironmentMap("env"); + workflow.SetAmbientOcclusionMap("ambient"); + workflow.SetRoughnessMap("rough"); + workflow.SetMetalnessMap("metalness"); + workflow.SetEmissiveMap("emissive"); + workflow.SetGlossinessMap("gloss"); + workflow.SetSpecularMap("gloss"); + workflow.SetLightMap("light", 1u); + workflow.SetMetalness(1.0); + workflow.SetRoughness(0.1); + + // Testing using METAL workflow + { + sdf::Pbr pbr; + workflow.SetType(sdf::PbrWorkflowType::METAL); + pbr.SetWorkflow(sdf::PbrWorkflowType::METAL, workflow); + material.SetPbrMaterial(pbr); + + sdf::ElementPtr elem = material.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Material material2; + material2.Load(elem); + + EXPECT_EQ(material.Ambient(), material2.Ambient()); + EXPECT_EQ(material.Diffuse(), material2.Diffuse()); + EXPECT_EQ(material.Specular(), material2.Specular()); + EXPECT_EQ(material.Emissive(), material2.Emissive()); + EXPECT_DOUBLE_EQ(material.RenderOrder(), material2.RenderOrder()); + EXPECT_EQ(material.Lighting(), material2.Lighting()); + EXPECT_EQ(material.DoubleSided(), material2.DoubleSided()); + EXPECT_EQ(material.ScriptUri(), material2.ScriptUri()); + EXPECT_EQ(material.ScriptName(), material2.ScriptName()); + EXPECT_EQ(material.Shader(), material2.Shader()); + EXPECT_EQ(material.NormalMap(), material2.NormalMap()); + + const sdf::Pbr *pbr2 = material2.PbrMaterial(); + const sdf::PbrWorkflow *flow1 = pbr.Workflow(sdf::PbrWorkflowType::METAL); + const sdf::PbrWorkflow *flow2 = pbr2->Workflow(sdf::PbrWorkflowType::METAL); + EXPECT_EQ(flow1->AlbedoMap(), flow2->AlbedoMap()); + EXPECT_EQ(flow1->NormalMap(), flow2->NormalMap()); + EXPECT_EQ(flow1->AmbientOcclusionMap(), + flow2->AmbientOcclusionMap()); + EXPECT_EQ(flow1->RoughnessMap(), flow2->RoughnessMap()); + EXPECT_EQ(flow1->MetalnessMap(), flow2->MetalnessMap()); + EXPECT_EQ(flow1->EmissiveMap(), flow2->EmissiveMap()); + EXPECT_EQ(flow1->LightMap(), flow2->LightMap()); + EXPECT_DOUBLE_EQ(flow1->Metalness(), flow2->Metalness()); + EXPECT_DOUBLE_EQ(flow1->Roughness(), flow2->Roughness()); + EXPECT_EQ(flow1->Type(), flow2->Type()); + } + + // Testing using SPECULAR workflow + { + sdf::Pbr pbr; + workflow.SetType(sdf::PbrWorkflowType::SPECULAR); + pbr.SetWorkflow(sdf::PbrWorkflowType::SPECULAR, workflow); + material.SetPbrMaterial(pbr); + + sdf::ElementPtr elem = material.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Material material2; + material2.Load(elem); + + EXPECT_EQ(material.Ambient(), material2.Ambient()); + EXPECT_EQ(material.Diffuse(), material2.Diffuse()); + EXPECT_EQ(material.Specular(), material2.Specular()); + EXPECT_EQ(material.Emissive(), material2.Emissive()); + EXPECT_DOUBLE_EQ(material.RenderOrder(), material2.RenderOrder()); + EXPECT_EQ(material.Lighting(), material2.Lighting()); + EXPECT_EQ(material.DoubleSided(), material2.DoubleSided()); + EXPECT_EQ(material.ScriptUri(), material2.ScriptUri()); + EXPECT_EQ(material.ScriptName(), material2.ScriptName()); + EXPECT_EQ(material.Shader(), material2.Shader()); + EXPECT_EQ(material.NormalMap(), material2.NormalMap()); + + const sdf::Pbr *pbr2 = material2.PbrMaterial(); + const sdf::PbrWorkflow *flow1 = + pbr.Workflow(sdf::PbrWorkflowType::SPECULAR); + const sdf::PbrWorkflow *flow2 = + pbr2->Workflow(sdf::PbrWorkflowType::SPECULAR); + EXPECT_EQ(flow1->AlbedoMap(), flow2->AlbedoMap()); + EXPECT_EQ(flow1->NormalMap(), flow2->NormalMap()); + EXPECT_EQ(flow1->EnvironmentMap(), flow2->EnvironmentMap()); + EXPECT_EQ(flow1->AmbientOcclusionMap(), + flow2->AmbientOcclusionMap()); + EXPECT_EQ(flow1->EmissiveMap(), flow2->EmissiveMap()); + EXPECT_EQ(flow1->GlossinessMap(), flow2->GlossinessMap()); + EXPECT_EQ(flow1->SpecularMap(), flow2->SpecularMap()); + EXPECT_EQ(flow1->LightMap(), flow2->LightMap()); + EXPECT_EQ(flow1->Type(), flow2->Type()); + } +} From b28967c31abe2ed9570a93947a49f0bab952b976 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Tue, 7 Dec 2021 20:42:36 -0800 Subject: [PATCH 06/28] Added Geometry ToElement function (#776) Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig Co-authored-by: Louise Poubel --- include/sdf/Geometry.hh | 5 + src/Geometry.cc | 42 ++++++++ src/Geometry_TEST.cc | 205 ++++++++++++++++++++++++++++++++++++++++ 3 files changed, 252 insertions(+) diff --git a/include/sdf/Geometry.hh b/include/sdf/Geometry.hh index 6223a1737..b3d0a3b02 100644 --- a/include/sdf/Geometry.hh +++ b/include/sdf/Geometry.hh @@ -189,6 +189,11 @@ namespace sdf /// not been called. public: sdf::ElementPtr Element() const; + /// \brief Create and return an SDF element filled with data from this + /// geometry. + /// \return SDF element pointer with updated geometry values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/src/Geometry.cc b/src/Geometry.cc index 59cacd0f0..d2c933356 100644 --- a/src/Geometry.cc +++ b/src/Geometry.cc @@ -24,6 +24,7 @@ #include "sdf/Ellipsoid.hh" #include "sdf/Heightmap.hh" #include "sdf/Mesh.hh" +#include "sdf/parser.hh" #include "sdf/Plane.hh" #include "sdf/Sphere.hh" @@ -270,3 +271,44 @@ sdf::ElementPtr Geometry::Element() const { return this->dataPtr->sdf; } + +///////////////////////////////////////////////// +sdf::ElementPtr Geometry::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("geometry.sdf", elem); + + switch (this->dataPtr->type) + { + case GeometryType::BOX: + elem->InsertElement(this->dataPtr->box->ToElement()); + break; + case GeometryType::CYLINDER: + elem->InsertElement(this->dataPtr->cylinder->ToElement()); + break; + case GeometryType::PLANE: + elem->InsertElement(this->dataPtr->plane->ToElement()); + break; + case GeometryType::SPHERE: + elem->InsertElement(this->dataPtr->sphere->ToElement()); + break; + case GeometryType::MESH: + elem->InsertElement(this->dataPtr->mesh->ToElement()); + break; + case GeometryType::HEIGHTMAP: + elem->InsertElement(this->dataPtr->heightmap->ToElement()); + break; + case GeometryType::CAPSULE: + elem->InsertElement(this->dataPtr->capsule->ToElement()); + break; + case GeometryType::ELLIPSOID: + elem->InsertElement(this->dataPtr->ellipsoid->ToElement()); + break; + case GeometryType::EMPTY: + default: + elem->AddElement("empty"); + break; + } + + return elem; +} diff --git a/src/Geometry_TEST.cc b/src/Geometry_TEST.cc index 6aaab1a2a..0d3809a01 100644 --- a/src/Geometry_TEST.cc +++ b/src/Geometry_TEST.cc @@ -21,6 +21,7 @@ #include "sdf/Cylinder.hh" #include "sdf/Ellipsoid.hh" #include "sdf/Geometry.hh" +#include "sdf/Heightmap.hh" #include "sdf/Mesh.hh" #include "sdf/Plane.hh" #include "sdf/Sphere.hh" @@ -259,3 +260,207 @@ TEST(DOMGeometry, Plane) EXPECT_EQ(ignition::math::Vector3d::UnitX, geom.PlaneShape()->Normal()); EXPECT_EQ(ignition::math::Vector2d(9, 8), geom.PlaneShape()->Size()); } + +///////////////////////////////////////////////// +TEST(DOMGeometry, ToElement) +{ + // Box + { + sdf::Geometry geom; + + geom.SetType(sdf::GeometryType::BOX); + sdf::Box box; + geom.SetBoxShape(box); + + sdf::ElementPtr elem = geom.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Geometry geom2; + geom2.Load(elem); + + EXPECT_EQ(geom.Type(), geom2.Type()); + EXPECT_NE(nullptr, geom2.BoxShape()); + EXPECT_EQ(nullptr, geom2.CapsuleShape()); + EXPECT_EQ(nullptr, geom2.CylinderShape()); + EXPECT_EQ(nullptr, geom2.EllipsoidShape()); + EXPECT_EQ(nullptr, geom2.SphereShape()); + EXPECT_EQ(nullptr, geom2.PlaneShape()); + EXPECT_EQ(nullptr, geom2.MeshShape()); + EXPECT_EQ(nullptr, geom2.HeightmapShape()); + } + + // Capsule + { + sdf::Geometry geom; + + geom.SetType(sdf::GeometryType::CAPSULE); + sdf::Capsule capsule; + geom.SetCapsuleShape(capsule); + + sdf::ElementPtr elem = geom.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Geometry geom2; + geom2.Load(elem); + + EXPECT_EQ(geom.Type(), geom2.Type()); + EXPECT_EQ(nullptr, geom2.BoxShape()); + EXPECT_NE(nullptr, geom2.CapsuleShape()); + EXPECT_EQ(nullptr, geom2.CylinderShape()); + EXPECT_EQ(nullptr, geom2.EllipsoidShape()); + EXPECT_EQ(nullptr, geom2.SphereShape()); + EXPECT_EQ(nullptr, geom2.PlaneShape()); + EXPECT_EQ(nullptr, geom2.MeshShape()); + EXPECT_EQ(nullptr, geom2.HeightmapShape()); + } + + // Cylinder + { + sdf::Geometry geom; + + geom.SetType(sdf::GeometryType::CYLINDER); + sdf::Cylinder cylinder; + geom.SetCylinderShape(cylinder); + + sdf::ElementPtr elem = geom.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Geometry geom2; + geom2.Load(elem); + + EXPECT_EQ(geom.Type(), geom2.Type()); + EXPECT_EQ(nullptr, geom2.BoxShape()); + EXPECT_EQ(nullptr, geom2.CapsuleShape()); + EXPECT_NE(nullptr, geom2.CylinderShape()); + EXPECT_EQ(nullptr, geom2.EllipsoidShape()); + EXPECT_EQ(nullptr, geom2.SphereShape()); + EXPECT_EQ(nullptr, geom2.PlaneShape()); + EXPECT_EQ(nullptr, geom2.MeshShape()); + EXPECT_EQ(nullptr, geom2.HeightmapShape()); + } + + // Ellipsoid + { + sdf::Geometry geom; + + geom.SetType(sdf::GeometryType::ELLIPSOID); + sdf::Ellipsoid ellipsoid; + geom.SetEllipsoidShape(ellipsoid); + + sdf::ElementPtr elem = geom.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Geometry geom2; + geom2.Load(elem); + + EXPECT_EQ(geom.Type(), geom2.Type()); + EXPECT_EQ(nullptr, geom2.BoxShape()); + EXPECT_EQ(nullptr, geom2.CapsuleShape()); + EXPECT_EQ(nullptr, geom2.CylinderShape()); + EXPECT_NE(nullptr, geom2.EllipsoidShape()); + EXPECT_EQ(nullptr, geom2.SphereShape()); + EXPECT_EQ(nullptr, geom2.PlaneShape()); + EXPECT_EQ(nullptr, geom2.MeshShape()); + EXPECT_EQ(nullptr, geom2.HeightmapShape()); + } + + // Sphere + { + sdf::Geometry geom; + + geom.SetType(sdf::GeometryType::SPHERE); + sdf::Sphere sphere; + geom.SetSphereShape(sphere); + + sdf::ElementPtr elem = geom.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Geometry geom2; + geom2.Load(elem); + + EXPECT_EQ(geom.Type(), geom2.Type()); + EXPECT_EQ(nullptr, geom2.BoxShape()); + EXPECT_EQ(nullptr, geom2.CapsuleShape()); + EXPECT_EQ(nullptr, geom2.CylinderShape()); + EXPECT_EQ(nullptr, geom2.EllipsoidShape()); + EXPECT_NE(nullptr, geom2.SphereShape()); + EXPECT_EQ(nullptr, geom2.PlaneShape()); + EXPECT_EQ(nullptr, geom2.MeshShape()); + EXPECT_EQ(nullptr, geom2.HeightmapShape()); + } + + // Plane + { + sdf::Geometry geom; + + geom.SetType(sdf::GeometryType::PLANE); + sdf::Plane plane; + geom.SetPlaneShape(plane); + + sdf::ElementPtr elem = geom.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Geometry geom2; + geom2.Load(elem); + + EXPECT_EQ(geom.Type(), geom2.Type()); + EXPECT_EQ(nullptr, geom2.BoxShape()); + EXPECT_EQ(nullptr, geom2.CapsuleShape()); + EXPECT_EQ(nullptr, geom2.CylinderShape()); + EXPECT_EQ(nullptr, geom2.EllipsoidShape()); + EXPECT_EQ(nullptr, geom2.SphereShape()); + EXPECT_NE(nullptr, geom2.PlaneShape()); + EXPECT_EQ(nullptr, geom2.MeshShape()); + EXPECT_EQ(nullptr, geom2.HeightmapShape()); + } + + // Mesh + { + sdf::Geometry geom; + + geom.SetType(sdf::GeometryType::MESH); + sdf::Mesh mesh; + geom.SetMeshShape(mesh); + + sdf::ElementPtr elem = geom.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Geometry geom2; + geom2.Load(elem); + + EXPECT_EQ(geom.Type(), geom2.Type()); + EXPECT_EQ(nullptr, geom2.BoxShape()); + EXPECT_EQ(nullptr, geom2.CapsuleShape()); + EXPECT_EQ(nullptr, geom2.CylinderShape()); + EXPECT_EQ(nullptr, geom2.EllipsoidShape()); + EXPECT_EQ(nullptr, geom2.SphereShape()); + EXPECT_EQ(nullptr, geom2.PlaneShape()); + EXPECT_NE(nullptr, geom2.MeshShape()); + EXPECT_EQ(nullptr, geom2.HeightmapShape()); + } + + // Heightmap + { + sdf::Geometry geom; + + geom.SetType(sdf::GeometryType::HEIGHTMAP); + sdf::Heightmap heightmap; + geom.SetHeightmapShape(heightmap); + + sdf::ElementPtr elem = geom.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Geometry geom2; + geom2.Load(elem); + + EXPECT_EQ(geom.Type(), geom2.Type()); + EXPECT_EQ(nullptr, geom2.BoxShape()); + EXPECT_EQ(nullptr, geom2.CapsuleShape()); + EXPECT_EQ(nullptr, geom2.CylinderShape()); + EXPECT_EQ(nullptr, geom2.EllipsoidShape()); + EXPECT_EQ(nullptr, geom2.SphereShape()); + EXPECT_EQ(nullptr, geom2.PlaneShape()); + EXPECT_EQ(nullptr, geom2.MeshShape()); + EXPECT_NE(nullptr, geom2.HeightmapShape()); + } +} From e8a73e43eb64a2f3542de797bfadcae370e76f7e Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Thu, 9 Dec 2021 12:08:09 -0800 Subject: [PATCH 07/28] Added ToElement conversion for Collision, Surface, and Visual (#777) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Added ToElement conversion for Collision, Surface, and Visual Signed-off-by: Nate Koenig * Update src/Visual_TEST.cc Co-authored-by: Alejandro Hernández Cordero Co-authored-by: Nate Koenig Co-authored-by: Alejandro Hernández Cordero --- include/sdf/Collision.hh | 5 +++++ include/sdf/Surface.hh | 5 +++++ include/sdf/Visual.hh | 5 +++++ src/Collision.cc | 27 +++++++++++++++++++++++++++ src/Collision_TEST.cc | 32 ++++++++++++++++++++++++++++++++ src/Surface.cc | 16 ++++++++++++++++ src/Visual.cc | 40 +++++++++++++++++++++++++++++++++++++--- src/Visual_TEST.cc | 35 +++++++++++++++++++++++++++++++++++ 8 files changed, 162 insertions(+), 3 deletions(-) diff --git a/include/sdf/Collision.hh b/include/sdf/Collision.hh index 342985ff7..5a12eede2 100644 --- a/include/sdf/Collision.hh +++ b/include/sdf/Collision.hh @@ -115,6 +115,11 @@ namespace sdf /// not been called. public: sdf::ElementPtr Element() const; + /// \brief Create and return an SDF element filled with data from this + /// collision. + /// \return SDF element pointer with updated collision values. + public: sdf::ElementPtr ToElement() const; + /// \brief Give the name of the xml parent of this object, to be used /// for resolving poses. This is private and is intended to be called by /// Link::SetPoseRelativeToGraph. diff --git a/include/sdf/Surface.hh b/include/sdf/Surface.hh index dd39aea94..6312ffbd3 100644 --- a/include/sdf/Surface.hh +++ b/include/sdf/Surface.hh @@ -87,6 +87,11 @@ namespace sdf /// \param[in] _cont The contact object. public: void SetContact(const sdf::Contact &_contact); + /// \brief Create and return an SDF element filled with data from this + /// surface. + /// \return SDF element pointer with updated surface values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Visual.hh b/include/sdf/Visual.hh index fce9e6de2..a3f00fb58 100644 --- a/include/sdf/Visual.hh +++ b/include/sdf/Visual.hh @@ -160,6 +160,11 @@ namespace sdf /// \param[in] _laserRetro The lidar reflective intensity. public: void SetLaserRetro(double _laserRetro); + /// \brief Create and return an SDF element filled with data from this + /// visual. + /// \return SDF element pointer with updated visual values. + public: sdf::ElementPtr ToElement() const; + /// \brief Give the name of the xml parent of this object, to be used /// for resolving poses. This is private and is intended to be called by /// Link::SetPoseRelativeToGraph. diff --git a/src/Collision.cc b/src/Collision.cc index da67eb5e4..cbeabaf9b 100644 --- a/src/Collision.cc +++ b/src/Collision.cc @@ -20,6 +20,7 @@ #include "sdf/Collision.hh" #include "sdf/Error.hh" #include "sdf/Geometry.hh" +#include "sdf/parser.hh" #include "sdf/Surface.hh" #include "sdf/Types.hh" #include "FrameSemantics.hh" @@ -197,3 +198,29 @@ sdf::ElementPtr Collision::Element() const { return this->dataPtr->sdf; } + +///////////////////////////////////////////////// +sdf::ElementPtr Collision::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("collision.sdf", elem); + + elem->GetAttribute("name")->Set(this->Name()); + + // Set pose + sdf::ElementPtr poseElem = elem->GetElement("pose"); + if (!this->dataPtr->poseRelativeTo.empty()) + { + poseElem->GetAttribute("relative_to")->Set( + this->dataPtr->poseRelativeTo); + } + poseElem->Set(this->RawPose()); + + // Set the geometry + elem->InsertElement(this->dataPtr->geom.ToElement()); + + // Set the surface + elem->InsertElement(this->dataPtr->surface.ToElement()); + + return elem; +} diff --git a/src/Collision_TEST.cc b/src/Collision_TEST.cc index 33b49267d..bdf15ff18 100644 --- a/src/Collision_TEST.cc +++ b/src/Collision_TEST.cc @@ -168,3 +168,35 @@ TEST(DOMcollision, SetSurface) ASSERT_NE(nullptr, collision.Surface()->Contact()); EXPECT_EQ(collision.Surface()->Contact()->CollideBitmask(), 0x2); } + +///////////////////////////////////////////////// +TEST(DOMCollision, ToElement) +{ + sdf::Collision collision; + + collision.SetName("my-collision"); + + sdf::Geometry geom; + collision.SetGeom(geom); + collision.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3)); + + sdf::Surface surface; + sdf::Contact contact; + contact.SetCollideBitmask(123u); + surface.SetContact(contact); + collision.SetSurface(surface); + + sdf::ElementPtr elem = collision.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Collision collision2; + collision2.Load(elem); + const sdf::Surface *surface2 = collision2.Surface(); + + EXPECT_EQ(collision.Name(), collision2.Name()); + EXPECT_EQ(collision.RawPose(), collision2.RawPose()); + EXPECT_NE(nullptr, collision2.Geom()); + ASSERT_NE(nullptr, surface2); + ASSERT_NE(nullptr, surface2->Contact()); + EXPECT_EQ(123u, surface2->Contact()->CollideBitmask()); +} diff --git a/src/Surface.cc b/src/Surface.cc index 7e7283906..3977cf3fa 100644 --- a/src/Surface.cc +++ b/src/Surface.cc @@ -16,6 +16,7 @@ */ #include "sdf/Element.hh" +#include "sdf/parser.hh" #include "sdf/Surface.hh" #include "sdf/Types.hh" #include "sdf/sdf_config.h" @@ -79,6 +80,7 @@ Errors Contact::Load(ElementPtr _sdf) static_cast(_sdf->Get("collide_bitmask")); } + // \todo(nkoenig) Parse the remaining collide properties. return errors; } ///////////////////////////////////////////////// @@ -137,6 +139,7 @@ Errors Surface::Load(ElementPtr _sdf) errors.insert(errors.end(), err.begin(), err.end()); } + // \todo(nkoenig) Parse the remaining surface properties. return errors; } ///////////////////////////////////////////////// @@ -156,3 +159,16 @@ void Surface::SetContact(const sdf::Contact &_contact) { this->dataPtr->contact = _contact; } + +///////////////////////////////////////////////// +sdf::ElementPtr Surface::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("surface.sdf", elem); + + sdf::ElementPtr contactElem = elem->GetElement("contact"); + contactElem->GetElement("collide_bitmask")->Set( + this->dataPtr->contact.CollideBitmask()); + + return elem; +} diff --git a/src/Visual.cc b/src/Visual.cc index 6b6fe5e22..4421f66c8 100644 --- a/src/Visual.cc +++ b/src/Visual.cc @@ -17,12 +17,13 @@ #include #include #include +#include "FrameSemantics.hh" +#include "ScopedGraph.hh" #include "sdf/Error.hh" +#include "sdf/Geometry.hh" +#include "sdf/parser.hh" #include "sdf/Types.hh" #include "sdf/Visual.hh" -#include "sdf/Geometry.hh" -#include "FrameSemantics.hh" -#include "ScopedGraph.hh" #include "Utils.hh" using namespace sdf; @@ -300,3 +301,36 @@ void Visual::SetPoseRelativeToGraph( { this->dataPtr->poseRelativeToGraph = _graph; } + +///////////////////////////////////////////////// +sdf::ElementPtr Visual::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("visual.sdf", elem); + + elem->GetAttribute("name")->Set(this->Name()); + + // Set pose + sdf::ElementPtr poseElem = elem->GetElement("pose"); + if (!this->dataPtr->poseRelativeTo.empty()) + { + poseElem->GetAttribute("relative_to")->Set( + this->dataPtr->poseRelativeTo); + } + poseElem->Set(this->RawPose()); + + // Set the geometry + elem->InsertElement(this->dataPtr->geom.ToElement()); + + elem->GetElement("cast_shadows")->Set(this->CastShadows()); + elem->GetElement("laser_retro")->Set(this->LaserRetro()); + elem->GetElement("transparency")->Set(this->Transparency()); + elem->GetElement("visibility_flags")->Set(this->VisibilityFlags()); + + if (this->dataPtr->material) + { + elem->InsertElement(this->dataPtr->material->ToElement()); + } + + return elem; +} diff --git a/src/Visual_TEST.cc b/src/Visual_TEST.cc index 836abf3a8..6119416b7 100644 --- a/src/Visual_TEST.cc +++ b/src/Visual_TEST.cc @@ -285,3 +285,38 @@ TEST(DOMVisual, SetLaserRetro) EXPECT_TRUE(visual.HasLaserRetro()); EXPECT_DOUBLE_EQ(150, visual.LaserRetro()); } + +///////////////////////////////////////////////// +TEST(DOMVisual, ToElement) +{ + sdf::Visual visual; + visual.SetName("my-visual"); + visual.SetCastShadows(true); + visual.SetTransparency(0.2f); + visual.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3)); + visual.SetVisibilityFlags(1234u); + visual.SetHasLaserRetro(true); + visual.SetLaserRetro(1.2); + + sdf::Geometry geom; + visual.SetGeom(geom); + + sdf::Material mat; + visual.SetMaterial(mat); + + sdf::ElementPtr elem = visual.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Visual visual2; + visual2.Load(elem); + + EXPECT_EQ(visual.Name(), visual2.Name()); + EXPECT_EQ(visual.CastShadows(), visual2.CastShadows()); + EXPECT_DOUBLE_EQ(visual.Transparency(), visual2.Transparency()); + EXPECT_EQ(visual.RawPose(), visual2.RawPose()); + EXPECT_EQ(visual.VisibilityFlags(), visual2.VisibilityFlags()); + EXPECT_EQ(visual.HasLaserRetro(), visual2.HasLaserRetro()); + EXPECT_DOUBLE_EQ(visual.LaserRetro(), visual2.LaserRetro()); + EXPECT_NE(nullptr, visual2.Geom()); + EXPECT_NE(nullptr, visual2.Material()); +} From 93c045cda0b167ff226ec5940740ccb415225f5e Mon Sep 17 00:00:00 2001 From: Jenn Nguyen Date: Thu, 9 Dec 2021 14:16:10 -0800 Subject: [PATCH 08/28] PrintConfig option to preserve includes when converting to string (#749) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Jenn Nguyen Co-authored-by: Marco A. Gutiérrez Co-authored-by: Addisu Z. Taddese --- include/sdf/PrintConfig.hh | 31 +++-- src/CMakeLists.txt | 1 + src/Element.cc | 19 +-- src/PrintConfig.cc | 15 +- src/PrintConfig_TEST.cc | 32 +++++ src/cmd/cmdsdformat.rb.in | 33 ++++- src/ign.cc | 30 ++++ test/integration/CMakeLists.txt | 1 + test/integration/interface_api.cc | 35 +++++ test/integration/print_config.cc | 223 ++++++++++++++++++++++++++++++ 10 files changed, 393 insertions(+), 27 deletions(-) create mode 100644 src/PrintConfig_TEST.cc create mode 100644 test/integration/print_config.cc diff --git a/include/sdf/PrintConfig.hh b/include/sdf/PrintConfig.hh index d9d3d507c..2e3b700de 100644 --- a/include/sdf/PrintConfig.hh +++ b/include/sdf/PrintConfig.hh @@ -24,20 +24,27 @@ namespace sdf { -inline namespace SDF_VERSION_NAMESPACE -{ + inline namespace SDF_VERSION_NAMESPACE { -/// This class contains configuration options for printing elements. -class SDFORMAT_VISIBLE PrintConfig -{ - /// \brief Default constructor. - public: PrintConfig(); + /// This class contains configuration options for printing elements. + class SDFORMAT_VISIBLE PrintConfig + { + /// \brief Default constructor. + public: PrintConfig(); - /// \brief Private data pointer. - IGN_UTILS_IMPL_PTR(dataPtr) -}; + /// \brief Set print config to preserve tags. + /// \param[in] _preserve True to preserve tags. + /// False to expand included model. + public: void SetPreserveIncludes(bool _preserve); -} -} + /// \brief Check if tags are to be preserved or expanded. + /// \return True if tags are preserved. + /// False if they are to be expanded. + public: bool PreserveIncludes() const; + /// \brief Private data pointer. + IGN_UTILS_IMPL_PTR(dataPtr) + }; + } +} #endif diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 1e3c67eb2..a36fe8eda 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -134,6 +134,7 @@ if (BUILD_SDF_TEST) ParticleEmitter_TEST.cc Pbr_TEST.cc Physics_TEST.cc + PrintConfig_TEST.cc Plane_TEST.cc Root_TEST.cc Scene_TEST.cc diff --git a/src/Element.cc b/src/Element.cc index 091c7df24..d9e710868 100644 --- a/src/Element.cc +++ b/src/Element.cc @@ -505,7 +505,11 @@ void Element::PrintValuesImpl(const std::string &_prefix, const PrintConfig &_config, std::ostringstream &_out) const { - if (this->GetExplicitlySetInFile() || _includeDefaultElements) + if (_config.PreserveIncludes() && this->GetIncludeElement() != nullptr) + { + _out << this->GetIncludeElement()->ToString(_prefix, _config); + } + else if (this->GetExplicitlySetInFile() || _includeDefaultElements) { _out << _prefix << "<" << this->dataPtr->name; @@ -533,14 +537,11 @@ void Element::PrintValuesImpl(const std::string &_prefix, for (eiter = this->dataPtr->elements.begin(); eiter != this->dataPtr->elements.end(); ++eiter) { - if ((*eiter)->GetExplicitlySetInFile() || _includeDefaultElements) - { - (*eiter)->ToString(_prefix + " ", - _includeDefaultElements, - _includeDefaultAttributes, - _config, - _out); - } + (*eiter)->ToString(_prefix + " ", + _includeDefaultElements, + _includeDefaultAttributes, + _config, + _out); } _out << _prefix << "dataPtr->name << ">\n"; } diff --git a/src/PrintConfig.cc b/src/PrintConfig.cc index fb9f41999..3770f5007 100644 --- a/src/PrintConfig.cc +++ b/src/PrintConfig.cc @@ -24,7 +24,8 @@ inline namespace SDF_VERSION_NAMESPACE ///////////////////////////////////////////////// class PrintConfig::Implementation { - + /// \brief True to preserve tags, false to expand. + public: bool preserveIncludes = false; }; ///////////////////////////////////////////////// @@ -33,5 +34,17 @@ PrintConfig::PrintConfig() { } +///////////////////////////////////////////////// +void PrintConfig::SetPreserveIncludes(bool _preserve) +{ + this->dataPtr->preserveIncludes = _preserve; +} + +///////////////////////////////////////////////// +bool PrintConfig::PreserveIncludes() const +{ + return this->dataPtr->preserveIncludes; +} + } } diff --git a/src/PrintConfig_TEST.cc b/src/PrintConfig_TEST.cc new file mode 100644 index 000000000..ff473bf5d --- /dev/null +++ b/src/PrintConfig_TEST.cc @@ -0,0 +1,32 @@ +/* + * Copyright 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include + +#include "sdf/PrintConfig.hh" +#include "test_config.h" + +///////////////////////////////////////////////// +TEST(PrintConfig, PreserveIncludes) +{ + sdf::PrintConfig config; + EXPECT_FALSE(config.PreserveIncludes()); + config.SetPreserveIncludes(true); + EXPECT_TRUE(config.PreserveIncludes()); + config.SetPreserveIncludes(false); + EXPECT_FALSE(config.PreserveIncludes()); +} diff --git a/src/cmd/cmdsdformat.rb.in b/src/cmd/cmdsdformat.rb.in index 52130611d..9d4d757c4 100644 --- a/src/cmd/cmdsdformat.rb.in +++ b/src/cmd/cmdsdformat.rb.in @@ -43,6 +43,7 @@ COMMANDS = { 'sdf' => " -g [ --graph ] arg Print the PoseRelativeTo or FrameAttachedTo graph. (WARNING: This is for advanced\n" + " use only and the output may change without any promise of stability)\n" + " -p [ --print ] arg Print converted arg.\n" + + " -i [ --preserve-includes ] Preserve included tags when printing converted arg (does not preserve merge-includes).\n" + COMMON_OPTIONS } @@ -75,9 +76,11 @@ class Cmd opts.on('-d', '--describe [VERSION]', 'Print the aggregated SDFormat spec description. Default version (@SDF_PROTOCOL_VERSION@)') do |v| options['describe'] = v end - opts.on('-p arg', '--print arg', String, - 'Print converted arg') do |arg| - options['print'] = arg + opts.on('-p', '--print', 'Print converted arg') do + options['print'] = 1 + end + opts.on('-i', '--preserve-includes', 'Preserve included tags when printing converted arg (does not preserve merge-includes)') do + options['preserve_includes'] = 1 end opts.on('-g arg', '--graph type', String, 'Print PoseRelativeTo or FrameAttachedTo graph') do |graph_type| @@ -101,6 +104,21 @@ class Cmd options['command'] = ARGV[0] + if options['preserve_includes'] and not options['print'] + puts usage + exit(-1) + end + + if options['print'] + filename = args.pop + if filename + options['print'] = filename + else + puts usage + exit(-1) + end + end + options end @@ -160,8 +178,13 @@ class Cmd Importer.extern 'int cmdDescribe(const char *)' exit(Importer.cmdDescribe(options['describe'])) elsif options.key?('print') - Importer.extern 'int cmdPrint(const char *)' - exit(Importer.cmdPrint(File.expand_path(options['print']))) + if options['preserve_includes'] + Importer.extern 'int cmdPrintPreserveIncludes(const char *)' + exit(Importer.cmdPrintPreserveIncludes(File.expand_path(options['print']))) + else + Importer.extern 'int cmdPrint(const char *)' + exit(Importer.cmdPrint(File.expand_path(options['print']))) + end elsif options.key?('graph') Importer.extern 'int cmdGraph(const char *, const char *)' exit(Importer.cmdGraph(options['graph'][:type], File.expand_path(ARGV[1]))) diff --git a/src/ign.cc b/src/ign.cc index e046d6fc1..16cdb0d24 100644 --- a/src/ign.cc +++ b/src/ign.cc @@ -158,6 +158,36 @@ extern "C" SDFORMAT_VISIBLE int cmdPrint(const char *_path) return 0; } +////////////////////////////////////////////////// +extern "C" SDFORMAT_VISIBLE int cmdPrintPreserveIncludes(const char *_path) +{ + if (!sdf::filesystem::exists(_path)) + { + std::cerr << "Error: File [" << _path << "] does not exist.\n"; + return -1; + } + + sdf::SDFPtr sdf(new sdf::SDF()); + + if (!sdf::init(sdf)) + { + std::cerr << "Error: SDF schema initialization failed.\n"; + return -1; + } + + if (!sdf::readFile(_path, sdf)) + { + std::cerr << "Error: SDF parsing the xml failed.\n"; + return -1; + } + + sdf::PrintConfig config; + config.SetPreserveIncludes(true); + sdf->PrintValues(config); + + return 0; +} + ////////////////////////////////////////////////// // cppcheck-suppress unusedFunction extern "C" SDFORMAT_VISIBLE int cmdGraph( diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index bc2fb4481..43d786c6e 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -40,6 +40,7 @@ set(tests plugin_bool.cc plugin_include.cc pose_1_9_sdf.cc + print_config.cc provide_feedback.cc root_dom.cc scene_dom.cc diff --git a/test/integration/interface_api.cc b/test/integration/interface_api.cc index 05a60c2b9..badda1669 100644 --- a/test/integration/interface_api.cc +++ b/test/integration/interface_api.cc @@ -32,6 +32,7 @@ #include "sdf/InterfaceModel.hh" #include "sdf/Model.hh" #include "sdf/Param.hh" +#include "sdf/PrintConfig.hh" #include "sdf/Root.hh" #include "sdf/Types.hh" #include "sdf/World.hh" @@ -860,3 +861,37 @@ TEST_F(InterfaceAPI, NameCollision) EXPECT_EQ(sdf::ErrorCode::DUPLICATE_NAME, errors[0].Code()); } } + +///////////////////////////////////////////////// +// Tests PrintConfig +TEST_F(InterfaceAPI, TomlParserModelIncludePrintConfig) +{ + const std::string testFile = sdf::testing::TestFile( + "sdf", "model_include_with_interface_api.sdf"); + + this->config.RegisterCustomModelParser(customTomlParser); + sdf::Root root; + sdf::Errors errors = root.Load(testFile, this->config); + EXPECT_TRUE(errors.empty()) << errors; + + const sdf::Model *model = root.Model(); + ASSERT_NE(nullptr, model); + const sdf::ElementPtr includeElem = model->Element()->GetFirstElement(); + ASSERT_NE(nullptr, includeElem); + + const std::string expectedIncludeStr = +R"( + double_pendulum.toml + 1 0 0 0 0 0 + + value1 + value2 + + +)"; + + sdf::PrintConfig printConfig; + EXPECT_EQ(includeElem->ToString("", printConfig), expectedIncludeStr); + printConfig.SetPreserveIncludes(true); + EXPECT_EQ(includeElem->ToString("", printConfig), expectedIncludeStr); +} diff --git a/test/integration/print_config.cc b/test/integration/print_config.cc new file mode 100644 index 000000000..a3cc9aba1 --- /dev/null +++ b/test/integration/print_config.cc @@ -0,0 +1,223 @@ +/* + * Copyright 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include + +#include +#include + +#include "sdf/sdf.hh" + +#include "test_config.h" + +///////////////////////////////////////////////// +TEST(PrintConfig, PreserveIncludes) +{ + const std::string modelPath = sdf::testing::TestFile("integration", "model"); + + sdf::ParserConfig parserConfig; + parserConfig.SetFindCallback( + [&](const std::string &_file) + { + return sdf::filesystem::append(modelPath, _file); + }); + + const std::string includeStr = +R"( + box + test_box + 1 2 3 0 0 0 + link + + +)"; + + const std::string modelWithIncludeStr = +R"( + + test_model + test_model + 1 2 3 0 0 0 + link + + + +)"; + + const std::string sdfStr = + "" + " " + + includeStr + + modelWithIncludeStr + + " " + ""; + + sdf::Root root; + sdf::Errors errors = root.LoadSdfString(sdfStr, parserConfig); + EXPECT_TRUE(errors.empty()) << errors; + + auto *world = root.WorldByIndex(0); + ASSERT_NE(world, nullptr); + auto *includedModel = world->ModelByIndex(0); + ASSERT_NE(includedModel, nullptr); + auto *modelWithInclude = world->ModelByIndex(1); + ASSERT_NE(modelWithInclude, nullptr); + + const std::string expandedIncludeStr = +R"( + 1 2 3 0 0 0 + + + + + 1 1 1 + + + + + + + 1 1 1 + + + + + + +)"; + + const std::string expandedModelWithIncludeStr = +R"( + + + + + + meshes/mesh.dae + + my_submesh +
true
+
+ 0.1 0.2 0.3 +
+
+
+ + + + meshes/mesh.dae + + another_submesh +
false
+
+ 1.2 2.3 3.4 +
+
+
+ + 1 2 3 0 0 0 + +
+
+)"; + + sdf::PrintConfig config; + // by default, included model should be expanded + EXPECT_EQ(includedModel->Element()->ToString("", config), expandedIncludeStr); + EXPECT_EQ(modelWithInclude->Element()->ToString("", config), + expandedModelWithIncludeStr); + + config.SetPreserveIncludes(true); + EXPECT_EQ(includedModel->Element()->ToString("", config), includeStr); + EXPECT_EQ(modelWithInclude->Element()->ToString("", config), + modelWithIncludeStr); +} + +///////////////////////////////////////////////// +// Test verifies preserving includes does not work for merge-includes. +// Need to update test if issue is addressed. +// https://github.com/ignitionrobotics/sdformat/issues/769 +TEST(PrintConfig, PreserveIncludesWithMerge) +{ + const std::string modelPath = sdf::testing::TestFile("integration", "model"); + + sdf::ParserConfig parserConfig; + parserConfig.SetFindCallback( + [&](const std::string &_file) + { + return sdf::filesystem::append(modelPath, _file); + }); + + const std::string includeMergeStr = +R"( + + box + test_box2 + + +)"; + + const std::string sdfStr = + "" + " " + + includeMergeStr + + " " + ""; + + sdf::Root root; + sdf::Errors errors = root.LoadSdfString(sdfStr, parserConfig); + EXPECT_TRUE(errors.empty()) << errors; + + auto *world = root.WorldByIndex(0); + ASSERT_NE(world, nullptr); + auto *includeMergedModel = world->ModelByIndex(0); + ASSERT_NE(includeMergedModel, nullptr); + + const std::string expectedIncludeMerge = +R"( + + 0 0 0.5 0 -0 0 + + + + + + 1 1 1 + + + + + + + 1 1 1 + + + + 0 0 0 0 0 0 + + +)"; + + sdf::PrintConfig config; + EXPECT_EQ(includeMergedModel->Element()->ToString("", config), + expectedIncludeMerge); + config.SetPreserveIncludes(true); + EXPECT_NE(includeMergedModel->Element()->ToString("", config), + includeMergeStr); + EXPECT_EQ(includeMergedModel->Element()->ToString("", config), + expectedIncludeMerge); +} From 5b48e41daca9264c25b568631fd713418543f694 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Thu, 9 Dec 2021 17:30:39 -0800 Subject: [PATCH 09/28] Added ToElement for ParticleEmitter and Link (#781) * Added ToElement for ParticleEmitter and Link Signed-off-by: Nate Koenig * expect double eq Signed-off-by: Ian Chen Co-authored-by: Nate Koenig Co-authored-by: Ian Chen --- include/sdf/Link.hh | 14 +++++ include/sdf/ParticleEmitter.hh | 5 ++ src/Link.cc | 84 ++++++++++++++++++++++++++ src/Link_TEST.cc | 106 +++++++++++++++++++++++++++++++++ src/ParticleEmitter.cc | 45 +++++++++++++- src/ParticleEmitter_TEST.cc | 51 ++++++++++++++++ 6 files changed, 304 insertions(+), 1 deletion(-) diff --git a/include/sdf/Link.hh b/include/sdf/Link.hh index eca492f77..55207c476 100644 --- a/include/sdf/Link.hh +++ b/include/sdf/Link.hh @@ -276,6 +276,12 @@ namespace sdf /// exists. public: bool AddSensor(const Sensor &_sensor); + /// \brief Add a particle emitter to the link. + /// \param[in] _emitter Particle emitter to add. + /// \return True if successful, false if a particle emitter with the name + /// already exists. + public: bool AddParticleEmitter(const ParticleEmitter &_sensor); + /// \brief Remove all collisions public: void ClearCollisions(); @@ -288,6 +294,14 @@ namespace sdf /// \brief Remove all sensors public: void ClearSensors(); + /// \brief Remove all particle emitters + public: void ClearParticleEmitters(); + + /// \brief Create and return an SDF element filled with data from this + /// link. + /// \return SDF element pointer with updated link values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/ParticleEmitter.hh b/include/sdf/ParticleEmitter.hh index d15eaa639..95b68b202 100644 --- a/include/sdf/ParticleEmitter.hh +++ b/include/sdf/ParticleEmitter.hh @@ -316,6 +316,11 @@ namespace sdf /// \paramp[in] _filePath Full path to the file on disk. public: void SetFilePath(const std::string &_filePath); + /// \brief Create and return an SDF element filled with data from this + /// particle emitter. + /// \return SDF element pointer with updated particle emitter values. + public: sdf::ElementPtr ToElement() const; + /// \brief Set the name of the xml parent of this object, to be used /// for resolving poses. This is private and is intended to be called by /// Link::SetPoseRelativeToGraph. diff --git a/src/Link.cc b/src/Link.cc index 7a5ed5846..14ff6fe10 100644 --- a/src/Link.cc +++ b/src/Link.cc @@ -25,6 +25,7 @@ #include "sdf/Error.hh" #include "sdf/Light.hh" #include "sdf/Link.hh" +#include "sdf/parser.hh" #include "sdf/ParticleEmitter.hh" #include "sdf/Sensor.hh" #include "sdf/Types.hh" @@ -534,6 +535,15 @@ bool Link::AddSensor(const Sensor &_sensor) return true; } +////////////////////////////////////////////////// +bool Link::AddParticleEmitter(const ParticleEmitter &_emitter) +{ + if (this->ParticleEmitterNameExists(_emitter.Name())) + return false; + this->dataPtr->emitters.push_back(_emitter); + return true; +} + ////////////////////////////////////////////////// void Link::ClearCollisions() { @@ -557,3 +567,77 @@ void Link::ClearSensors() { this->dataPtr->sensors.clear(); } + +////////////////////////////////////////////////// +void Link::ClearParticleEmitters() +{ + this->dataPtr->emitters.clear(); +} + +///////////////////////////////////////////////// +sdf::ElementPtr Link::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("link.sdf", elem); + + elem->GetAttribute("name")->Set(this->Name()); + + // Set pose + sdf::ElementPtr poseElem = elem->GetElement("pose"); + if (!this->dataPtr->poseRelativeTo.empty()) + { + poseElem->GetAttribute("relative_to")->Set( + this->dataPtr->poseRelativeTo); + } + poseElem->Set(this->RawPose()); + + // inertial + sdf::ElementPtr inertialElem = elem->GetElement("inertial"); + inertialElem->GetElement("pose")->Set( + this->dataPtr->inertial.Pose()); + const ignition::math::MassMatrix3d &massMatrix = + this->dataPtr->inertial.MassMatrix(); + inertialElem->GetElement("mass")->Set(massMatrix.Mass()); + sdf::ElementPtr inertiaElem = inertialElem->GetElement("inertia"); + inertiaElem->GetElement("ixx")->Set(massMatrix.Ixx()); + inertiaElem->GetElement("ixy")->Set(massMatrix.Ixy()); + inertiaElem->GetElement("ixz")->Set(massMatrix.Ixz()); + inertiaElem->GetElement("iyy")->Set(massMatrix.Iyy()); + inertiaElem->GetElement("iyz")->Set(massMatrix.Iyz()); + inertiaElem->GetElement("izz")->Set(massMatrix.Izz()); + + // wind mode + elem->GetElement("enable_wind")->Set(this->EnableWind()); + + // Collisions + for (const sdf::Collision &collision : this->dataPtr->collisions) + { + elem->InsertElement(collision.ToElement()); + } + + // Light + for (const sdf::Light &light : this->dataPtr->lights) + { + elem->InsertElement(light.ToElement()); + } + + // Particle emitters + for (const sdf::ParticleEmitter &emitter : this->dataPtr->emitters) + { + elem->InsertElement(emitter.ToElement()); + } + + // Sensors + for (const sdf::Sensor &sensor : this->dataPtr->sensors) + { + elem->InsertElement(sensor.ToElement()); + } + + // Visuals + for (const sdf::Visual &visual : this->dataPtr->visuals) + { + elem->InsertElement(visual.ToElement()); + } + + return elem; +} diff --git a/src/Link_TEST.cc b/src/Link_TEST.cc index 6dd29d8c5..dc80a479c 100644 --- a/src/Link_TEST.cc +++ b/src/Link_TEST.cc @@ -303,3 +303,109 @@ TEST(DOMLink, AddSensor) ASSERT_NE(nullptr, sensorFromLink); EXPECT_EQ(sensorFromLink->Name(), sensor.Name()); } + +///////////////////////////////////////////////// +TEST(DOMLink, ToElement) +{ + sdf::Link link; + link.SetName("my-name"); + + ignition::math::Inertiald inertial { + {2.3, + ignition::math::Vector3d(1.4, 2.3, 3.2), + ignition::math::Vector3d(0.1, 0.2, 0.3)}, + ignition::math::Pose3d(1, 2, 3, 0, 0, 0)}; + EXPECT_TRUE(link.SetInertial(inertial)); + link.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3)); + link.SetEnableWind(true); + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 1; ++i) + { + sdf::Collision collision; + collision.SetName("collision" + std::to_string(i)); + EXPECT_TRUE(link.AddCollision(collision)); + EXPECT_FALSE(link.AddCollision(collision)); + } + link.ClearCollisions(); + } + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 2; i++) + { + sdf::Visual visual; + visual.SetName("visual" + std::to_string(i)); + EXPECT_TRUE(link.AddVisual(visual)); + EXPECT_FALSE(link.AddVisual(visual)); + } + link.ClearVisuals(); + } + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 3; i++) + { + sdf::Light light; + light.SetName("light" + std::to_string(i)); + EXPECT_TRUE(link.AddLight(light)); + EXPECT_FALSE(link.AddLight(light)); + } + link.ClearLights(); + } + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 4; i++) + { + sdf::Sensor sensor; + sensor.SetName("sensor" + std::to_string(i)); + EXPECT_TRUE(link.AddSensor(sensor)); + EXPECT_FALSE(link.AddSensor(sensor)); + } + link.ClearSensors(); + } + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 5; i++) + { + sdf::ParticleEmitter emitter; + emitter.SetName("emitter" + std::to_string(i)); + EXPECT_TRUE(link.AddParticleEmitter(emitter)); + EXPECT_FALSE(link.AddParticleEmitter(emitter)); + } + link.ClearParticleEmitters(); + } + + sdf::ElementPtr elem = link.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Link link2; + link2.Load(elem); + + EXPECT_EQ(link.Name(), link2.Name()); + EXPECT_EQ(link.Inertial(), link2.Inertial()); + EXPECT_EQ(link.RawPose(), link2.RawPose()); + EXPECT_EQ(link.EnableWind(), link2.EnableWind()); + EXPECT_EQ(link.CollisionCount(), link2.CollisionCount()); + for (uint64_t i = 0; i < link2.CollisionCount(); ++i) + EXPECT_NE(nullptr, link2.CollisionByIndex(i)); + + EXPECT_EQ(link.VisualCount(), link2.VisualCount()); + for (uint64_t i = 0; i < link2.VisualCount(); ++i) + EXPECT_NE(nullptr, link2.VisualByIndex(i)); + + EXPECT_EQ(link.LightCount(), link2.LightCount()); + for (uint64_t i = 0; i < link2.LightCount(); ++i) + EXPECT_NE(nullptr, link2.LightByIndex(i)); + + EXPECT_EQ(link.SensorCount(), link2.SensorCount()); + for (uint64_t i = 0; i < link2.SensorCount(); ++i) + EXPECT_NE(nullptr, link2.SensorByIndex(i)); + + EXPECT_EQ(link.ParticleEmitterCount(), link2.ParticleEmitterCount()); + for (uint64_t i = 0; i < link2.ParticleEmitterCount(); ++i) + EXPECT_NE(nullptr, link2.ParticleEmitterByIndex(i)); +} diff --git a/src/ParticleEmitter.cc b/src/ParticleEmitter.cc index f1e353a66..7bb6a83a9 100644 --- a/src/ParticleEmitter.cc +++ b/src/ParticleEmitter.cc @@ -19,8 +19,9 @@ #include #include -#include "sdf/ParticleEmitter.hh" #include "sdf/Error.hh" +#include "sdf/parser.hh" +#include "sdf/ParticleEmitter.hh" #include "sdf/Types.hh" #include "FrameSemantics.hh" @@ -515,3 +516,45 @@ void ParticleEmitter::SetPoseRelativeToGraph( { this->dataPtr->poseRelativeToGraph = _graph; } + +///////////////////////////////////////////////// +sdf::ElementPtr ParticleEmitter::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("particle_emitter.sdf", elem); + + // Set pose + sdf::ElementPtr poseElem = elem->GetElement("pose"); + if (!this->dataPtr->poseRelativeTo.empty()) + { + poseElem->GetAttribute("relative_to")->Set( + this->dataPtr->poseRelativeTo); + } + poseElem->Set(this->RawPose()); + + elem->GetAttribute("name")->Set(this->Name()); + elem->GetAttribute("type")->Set(this->TypeStr()); + elem->GetElement("emitting")->Set(this->Emitting()); + elem->GetElement("duration")->Set(this->Duration()); + elem->GetElement("size")->Set(this->Size()); + elem->GetElement("particle_size")->Set(this->ParticleSize()); + elem->GetElement("lifetime")->Set(this->Lifetime()); + elem->GetElement("rate")->Set(this->Rate()); + elem->GetElement("min_velocity")->Set(this->MinVelocity()); + elem->GetElement("max_velocity")->Set(this->MaxVelocity()); + elem->GetElement("scale_rate")->Set(this->ScaleRate()); + elem->GetElement("color_start")->Set(this->ColorStart()); + elem->GetElement("color_end")->Set(this->ColorEnd()); + elem->GetElement("color_range_image")->Set(this->ColorRangeImage()); + elem->GetElement("topic")->Set(this->Topic()); + elem->GetElement("particle_scatter_ratio")->Set(this->ScatterRatio()); + + if (this->dataPtr->material) + { + elem->InsertElement(this->dataPtr->material->ToElement()); + } + + return elem; +} + + diff --git a/src/ParticleEmitter_TEST.cc b/src/ParticleEmitter_TEST.cc index 3cc03c85c..2ddb2b512 100644 --- a/src/ParticleEmitter_TEST.cc +++ b/src/ParticleEmitter_TEST.cc @@ -116,3 +116,54 @@ TEST(DOMParticleEmitter, Construction) emitter.SetPoseRelativeTo("/test/relative"); EXPECT_EQ("/test/relative", emitter.PoseRelativeTo()); } + +///////////////////////////////////////////////// +TEST(DOMParticleEmitter, ToElement) +{ + sdf::ParticleEmitter emitter; + + emitter.SetName("my-emitter"); + emitter.SetType(sdf::ParticleEmitterType::BOX); + emitter.SetEmitting(true); + emitter.SetDuration(1.2); + emitter.SetLifetime(3.4); + emitter.SetRate(12.5); + emitter.SetScaleRate(0.2); + emitter.SetMinVelocity(32.4); + emitter.SetMaxVelocity(50.1); + emitter.SetSize(ignition::math::Vector3d(1, 2, 3)); + emitter.SetParticleSize(ignition::math::Vector3d(4, 5, 6)); + emitter.SetColorStart(ignition::math::Color(0.1f, 0.2f, 0.3f, 1.0f)); + emitter.SetColorEnd(ignition::math::Color(0.4f, 0.5f, 0.6f, 1.0f)); + emitter.SetColorRangeImage("my-image"); + emitter.SetTopic("my-topic"); + emitter.SetScatterRatio(0.3f); + emitter.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3)); + sdf::Material material; + emitter.SetMaterial(material); + + sdf::ElementPtr elem = emitter.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::ParticleEmitter emitter2; + emitter2.Load(elem); + + EXPECT_EQ(emitter.Name(), emitter2.Name()); + EXPECT_EQ(emitter.Type(), emitter2.Type()); + EXPECT_EQ(emitter.Emitting(), emitter2.Emitting()); + EXPECT_DOUBLE_EQ(emitter.Duration(), emitter2.Duration()); + EXPECT_DOUBLE_EQ(emitter.Lifetime(), emitter2.Lifetime()); + EXPECT_DOUBLE_EQ(emitter.Rate(), emitter2.Rate()); + EXPECT_DOUBLE_EQ(emitter.ScaleRate(), emitter2.ScaleRate()); + EXPECT_DOUBLE_EQ(emitter.MinVelocity(), emitter2.MinVelocity()); + EXPECT_DOUBLE_EQ(emitter.MaxVelocity(), emitter2.MaxVelocity()); + EXPECT_EQ(emitter.Size(), emitter2.Size()); + EXPECT_EQ(emitter.ParticleSize(), emitter2.ParticleSize()); + EXPECT_EQ(emitter.ColorStart(), emitter2.ColorStart()); + EXPECT_EQ(emitter.ColorEnd(), emitter2.ColorEnd()); + EXPECT_EQ(emitter.ColorRangeImage(), emitter2.ColorRangeImage()); + EXPECT_EQ(emitter.Topic(), emitter2.Topic()); + EXPECT_FLOAT_EQ(emitter.ScatterRatio(), emitter2.ScatterRatio()); + EXPECT_EQ(emitter.RawPose(), emitter2.RawPose()); + EXPECT_NE(nullptr, emitter2.Material()); +} From 2f21fb24b9ab6d858ddaa5316d86424ae0f0df55 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Fri, 10 Dec 2021 08:10:56 -0800 Subject: [PATCH 10/28] Model actor toelement functions (#782) * Adding toelement for model and actor Signed-off-by: Nate Koenig * Updated tests Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- include/sdf/Actor.hh | 23 ++++++++++ include/sdf/Model.hh | 5 +++ src/Actor.cc | 102 +++++++++++++++++++++++++++++++++++++++++++ src/Actor_TEST.cc | 95 ++++++++++++++++++++++++++++++++++++++++ src/Model.cc | 48 ++++++++++++++++++++ src/Model_TEST.cc | 78 +++++++++++++++++++++++++++++++++ 6 files changed, 351 insertions(+) diff --git a/include/sdf/Actor.hh b/include/sdf/Actor.hh index d14cd04f1..a8a537b53 100644 --- a/include/sdf/Actor.hh +++ b/include/sdf/Actor.hh @@ -360,6 +360,29 @@ namespace sdf /// not been called. public: sdf::ElementPtr Element() const; + /// \brief Add a link to the actor. + /// \param[in] _link Link to add. + /// \return True if successful, false if a link with the name already + /// exists. + public: bool AddLink(const Link &_link); + + /// \brief Add a joint to the actor. + /// \param[in] _link Joint to add. + /// \return True if successful, false if a joint with the name already + /// exists. + public: bool AddJoint(const Joint &_joint); + + /// \brief Remove all links. + public: void ClearLinks(); + + /// \brief Remove all joints. + public: void ClearJoints(); + + /// \brief Create and return an SDF element filled with data from this + /// actor. + /// \return SDF element pointer with updated actor values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Model.hh b/include/sdf/Model.hh index ac047de1d..75ed0420d 100644 --- a/include/sdf/Model.hh +++ b/include/sdf/Model.hh @@ -346,6 +346,11 @@ namespace sdf public: const NestedInclude *InterfaceModelNestedIncludeByIndex( const uint64_t _index) const; + /// \brief Create and return an SDF element filled with data from this + /// model. + /// \return SDF element pointer with updated model values. + public: sdf::ElementPtr ToElement() const; + /// \brief Add a link to the model. /// \param[in] _link Link to add. /// \return True if successful, false if a link with the name already diff --git a/src/Actor.cc b/src/Actor.cc index 2f10ae7b4..aaf43adb3 100644 --- a/src/Actor.cc +++ b/src/Actor.cc @@ -19,6 +19,7 @@ #include #include "sdf/Actor.hh" #include "sdf/Error.hh" +#include "sdf/parser.hh" #include "Utils.hh" using namespace sdf; @@ -681,3 +682,104 @@ void Actor::SetFilePath(const std::string &_filePath) { this->dataPtr->filePath = _filePath; } + +////////////////////////////////////////////////// +bool Actor::AddLink(const Link &_link) +{ + if (this->LinkNameExists(_link.Name())) + return false; + this->dataPtr->links.push_back(_link); + return true; +} + +////////////////////////////////////////////////// +bool Actor::AddJoint(const Joint &_joint) +{ + if (this->JointNameExists(_joint.Name())) + return false; + this->dataPtr->joints.push_back(_joint); + return true; +} + +////////////////////////////////////////////////// +void Actor::ClearLinks() +{ + this->dataPtr->links.clear(); +} + +////////////////////////////////////////////////// +void Actor::ClearJoints() +{ + this->dataPtr->joints.clear(); +} + +///////////////////////////////////////////////// +sdf::ElementPtr Actor::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("actor.sdf", elem); + + elem->GetAttribute("name")->Set(this->Name()); + // Set pose + sdf::ElementPtr poseElem = elem->GetElement("pose"); + if (!this->dataPtr->poseRelativeTo.empty()) + { + poseElem->GetAttribute("relative_to")->Set( + this->dataPtr->poseRelativeTo); + } + poseElem->Set(this->RawPose()); + + // Skin + if (this->dataPtr->skinFilename != "__default__") + { + sdf::ElementPtr skinElem = elem->GetElement("skin"); + skinElem->GetElement("filename")->Set(this->dataPtr->skinFilename); + skinElem->GetElement("scale")->Set(this->dataPtr->skinScale); + } + + // Script + sdf::ElementPtr scriptElem = elem->GetElement("script"); + scriptElem->GetElement("loop")->Set(this->ScriptLoop()); + scriptElem->GetElement("delay_start")->Set(this->ScriptDelayStart()); + scriptElem->GetElement("auto_start")->Set(this->ScriptAutoStart()); + // Trajectory for the script + for (const sdf::Trajectory &traj : this->dataPtr->trajectories) + { + sdf::ElementPtr trajElem = scriptElem->AddElement("trajectory"); + trajElem->GetAttribute("id")->Set(traj.Id()); + trajElem->GetAttribute("type")->Set(traj.Type()); + trajElem->GetAttribute("tension")->Set(traj.Tension()); + // Waypoints in the trajectory. + for (uint64_t i = 0; i < traj.WaypointCount(); ++i) + { + const Waypoint *wp = traj.WaypointByIndex(i); + if (wp) + { + sdf::ElementPtr wayElem = trajElem->AddElement("waypoint"); + wayElem->GetElement("time")->Set(wp->Time()); + wayElem->GetElement("pose")->Set(wp->Pose()); + } + } + } + + // Animations + for (const sdf::Animation &anim : this->dataPtr->animations) + { + sdf::ElementPtr animElem = elem->AddElement("animation"); + animElem->GetAttribute("name")->Set(anim.Name()); + animElem->GetElement("filename")->Set(anim.Filename()); + animElem->GetElement("scale")->Set(anim.Scale()); + animElem->GetElement("interpolate_x")->Set(anim.InterpolateX()); + } + + // Joints + for (const sdf::Joint &joint : this->dataPtr->joints) + elem->InsertElement(joint.ToElement()); + + // Link + for (const sdf::Link &link : this->dataPtr->links) + elem->InsertElement(link.ToElement()); + + return elem; +} + diff --git a/src/Actor_TEST.cc b/src/Actor_TEST.cc index bac434933..6b9ed9c03 100644 --- a/src/Actor_TEST.cc +++ b/src/Actor_TEST.cc @@ -502,3 +502,98 @@ TEST(DOMTrajectory, CopyAssignmentAfterMove) EXPECT_TRUE(TrajectoriesEqual(sdf::Trajectory(), trajectory1)); EXPECT_TRUE(TrajectoriesEqual(CreateDummyTrajectory(), trajectory2)); } + +///////////////////////////////////////////////// +TEST(DOMActor, ToElement) +{ + sdf::Actor actor; + + actor.SetName("my-actor"); + actor.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3)); + actor.SetSkinFilename("my-skinfilename"); + actor.SetSkinScale(1.2); + actor.SetScriptLoop(true); + actor.SetScriptDelayStart(2.4); + actor.SetScriptAutoStart(true); + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 1; ++i) + { + sdf::Link link; + link.SetName("link" + std::to_string(i)); + EXPECT_TRUE(actor.AddLink(link)); + EXPECT_FALSE(actor.AddLink(link)); + } + actor.ClearLinks(); + } + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 2; ++i) + { + sdf::Joint joint; + joint.SetName("joint" + std::to_string(i)); + EXPECT_TRUE(actor.AddJoint(joint)); + EXPECT_FALSE(actor.AddJoint(joint)); + } + actor.ClearJoints(); + } + + sdf::Trajectory trajectory; + trajectory.SetId(1); + trajectory.SetType("type"); + trajectory.SetTension(1.0); + sdf::Waypoint waypointA, waypointB; + waypointA.SetTime(0.0); + waypointA.SetPose(ignition::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3)); + trajectory.AddWaypoint(waypointA); + waypointB.SetTime(1.0); + waypointB.SetPose(ignition::math::Pose3d(2, 4, 6, 0.1, 0.2, 0.3)); + trajectory.AddWaypoint(waypointB); + actor.AddTrajectory(trajectory); + + sdf::Animation animation; + animation.SetName("my-animation"); + animation.SetFilename("my-filename"); + animation.SetScale(1.2); + animation.SetInterpolateX(true); + + sdf::ElementPtr elem = actor.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Actor actor2; + actor2.Load(elem); + + EXPECT_EQ(actor.Name(), actor2.Name()); + EXPECT_EQ(actor.RawPose(), actor2.RawPose()); + EXPECT_DOUBLE_EQ(actor.SkinScale(), actor2.SkinScale()); + EXPECT_EQ(actor.ScriptLoop(), actor2.ScriptLoop()); + EXPECT_DOUBLE_EQ(actor.ScriptDelayStart(), actor2.ScriptDelayStart()); + + EXPECT_EQ(actor.LinkCount(), actor2.LinkCount()); + for (uint64_t i = 0; i < actor2.LinkCount(); ++i) + EXPECT_NE(nullptr, actor2.LinkByIndex(i)); + + EXPECT_EQ(actor.JointCount(), actor2.JointCount()); + for (uint64_t i = 0; i < actor2.JointCount(); ++i) + EXPECT_NE(nullptr, actor2.JointByIndex(i)); + + ASSERT_EQ(1u, actor2.TrajectoryCount()); + const sdf::Trajectory *trajectory2 = actor2.TrajectoryByIndex(0u); + ASSERT_NE(nullptr, trajectory2); + EXPECT_EQ(trajectory.Id(), trajectory2->Id()); + EXPECT_EQ(trajectory.Type(), trajectory2->Type()); + EXPECT_DOUBLE_EQ(trajectory.Tension(), trajectory2->Tension()); + + ASSERT_EQ(2u, trajectory2->WaypointCount()); + const sdf::Waypoint *waypointA2 = trajectory2->WaypointByIndex(0u); + ASSERT_NE(nullptr, waypointA2); + EXPECT_DOUBLE_EQ(waypointA.Time(), waypointA2->Time()); + EXPECT_EQ(waypointA.Pose(), waypointA2->Pose()); + + const sdf::Waypoint *waypointB2 = trajectory2->WaypointByIndex(1u); + ASSERT_NE(nullptr, waypointB2); + EXPECT_DOUBLE_EQ(waypointB.Time(), waypointB2->Time()); + EXPECT_EQ(waypointB.Pose(), waypointB2->Pose()); +} diff --git a/src/Model.cc b/src/Model.cc index 361b23243..bf5810803 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -791,6 +791,54 @@ const NestedInclude *Model::InterfaceModelNestedIncludeByIndex( return nullptr; } +///////////////////////////////////////////////// +sdf::ElementPtr Model::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("model.sdf", elem); + + elem->GetAttribute("name")->Set(this->Name()); + + if (!this->dataPtr->canonicalLink.empty()) + { + elem->GetAttribute("canonical_link")->Set(this->dataPtr->canonicalLink); + } + + if (!this->dataPtr->placementFrameName.empty()) + { + elem->GetAttribute("placement_frame")->Set( + this->dataPtr->placementFrameName); + } + + elem->GetElement("static")->Set(this->Static()); + elem->GetElement("self_collide")->Set(this->SelfCollide()); + elem->GetElement("allow_auto_disable")->Set(this->AllowAutoDisable()); + elem->GetElement("enable_wind")->Set(this->EnableWind()); + + // Set pose + sdf::ElementPtr poseElem = elem->GetElement("pose"); + if (!this->dataPtr->poseRelativeTo.empty()) + { + poseElem->GetAttribute("relative_to")->Set( + this->dataPtr->poseRelativeTo); + } + poseElem->Set(this->RawPose()); + + // Links + for (const sdf::Link &link : this->dataPtr->links) + elem->InsertElement(link.ToElement()); + + // Joints + for (const sdf::Joint &joint : this->dataPtr->joints) + elem->InsertElement(joint.ToElement()); + + // Model + for (const sdf::Model &model : this->dataPtr->models) + elem->InsertElement(model.ToElement()); + + return elem; +} + ////////////////////////////////////////////////// bool Model::AddLink(const Link &_link) { diff --git a/src/Model_TEST.cc b/src/Model_TEST.cc index 6054d1fe7..537ebe0ba 100644 --- a/src/Model_TEST.cc +++ b/src/Model_TEST.cc @@ -282,3 +282,81 @@ TEST(DOMModel, AddModel) ASSERT_NE(nullptr, modelFromModel); EXPECT_EQ(modelFromModel->Name(), nestedModel.Name()); } + +///////////////////////////////////////////////// +TEST(DOMModel, ToElement) +{ + sdf::Model model; + + model.SetName("my-model"); + model.SetStatic(true); + model.SetSelfCollide(true); + model.SetAllowAutoDisable(true); + model.SetEnableWind(true); + model.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3)); + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 1; ++i) + { + sdf::Link link; + link.SetName("link" + std::to_string(i)); + EXPECT_TRUE(model.AddLink(link)); + EXPECT_FALSE(model.AddLink(link)); + } + model.ClearLinks(); + } + model.SetCanonicalLinkName("link1"); + model.SetPlacementFrameName("link0"); + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 2; ++i) + { + sdf::Joint joint; + joint.SetName("joint" + std::to_string(i)); + EXPECT_TRUE(model.AddJoint(joint)); + EXPECT_FALSE(model.AddJoint(joint)); + } + model.ClearJoints(); + } + + for (int j = 0; j < 1; ++j) + { + for (int i = 0; i < 3; ++i) + { + sdf::Model nestedModel; + nestedModel.SetName("model" + std::to_string(i)); + EXPECT_TRUE(model.AddModel(nestedModel)); + EXPECT_FALSE(model.AddModel(nestedModel)); + } + model.ClearModels(); + } + + sdf::ElementPtr elem = model.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Model model2; + model2.Load(elem); + + EXPECT_EQ(model.Name(), model2.Name()); + EXPECT_EQ(model.Static(), model2.Static()); + EXPECT_EQ(model.SelfCollide(), model2.SelfCollide()); + EXPECT_EQ(model.AllowAutoDisable(), model2.AllowAutoDisable()); + EXPECT_EQ(model.EnableWind(), model2.EnableWind()); + EXPECT_EQ(model.RawPose(), model2.RawPose()); + EXPECT_EQ(model.CanonicalLinkName(), model2.CanonicalLinkName()); + EXPECT_EQ(model.PlacementFrameName(), model2.PlacementFrameName()); + + EXPECT_EQ(model.LinkCount(), model2.LinkCount()); + for (uint64_t i = 0; i < model2.LinkCount(); ++i) + EXPECT_NE(nullptr, model2.LinkByIndex(i)); + + EXPECT_EQ(model.JointCount(), model2.JointCount()); + for (uint64_t i = 0; i < model2.JointCount(); ++i) + EXPECT_NE(nullptr, model2.JointByIndex(i)); + + EXPECT_EQ(model.ModelCount(), model2.ModelCount()); + for (uint64_t i = 0; i < model2.ModelCount(); ++i) + EXPECT_NE(nullptr, model2.ModelByIndex(i)); +} From 24a27828c8b3cc94d62ac827090ade71b7c998c2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Sebastian=20Wallk=C3=B6tter?= Date: Fri, 10 Dec 2021 19:25:15 +0100 Subject: [PATCH 11/28] Documentation: Clarify behavior of //model/model/static (#713) Adds a sentence to the behavior of //model/static to avoid confusion on what might happen if it is used within a model that is itself included in another model. Also adds some clarification to //model/@canonical_link. Signed-off-by: FirefoxMetzger Signed-off-by: Addisu Z. Taddese Co-authored-by: Addisu Z. Taddese --- sdf/1.5/model.sdf | 7 ++++++- sdf/1.6/model.sdf | 7 ++++++- sdf/1.7/model.sdf | 16 ++++++++++++---- sdf/1.8/model.sdf | 16 ++++++++++++---- 4 files changed, 36 insertions(+), 10 deletions(-) diff --git a/sdf/1.5/model.sdf b/sdf/1.5/model.sdf index de38cbd56..766cee75d 100644 --- a/sdf/1.5/model.sdf +++ b/sdf/1.5/model.sdf @@ -7,7 +7,12 @@ - If set to true, the model is immovable. Otherwise the model is simulated in the dynamics engine. + + If set to true, the model is immovable; i.e., a dynamics engine will not + update its position. The model's implicit frame will be attached to the + world's implicit frame. This holds even if this model is nested (or + included) by another model. + diff --git a/sdf/1.6/model.sdf b/sdf/1.6/model.sdf index 82fb5a0f6..1b6a3caaa 100644 --- a/sdf/1.6/model.sdf +++ b/sdf/1.6/model.sdf @@ -7,7 +7,12 @@ - If set to true, the model is immovable. Otherwise the model is simulated in the dynamics engine. + + If set to true, the model is immovable; i.e., a dynamics engine will not + update its position. The model's implicit frame will be attached to the + world's implicit frame. This holds even if this model is nested (or + included) by another model. + diff --git a/sdf/1.7/model.sdf b/sdf/1.7/model.sdf index 80d9a5940..ce875dd25 100644 --- a/sdf/1.7/model.sdf +++ b/sdf/1.7/model.sdf @@ -14,14 +14,22 @@ The name of the model's canonical link, to which the model's implicit - coordinate frame is attached. If unset or set to an empty string, - the first link element listed as a child of this model is chosen - as the canonical link. + coordinate frame is attached. If unset or set to an empty string, the + first `/link` listed as a direct child of this model is chosen as the + canonical link. If the model has no direct `/link` children, it will + instead be attached to the first nested (or included) model's implicit + frame. - If set to true, the model is immovable. Otherwise the model is simulated in the dynamics engine. + + If set to true, the model is immovable; i.e., a dynamics engine will not + update its position. This will also overwrite this model's `@canonical_link` + and instead attach the model's implicit frame to the world's implicit frame. + This holds even if this model is nested (or included) by another model + instead of being a direct child of `//world`. + diff --git a/sdf/1.8/model.sdf b/sdf/1.8/model.sdf index ce38709a3..d7df25f9a 100644 --- a/sdf/1.8/model.sdf +++ b/sdf/1.8/model.sdf @@ -14,9 +14,11 @@ The name of the model's canonical link, to which the model's implicit - coordinate frame is attached. If unset or set to an empty string, - the first link element listed as a child of this model is chosen - as the canonical link. + coordinate frame is attached. If unset or set to an empty string, the + first `/link` listed as a direct child of this model is chosen as the + canonical link. If the model has no direct `/link` children, it will + instead be attached to the first nested (or included) model's implicit + frame. @@ -24,7 +26,13 @@ - If set to true, the model is immovable. Otherwise the model is simulated in the dynamics engine. + + If set to true, the model is immovable; i.e., a dynamics engine will not + update its position. This will also overwrite this model's `@canonical_link` + and instead attach the model's implicit frame to the world's implicit frame. + This holds even if this model is nested (or included) by another model + instead of being a direct child of `//world`. + From 826e7d62dafc303463af9991db7b917008e99004 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Sat, 11 Dec 2021 08:34:26 -0800 Subject: [PATCH 12/28] More to element (#783) * Added more ToElement functions Signed-off-by: Nate Koenig * Revert Link toelement changes Signed-off-by: Nate Koenig * Added toelement conversion for world, scene, sky, gui Signed-off-by: Nate Koenig * Fix element insertion, and updated tests Signed-off-by: Nate Koenig * Update docs Signed-off-by: Nate Koenig * Updates Signed-off-by: Nate Koenig * minor doxygen update Signed-off-by: Ian Chen Co-authored-by: Nate Koenig Co-authored-by: Ian Chen --- include/sdf/Element.hh | 9 +++- include/sdf/Gui.hh | 5 ++ include/sdf/Scene.hh | 5 ++ include/sdf/Sky.hh | 5 ++ include/sdf/World.hh | 16 +++++- sdf/1.9/scene.sdf | 2 +- src/Actor.cc | 5 +- src/Actor_TEST.cc | 10 ++-- src/Collision.cc | 4 +- src/Element.cc | 8 +++ src/Element_TEST.cc | 8 ++- src/Geometry.cc | 16 +++--- src/Gui.cc | 13 +++++ src/Gui_TEST.cc | 16 ++++++ src/Link.cc | 10 ++-- src/Link_TEST.cc | 39 +++++++------- src/Model.cc | 6 +-- src/Model_TEST.cc | 15 +++--- src/ParticleEmitter.cc | 2 +- src/Scene.cc | 19 +++++++ src/Scene_TEST.cc | 30 +++++++++++ src/Sky.cc | 22 ++++++++ src/Sky_TEST.cc | 30 +++++++++++ src/Visual.cc | 4 +- src/World.cc | 86 +++++++++++++++++++++++++++++++ src/World_TEST.cc | 113 +++++++++++++++++++++++++++++++++++++++++ src/parser.cc | 6 +-- 27 files changed, 441 insertions(+), 63 deletions(-) diff --git a/include/sdf/Element.hh b/include/sdf/Element.hh index 0a0d3fbb9..99cc471c8 100644 --- a/include/sdf/Element.hh +++ b/include/sdf/Element.hh @@ -93,7 +93,7 @@ namespace sdf public: ElementPtr GetParent() const; /// \brief Set the parent of this Element. - /// \param[in] _parent Paren for this element. + /// \param[in] _parent Parent for this element. public: void SetParent(const ElementPtr _parent); /// \brief Set the name of the Element. @@ -462,6 +462,13 @@ namespace sdf /// \param[in] _elem the element object to add. public: void InsertElement(ElementPtr _elem); + /// \brief Add an element object, and optionally set the given element's + /// parent to this object. + /// \param[in] _elem the element object to add. + /// \param[in] _setParentToSelf If true, set the _elem's parent to this + /// object and then insert. + public: void InsertElement(ElementPtr _elem, bool _setParentToSelf); + /// \brief Remove this element from its parent. public: void RemoveFromParent(); diff --git a/include/sdf/Gui.hh b/include/sdf/Gui.hh index eec65d134..37e8391e9 100644 --- a/include/sdf/Gui.hh +++ b/include/sdf/Gui.hh @@ -61,6 +61,11 @@ namespace sdf /// not been called. public: sdf::ElementPtr Element() const; + /// \brief Create and return an SDF element filled with data from this + /// gui. + /// \return SDF element pointer with updated gui values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Scene.hh b/include/sdf/Scene.hh index 2a137760c..c4a09106e 100644 --- a/include/sdf/Scene.hh +++ b/include/sdf/Scene.hh @@ -97,6 +97,11 @@ namespace sdf /// not been called. public: sdf::ElementPtr Element() const; + /// \brief Create and return an SDF element filled with data from this + /// scene. + /// \return SDF element pointer with updated scene values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Sky.hh b/include/sdf/Sky.hh index cd76cfd47..e84693618 100644 --- a/include/sdf/Sky.hh +++ b/include/sdf/Sky.hh @@ -113,6 +113,11 @@ namespace sdf /// not been called. public: sdf::ElementPtr Element() const; + /// \brief Create and return an SDF element filled with data from this + /// sky. + /// \return SDF element pointer with updated sky values. + public: sdf::ElementPtr ToElement() const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/World.hh b/include/sdf/World.hh index 4280cc57b..33cb0a01f 100644 --- a/include/sdf/World.hh +++ b/include/sdf/World.hh @@ -194,10 +194,16 @@ namespace sdf /// \brief Add a light to the world. /// \param[in] _light Light to add. - /// \return True if successful, false if a lights with the name already + /// \return True if successful, false if a light with the name already /// exists. public: bool AddLight(const Light &_light); + /// \brief Add a physics object to the world. + /// \param[in] _physics Physics to add. + /// \return True if successful, false if a physics object with the name + /// already exists. + public: bool AddPhysics(const Physics &_physics); + /// \brief Remove all models. public: void ClearModels(); @@ -207,6 +213,9 @@ namespace sdf /// \brief Remove all models. public: void ClearLights(); + /// \brief Remove all physics. + public: void ClearPhysics(); + /// \brief Get the number of actors. /// \return Number of actors contained in this World object. public: uint64_t ActorCount() const; @@ -352,6 +361,11 @@ namespace sdf public: const NestedInclude* InterfaceModelNestedIncludeByIndex( const uint64_t _index) const; + /// \brief Create and return an SDF element filled with data from this + /// world. + /// \return SDF element pointer with updated world values. + public: sdf::ElementPtr ToElement() const; + /// \brief Give the Scoped PoseRelativeToGraph to be passed on to child /// entities for resolving poses. This is private and is intended to be /// called by Root::Load. diff --git a/sdf/1.9/scene.sdf b/sdf/1.9/scene.sdf index 0cdb52eb1..01b26a7a2 100644 --- a/sdf/1.9/scene.sdf +++ b/sdf/1.9/scene.sdf @@ -23,7 +23,7 @@ - Sunset time [0..24] + Information about clouds in the sky. Speed of the clouds diff --git a/src/Actor.cc b/src/Actor.cc index aaf43adb3..35872bf56 100644 --- a/src/Actor.cc +++ b/src/Actor.cc @@ -774,12 +774,11 @@ sdf::ElementPtr Actor::ToElement() const // Joints for (const sdf::Joint &joint : this->dataPtr->joints) - elem->InsertElement(joint.ToElement()); + elem->InsertElement(joint.ToElement(), true); // Link for (const sdf::Link &link : this->dataPtr->links) - elem->InsertElement(link.ToElement()); + elem->InsertElement(link.ToElement(), true); return elem; } - diff --git a/src/Actor_TEST.cc b/src/Actor_TEST.cc index 6b9ed9c03..1e676ad0e 100644 --- a/src/Actor_TEST.cc +++ b/src/Actor_TEST.cc @@ -516,7 +516,7 @@ TEST(DOMActor, ToElement) actor.SetScriptDelayStart(2.4); actor.SetScriptAutoStart(true); - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { for (int i = 0; i < 1; ++i) { @@ -525,10 +525,11 @@ TEST(DOMActor, ToElement) EXPECT_TRUE(actor.AddLink(link)); EXPECT_FALSE(actor.AddLink(link)); } - actor.ClearLinks(); + if (j == 0) + actor.ClearLinks(); } - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { for (int i = 0; i < 2; ++i) { @@ -537,7 +538,8 @@ TEST(DOMActor, ToElement) EXPECT_TRUE(actor.AddJoint(joint)); EXPECT_FALSE(actor.AddJoint(joint)); } - actor.ClearJoints(); + if (j == 0) + actor.ClearJoints(); } sdf::Trajectory trajectory; diff --git a/src/Collision.cc b/src/Collision.cc index cbeabaf9b..7a5929a50 100644 --- a/src/Collision.cc +++ b/src/Collision.cc @@ -217,10 +217,10 @@ sdf::ElementPtr Collision::ToElement() const poseElem->Set(this->RawPose()); // Set the geometry - elem->InsertElement(this->dataPtr->geom.ToElement()); + elem->InsertElement(this->dataPtr->geom.ToElement(), true); // Set the surface - elem->InsertElement(this->dataPtr->surface.ToElement()); + elem->InsertElement(this->dataPtr->surface.ToElement(), true); return elem; } diff --git a/src/Element.cc b/src/Element.cc index d9e710868..168403b8c 100644 --- a/src/Element.cc +++ b/src/Element.cc @@ -929,6 +929,14 @@ void Element::InsertElement(ElementPtr _elem) this->dataPtr->elements.push_back(_elem); } +///////////////////////////////////////////////// +void Element::InsertElement(ElementPtr _elem, bool _setParentToSelf) +{ + if (_setParentToSelf) + _elem->SetParent(shared_from_this()); + this->dataPtr->elements.push_back(_elem); +} + ///////////////////////////////////////////////// bool Element::HasElementDescription(const std::string &_name) const { diff --git a/src/Element_TEST.cc b/src/Element_TEST.cc index de58a067f..4261d12f9 100644 --- a/src/Element_TEST.cc +++ b/src/Element_TEST.cc @@ -91,11 +91,9 @@ TEST(Element, SetExplicitlySetInFile) sdf::ElementPtr parent = std::make_shared(); sdf::ElementPtr elem = std::make_shared(); - elem->SetParent(parent); - parent->InsertElement(elem); + parent->InsertElement(elem, true); sdf::ElementPtr elem2 = std::make_shared(); - elem2->SetParent(parent); - parent->InsertElement(elem2); + parent->InsertElement(elem2, true); EXPECT_TRUE(elem->GetExplicitlySetInFile()); @@ -111,7 +109,7 @@ TEST(Element, SetExplicitlySetInFile) // set to the same value when using this function sdf::ElementPtr child = std::make_shared(); child->SetParent(elem); - elem->InsertElement(child); + elem->InsertElement(child, false); sdf::ElementPtr sibling = std::make_shared(); sibling->SetParent(elem); diff --git a/src/Geometry.cc b/src/Geometry.cc index d2c933356..6fb2edb3d 100644 --- a/src/Geometry.cc +++ b/src/Geometry.cc @@ -281,28 +281,28 @@ sdf::ElementPtr Geometry::ToElement() const switch (this->dataPtr->type) { case GeometryType::BOX: - elem->InsertElement(this->dataPtr->box->ToElement()); + elem->InsertElement(this->dataPtr->box->ToElement(), true); break; case GeometryType::CYLINDER: - elem->InsertElement(this->dataPtr->cylinder->ToElement()); + elem->InsertElement(this->dataPtr->cylinder->ToElement(), true); break; case GeometryType::PLANE: - elem->InsertElement(this->dataPtr->plane->ToElement()); + elem->InsertElement(this->dataPtr->plane->ToElement(), true); break; case GeometryType::SPHERE: - elem->InsertElement(this->dataPtr->sphere->ToElement()); + elem->InsertElement(this->dataPtr->sphere->ToElement(), true); break; case GeometryType::MESH: - elem->InsertElement(this->dataPtr->mesh->ToElement()); + elem->InsertElement(this->dataPtr->mesh->ToElement(), true); break; case GeometryType::HEIGHTMAP: - elem->InsertElement(this->dataPtr->heightmap->ToElement()); + elem->InsertElement(this->dataPtr->heightmap->ToElement(), true); break; case GeometryType::CAPSULE: - elem->InsertElement(this->dataPtr->capsule->ToElement()); + elem->InsertElement(this->dataPtr->capsule->ToElement(), true); break; case GeometryType::ELLIPSOID: - elem->InsertElement(this->dataPtr->ellipsoid->ToElement()); + elem->InsertElement(this->dataPtr->ellipsoid->ToElement(), true); break; case GeometryType::EMPTY: default: diff --git a/src/Gui.cc b/src/Gui.cc index f78973c22..06620426b 100644 --- a/src/Gui.cc +++ b/src/Gui.cc @@ -15,6 +15,7 @@ * */ #include "sdf/Gui.hh" +#include "sdf/parser.hh" #include "Utils.hh" using namespace sdf; @@ -56,6 +57,8 @@ Errors Gui::Load(ElementPtr _sdf) this->dataPtr->fullscreen = _sdf->Get("fullscreen", this->dataPtr->fullscreen).first; + // \todo(nkoenig) Parse all the elements in gui.sdf + return errors; } @@ -82,3 +85,13 @@ sdf::ElementPtr Gui::Element() const { return this->dataPtr->sdf; } + +///////////////////////////////////////////////// +sdf::ElementPtr Gui::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("gui.sdf", elem); + + elem->GetAttribute("fullscreen")->Set(this->dataPtr->fullscreen); + return elem; +} diff --git a/src/Gui_TEST.cc b/src/Gui_TEST.cc index a2ce6b844..aaef5ab26 100644 --- a/src/Gui_TEST.cc +++ b/src/Gui_TEST.cc @@ -123,3 +123,19 @@ TEST(DOMGui, Equal) gui.SetFullscreen(false); EXPECT_FALSE(gui == gui2); } + +///////////////////////////////////////////////// +TEST(DOMGui, ToElement) +{ + sdf::Gui gui; + + gui.SetFullscreen(true); + + sdf::ElementPtr elem = gui.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Gui gui2; + gui2.Load(elem); + + EXPECT_EQ(gui.Fullscreen(), gui2.Fullscreen()); +} diff --git a/src/Link.cc b/src/Link.cc index 14ff6fe10..0c51881c1 100644 --- a/src/Link.cc +++ b/src/Link.cc @@ -612,31 +612,31 @@ sdf::ElementPtr Link::ToElement() const // Collisions for (const sdf::Collision &collision : this->dataPtr->collisions) { - elem->InsertElement(collision.ToElement()); + elem->InsertElement(collision.ToElement(), true); } // Light for (const sdf::Light &light : this->dataPtr->lights) { - elem->InsertElement(light.ToElement()); + elem->InsertElement(light.ToElement(), true); } // Particle emitters for (const sdf::ParticleEmitter &emitter : this->dataPtr->emitters) { - elem->InsertElement(emitter.ToElement()); + elem->InsertElement(emitter.ToElement(), true); } // Sensors for (const sdf::Sensor &sensor : this->dataPtr->sensors) { - elem->InsertElement(sensor.ToElement()); + elem->InsertElement(sensor.ToElement(), true); } // Visuals for (const sdf::Visual &visual : this->dataPtr->visuals) { - elem->InsertElement(visual.ToElement()); + elem->InsertElement(visual.ToElement(), true); } return elem; diff --git a/src/Link_TEST.cc b/src/Link_TEST.cc index dc80a479c..8ba1e4ce5 100644 --- a/src/Link_TEST.cc +++ b/src/Link_TEST.cc @@ -319,7 +319,7 @@ TEST(DOMLink, ToElement) link.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3)); link.SetEnableWind(true); - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { for (int i = 0; i < 1; ++i) { @@ -328,22 +328,24 @@ TEST(DOMLink, ToElement) EXPECT_TRUE(link.AddCollision(collision)); EXPECT_FALSE(link.AddCollision(collision)); } - link.ClearCollisions(); + if (j == 0) + link.ClearCollisions(); } - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { - for (int i = 0; i < 2; i++) - { - sdf::Visual visual; - visual.SetName("visual" + std::to_string(i)); - EXPECT_TRUE(link.AddVisual(visual)); - EXPECT_FALSE(link.AddVisual(visual)); - } - link.ClearVisuals(); + for (int i = 0; i < 2; i++) + { + sdf::Visual visual; + visual.SetName("visual" + std::to_string(i)); + EXPECT_TRUE(link.AddVisual(visual)); + EXPECT_FALSE(link.AddVisual(visual)); + } + if (j == 0) + link.ClearVisuals(); } - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { for (int i = 0; i < 3; i++) { @@ -352,10 +354,11 @@ TEST(DOMLink, ToElement) EXPECT_TRUE(link.AddLight(light)); EXPECT_FALSE(link.AddLight(light)); } - link.ClearLights(); + if (j == 0) + link.ClearLights(); } - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { for (int i = 0; i < 4; i++) { @@ -364,10 +367,11 @@ TEST(DOMLink, ToElement) EXPECT_TRUE(link.AddSensor(sensor)); EXPECT_FALSE(link.AddSensor(sensor)); } - link.ClearSensors(); + if (j == 0) + link.ClearSensors(); } - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { for (int i = 0; i < 5; i++) { @@ -376,7 +380,8 @@ TEST(DOMLink, ToElement) EXPECT_TRUE(link.AddParticleEmitter(emitter)); EXPECT_FALSE(link.AddParticleEmitter(emitter)); } - link.ClearParticleEmitters(); + if (j == 0) + link.ClearParticleEmitters(); } sdf::ElementPtr elem = link.ToElement(); diff --git a/src/Model.cc b/src/Model.cc index bf5810803..b5cdbbcca 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -826,15 +826,15 @@ sdf::ElementPtr Model::ToElement() const // Links for (const sdf::Link &link : this->dataPtr->links) - elem->InsertElement(link.ToElement()); + elem->InsertElement(link.ToElement(), true); // Joints for (const sdf::Joint &joint : this->dataPtr->joints) - elem->InsertElement(joint.ToElement()); + elem->InsertElement(joint.ToElement(), true); // Model for (const sdf::Model &model : this->dataPtr->models) - elem->InsertElement(model.ToElement()); + elem->InsertElement(model.ToElement(), true); return elem; } diff --git a/src/Model_TEST.cc b/src/Model_TEST.cc index 537ebe0ba..e6ab9d5d5 100644 --- a/src/Model_TEST.cc +++ b/src/Model_TEST.cc @@ -295,7 +295,7 @@ TEST(DOMModel, ToElement) model.SetEnableWind(true); model.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3)); - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { for (int i = 0; i < 1; ++i) { @@ -304,12 +304,13 @@ TEST(DOMModel, ToElement) EXPECT_TRUE(model.AddLink(link)); EXPECT_FALSE(model.AddLink(link)); } - model.ClearLinks(); + if (j == 0) + model.ClearLinks(); } model.SetCanonicalLinkName("link1"); model.SetPlacementFrameName("link0"); - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { for (int i = 0; i < 2; ++i) { @@ -318,10 +319,11 @@ TEST(DOMModel, ToElement) EXPECT_TRUE(model.AddJoint(joint)); EXPECT_FALSE(model.AddJoint(joint)); } - model.ClearJoints(); + if (j == 0) + model.ClearJoints(); } - for (int j = 0; j < 1; ++j) + for (int j = 0; j <= 1; ++j) { for (int i = 0; i < 3; ++i) { @@ -330,7 +332,8 @@ TEST(DOMModel, ToElement) EXPECT_TRUE(model.AddModel(nestedModel)); EXPECT_FALSE(model.AddModel(nestedModel)); } - model.ClearModels(); + if (j == 0) + model.ClearModels(); } sdf::ElementPtr elem = model.ToElement(); diff --git a/src/ParticleEmitter.cc b/src/ParticleEmitter.cc index 7bb6a83a9..28c5414af 100644 --- a/src/ParticleEmitter.cc +++ b/src/ParticleEmitter.cc @@ -551,7 +551,7 @@ sdf::ElementPtr ParticleEmitter::ToElement() const if (this->dataPtr->material) { - elem->InsertElement(this->dataPtr->material->ToElement()); + elem->InsertElement(this->dataPtr->material->ToElement(), true); } return elem; diff --git a/src/Scene.cc b/src/Scene.cc index f99430d47..9825d601d 100644 --- a/src/Scene.cc +++ b/src/Scene.cc @@ -14,6 +14,7 @@ * limitations under the License. * */ +#include "sdf/parser.hh" #include "sdf/Scene.hh" #include "Utils.hh" @@ -176,3 +177,21 @@ sdf::ElementPtr Scene::Element() const { return this->dataPtr->sdf; } + +///////////////////////////////////////////////// +sdf::ElementPtr Scene::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("scene.sdf", elem); + + elem->GetElement("ambient")->Set(this->Ambient()); + elem->GetElement("background")->Set(this->Background()); + elem->GetElement("grid")->Set(this->Grid()); + elem->GetElement("origin_visual")->Set(this->OriginVisual()); + elem->GetElement("shadows")->Set(this->Shadows()); + + if (this->dataPtr->sky) + elem->InsertElement(this->dataPtr->sky->ToElement(), true); + + return elem; +} diff --git a/src/Scene_TEST.cc b/src/Scene_TEST.cc index 0e10ece0d..97d3479ad 100644 --- a/src/Scene_TEST.cc +++ b/src/Scene_TEST.cc @@ -170,3 +170,33 @@ TEST(DOMScene, Set) scene.SetSky(sky); EXPECT_NE(nullptr, scene.Sky()); } + +///////////////////////////////////////////////// +TEST(DOMScene, ToElement) +{ + sdf::Scene scene; + + scene.SetAmbient(ignition::math::Color(0.1f, 0.2f, 0.3f, 1.0f)); + scene.SetBackground(ignition::math::Color(0.2f, 0.3f, 0.4f, 1.0f)); + scene.SetGrid(true); + scene.SetOriginVisual(true); + scene.SetShadows(true); + + sdf::Sky sky; + scene.SetSky(sky); + + sdf::ElementPtr elem = scene.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Scene scene2; + scene2.Load(elem); + + EXPECT_EQ(scene.Ambient(), scene2.Ambient()); + EXPECT_EQ(scene.Background(), scene2.Background()); + EXPECT_EQ(scene.Grid(), scene2.Grid()); + EXPECT_EQ(scene.OriginVisual(), scene2.OriginVisual()); + EXPECT_EQ(scene.Shadows(), scene2.Shadows()); + + const sdf::Sky *sky2 = scene2.Sky(); + ASSERT_NE(nullptr, sky2); +} diff --git a/src/Sky.cc b/src/Sky.cc index 2635ac1f8..21651b07f 100644 --- a/src/Sky.cc +++ b/src/Sky.cc @@ -14,6 +14,7 @@ * limitations under the License. * */ +#include "sdf/parser.hh" #include "sdf/Sky.hh" #include "Utils.hh" @@ -201,3 +202,24 @@ sdf::ElementPtr Sky::Element() const { return this->dataPtr->sdf; } + +///////////////////////////////////////////////// +sdf::ElementPtr Sky::ToElement() const +{ + sdf::ElementPtr sceneElem(new sdf::Element); + sdf::initFile("scene.sdf", sceneElem); + sdf::ElementPtr elem = sceneElem->GetElement("sky"); + + elem->GetElement("time")->Set(this->Time()); + elem->GetElement("sunrise")->Set(this->Sunrise()); + elem->GetElement("sunset")->Set(this->Sunset()); + + sdf::ElementPtr cloudElem = elem->GetElement("clouds"); + cloudElem->GetElement("speed")->Set(this->CloudSpeed()); + cloudElem->GetElement("direction")->Set(this->CloudDirection().Radian()); + cloudElem->GetElement("humidity")->Set(this->CloudHumidity()); + cloudElem->GetElement("mean_size")->Set(this->CloudMeanSize()); + cloudElem->GetElement("ambient")->Set(this->CloudAmbient()); + + return elem; +} diff --git a/src/Sky_TEST.cc b/src/Sky_TEST.cc index 03461bc43..e629493e5 100644 --- a/src/Sky_TEST.cc +++ b/src/Sky_TEST.cc @@ -186,3 +186,33 @@ TEST(DOMSky, Set) EXPECT_EQ(ignition::math::Color(0.1f, 0.2f, 0.3f), sky.CloudAmbient()); } + +///////////////////////////////////////////////// +TEST(DOMSky, ToElement) +{ + sdf::Sky sky; + + sky.SetTime(1.2); + sky.SetSunrise(0.5); + sky.SetSunset(10.2); + sky.SetCloudSpeed(100.2); + sky.SetCloudDirection(1.56); + sky.SetCloudHumidity(0.2); + sky.SetCloudMeanSize(0.5); + sky.SetCloudAmbient(ignition::math::Color(0.1f, 0.2f, 0.3f, 1.0f)); + + sdf::ElementPtr elem = sky.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Sky sky2; + sky2.Load(elem); + + EXPECT_DOUBLE_EQ(sky.Time(), sky2.Time()); + EXPECT_DOUBLE_EQ(sky.Sunrise(), sky2.Sunrise()); + EXPECT_DOUBLE_EQ(sky.Sunset(), sky2.Sunset()); + EXPECT_DOUBLE_EQ(sky.CloudSpeed(), sky2.CloudSpeed()); + EXPECT_EQ(sky.CloudDirection(), sky2.CloudDirection()); + EXPECT_DOUBLE_EQ(sky.CloudHumidity(), sky2.CloudHumidity()); + EXPECT_DOUBLE_EQ(sky.CloudMeanSize(), sky2.CloudMeanSize()); + EXPECT_EQ(sky.CloudAmbient(), sky2.CloudAmbient()); +} diff --git a/src/Visual.cc b/src/Visual.cc index 4421f66c8..f49118c2e 100644 --- a/src/Visual.cc +++ b/src/Visual.cc @@ -320,7 +320,7 @@ sdf::ElementPtr Visual::ToElement() const poseElem->Set(this->RawPose()); // Set the geometry - elem->InsertElement(this->dataPtr->geom.ToElement()); + elem->InsertElement(this->dataPtr->geom.ToElement(), true); elem->GetElement("cast_shadows")->Set(this->CastShadows()); elem->GetElement("laser_retro")->Set(this->LaserRetro()); @@ -329,7 +329,7 @@ sdf::ElementPtr Visual::ToElement() const if (this->dataPtr->material) { - elem->InsertElement(this->dataPtr->material->ToElement()); + elem->InsertElement(this->dataPtr->material->ToElement(), true); } return elem; diff --git a/src/World.cc b/src/World.cc index 64ed5ddb4..59041eec1 100644 --- a/src/World.cc +++ b/src/World.cc @@ -798,6 +798,72 @@ Errors World::Implementation::LoadSphericalCoordinates( return errors; } +///////////////////////////////////////////////// +sdf::ElementPtr World::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("world.sdf", elem); + + elem->GetAttribute("name")->Set(this->Name()); + elem->GetElement("gravity")->Set(this->Gravity()); + elem->GetElement("magnetic_field")->Set(this->MagneticField()); + + sdf::ElementPtr windElem = elem->GetElement("wind"); + windElem->GetElement("linear_velocity")->Set(this->WindLinearVelocity()); + + // Physics + for (const sdf::Physics &physics : this->dataPtr->physics) + elem->InsertElement(physics.ToElement(), true); + + // Models + for (const sdf::Model &model : this->dataPtr->models) + elem->InsertElement(model.ToElement(), true); + + // Actors + for (const sdf::Actor &actor : this->dataPtr->actors) + elem->InsertElement(actor.ToElement(), true); + + // Lights + for (const sdf::Light &light : this->dataPtr->lights) + elem->InsertElement(light.ToElement(), true); + + // Spherical coordinates. + if (this->dataPtr->sphericalCoordinates) + { + sdf::ElementPtr sphericalElem = elem->GetElement("spherical_coordinates"); + sphericalElem->GetElement("surface_model")->Set( + ignition::math::SphericalCoordinates::Convert( + this->dataPtr->sphericalCoordinates->Surface())); + sphericalElem->GetElement("world_frame_orientation")->Set("ENU"); + sphericalElem->GetElement("latitude_deg")->Set( + this->dataPtr->sphericalCoordinates->LatitudeReference().Degree()); + sphericalElem->GetElement("longitude_deg")->Set( + this->dataPtr->sphericalCoordinates->LongitudeReference().Degree()); + sphericalElem->GetElement("elevation")->Set( + this->dataPtr->sphericalCoordinates->ElevationReference()); + sphericalElem->GetElement("heading_deg")->Set( + this->dataPtr->sphericalCoordinates->HeadingOffset().Degree()); + } + + // Atmosphere + if (this->dataPtr->atmosphere) + elem->InsertElement(this->dataPtr->atmosphere->ToElement(), true); + + // Gui + if (this->dataPtr->gui) + elem->InsertElement(this->dataPtr->gui->ToElement(), true); + + // Scene + if (this->dataPtr->scene) + elem->InsertElement(this->dataPtr->scene->ToElement(), true); + + // Audio + if (this->dataPtr->audioDevice != "default") + elem->GetElement("audio")->GetElement("device")->Set(this->AudioDevice()); + + return elem; +} + ///////////////////////////////////////////////// void World::ClearModels() { @@ -816,6 +882,12 @@ void World::ClearLights() this->dataPtr->lights.clear(); } +///////////////////////////////////////////////// +void World::ClearPhysics() +{ + this->dataPtr->physics.clear(); +} + ///////////////////////////////////////////////// bool World::AddModel(const Model &_model) { @@ -844,3 +916,17 @@ bool World::AddLight(const Light &_light) return true; } + +///////////////////////////////////////////////// +bool World::AddPhysics(const Physics &_physics) +{ + if (this->PhysicsNameExists(_physics.Name())) + { + std::cout << "Not adding physics, it exists\n"; + return false; + } + std::cout << "Adding physics\n"; + this->dataPtr->physics.push_back(_physics); + + return true; +} diff --git a/src/World_TEST.cc b/src/World_TEST.cc index 7a76f33c8..74dd57e1b 100644 --- a/src/World_TEST.cc +++ b/src/World_TEST.cc @@ -21,6 +21,7 @@ #include "sdf/Light.hh" #include "sdf/Actor.hh" #include "sdf/Model.hh" +#include "sdf/Physics.hh" #include "sdf/World.hh" ///////////////////////////////////////////////// @@ -420,3 +421,115 @@ TEST(DOMWorld, AddLight) ASSERT_NE(nullptr, lightFromWorld); EXPECT_EQ(lightFromWorld->Name(), light.Name()); } + +///////////////////////////////////////////////// +TEST(DOMWorld, ToElement) +{ + sdf::World world; + + world.SetName("my-world"); + world.SetAudioDevice("my-audio"); + world.SetWindLinearVelocity(ignition::math::Vector3d(1, 2, 3)); + world.SetGravity(ignition::math::Vector3d(-1, 5, 10)); + world.SetMagneticField(ignition::math::Vector3d(2.0, 0.1, 0.5)); + world.SetSphericalCoordinates(ignition::math::SphericalCoordinates()); + + sdf::Atmosphere atmosphere; + world.SetAtmosphere(atmosphere); + + sdf::Gui gui; + world.SetGui(gui); + + sdf::Scene scene; + world.SetScene(scene); + + for (int j = 0; j <= 1; ++j) + { + for (int i = 0; i < 2; ++i) + { + sdf::Model model; + model.SetName("model" + std::to_string(i)); + EXPECT_TRUE(world.AddModel(model)); + EXPECT_FALSE(world.AddModel(model)); + } + if (j == 0) + world.ClearModels(); + } + + for (int j = 0; j <= 1; ++j) + { + for (int i = 0; i < 3; ++i) + { + sdf::Actor actor; + actor.SetName("actor" + std::to_string(i)); + EXPECT_TRUE(world.AddActor(actor)); + EXPECT_FALSE(world.AddActor(actor)); + } + if (j == 0) + world.ClearActors(); + } + + for (int j = 0; j <= 1; ++j) + { + for (int i = 0; i < 4; ++i) + { + sdf::Light light; + light.SetName("light" + std::to_string(i)); + EXPECT_TRUE(world.AddLight(light)); + EXPECT_FALSE(world.AddLight(light)); + } + if (j == 0) + world.ClearLights(); + } + + for (int j = 0; j <= 1; ++j) + { + for (int i = 0; i < 5; ++i) + { + sdf::Physics physics; + physics.SetName("physics" + std::to_string(i)); + EXPECT_TRUE(world.AddPhysics(physics)); + EXPECT_FALSE(world.AddPhysics(physics)); + } + if (j == 0) + world.ClearPhysics(); + } + + sdf::ElementPtr elem = world.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::World world2; + world2.Load(elem); + + EXPECT_EQ(world.Name(), world2.Name()); + EXPECT_EQ(world.AudioDevice(), world2.AudioDevice()); + EXPECT_EQ(world.WindLinearVelocity(), world2.WindLinearVelocity()); + EXPECT_EQ(world.Gravity(), world2.Gravity()); + EXPECT_EQ(world.MagneticField(), world2.MagneticField()); + EXPECT_EQ(*world.SphericalCoordinates(), *world2.SphericalCoordinates()); + + const sdf::Atmosphere *atmosphere2 = world2.Atmosphere(); + ASSERT_NE(nullptr, atmosphere2); + + const sdf::Gui *gui2 = world2.Gui(); + ASSERT_NE(nullptr, gui2); + + const sdf::Scene *scene2 = world2.Scene(); + ASSERT_NE(nullptr, scene2); + + EXPECT_EQ(world.ModelCount(), world2.ModelCount()); + for (uint64_t i = 0; i < world2.ModelCount(); ++i) + EXPECT_NE(nullptr, world2.ModelByIndex(i)); + + EXPECT_EQ(world.LightCount(), world2.LightCount()); + for (uint64_t i = 0; i < world2.LightCount(); ++i) + EXPECT_NE(nullptr, world2.LightByIndex(i)); + + EXPECT_EQ(world.ActorCount(), world2.ActorCount()); + for (uint64_t i = 0; i < world2.ActorCount(); ++i) + EXPECT_NE(nullptr, world2.ActorByIndex(i)); + + EXPECT_EQ(world.PhysicsCount(), world2.PhysicsCount()); + for (uint64_t i = 0; i < world2.PhysicsCount(); ++i) + EXPECT_NE(nullptr, world2.PhysicsByIndex(i)); +} diff --git a/src/parser.cc b/src/parser.cc index a3cec154a..0c45332b0 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -203,8 +203,7 @@ static void insertIncludedElement(sdf::SDFPtr _includeSDF, if (!_merge) { - firstElem->SetParent(_parent); - _parent->InsertElement(firstElem); + _parent->InsertElement(firstElem, true); return; } else if (firstElem->GetName() != "model") @@ -347,8 +346,7 @@ static void insertIncludedElement(sdf::SDFPtr _includeSDF, (elem->GetName() == "gripper") || (elem->GetName() == "plugin") || (elem->GetName().find(':') != std::string::npos)) { - elem->SetParent(_parent); - _parent->InsertElement(elem); + _parent->InsertElement(elem, true); } } } From 4a6b5b683455e5c67649296031edeedc51854258 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Mon, 13 Dec 2021 16:03:43 -0800 Subject: [PATCH 13/28] Support adding and clearing sensors from a joint (#785) Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- include/sdf/Joint.hh | 9 +++++++++ src/Joint.cc | 15 +++++++++++++++ src/Joint_TEST.cc | 18 ++++++++++++++++++ 3 files changed, 42 insertions(+) diff --git a/include/sdf/Joint.hh b/include/sdf/Joint.hh index 55f855c61..fdd59502e 100644 --- a/include/sdf/Joint.hh +++ b/include/sdf/Joint.hh @@ -230,6 +230,15 @@ namespace sdf /// \return SDF element pointer with updated joint values. public: sdf::ElementPtr ToElement() const; + /// \brief Add a sensors to the joint. + /// \param[in] _sensor Sensor to add. + /// \return True if successful, false if a sensor with the name already + /// exists. + public: bool AddSensor(const Sensor &_sensor); + + /// \brief Remove all sensors. + public: void ClearSensors(); + /// \brief Give the scoped FrameAttachedToGraph to be used for resolving /// parent and child link names. This is private and is intended to be /// called by Model::Load. diff --git a/src/Joint.cc b/src/Joint.cc index 0e77e1f34..1a9e64e84 100644 --- a/src/Joint.cc +++ b/src/Joint.cc @@ -528,3 +528,18 @@ sdf::ElementPtr Joint::ToElement() const // supported. return elem; } + +////////////////////////////////////////////////// +bool Joint::AddSensor(const Sensor &_sensor) +{ + if (this->SensorNameExists(_sensor.Name())) + return false; + this->dataPtr->sensors.push_back(_sensor); + return true; +} + +////////////////////////////////////////////////// +void Joint::ClearSensors() +{ + this->dataPtr->sensors.clear(); +} diff --git a/src/Joint_TEST.cc b/src/Joint_TEST.cc index e00463c20..ee7b7e69c 100644 --- a/src/Joint_TEST.cc +++ b/src/Joint_TEST.cc @@ -18,6 +18,7 @@ #include #include #include "sdf/Joint.hh" +#include "sdf/Sensor.hh" #include "sdf/JointAxis.hh" ///////////////////////////////////////////////// @@ -269,6 +270,19 @@ TEST(DOMJoint, ToElement) EXPECT_TRUE(axis1.SetXyz(ignition::math::Vector3d(0, 1, 0)).empty()); joint.SetAxis(1, axis1); + for (int j = 0; j <= 1; ++j) + { + for (int i = 0; i < 3; ++i) + { + sdf::Sensor sensor; + sensor.SetName("sensor" + std::to_string(i)); + EXPECT_TRUE(joint.AddSensor(sensor)); + EXPECT_FALSE(joint.AddSensor(sensor)); + } + if (j == 0) + joint.ClearSensors(); + } + sdf::ElementPtr jointElem = joint.ToElement(); EXPECT_NE(nullptr, jointElem); EXPECT_EQ(nullptr, joint.Element()); @@ -289,6 +303,10 @@ TEST(DOMJoint, ToElement) EXPECT_EQ(axis.Xyz(), joint2.Axis(0)->Xyz()); EXPECT_EQ(axis1.Xyz(), joint2.Axis(1)->Xyz()); + EXPECT_EQ(joint.SensorCount(), joint.SensorCount()); + for (uint64_t i = 0; i < joint.SensorCount(); ++i) + EXPECT_NE(nullptr, joint.SensorByIndex(i)); + // make changes to DOM and verify ToElement produces updated values joint2.SetParentLinkName("new_parent"); sdf::ElementPtr joint2Elem = joint2.ToElement(); From 1a889721e3ab3066e06ec4d15056f4ca1d2082aa Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Fri, 17 Dec 2021 10:42:15 -0800 Subject: [PATCH 14/28] Support URI in the Model DOM (#786) * Support URI in the Model DOM Signed-off-by: Nate Koenig * One minor test Signed-off-by: Nate Koenig * placement frame and static Signed-off-by: Nate Koenig * relative_to Signed-off-by: Nate Koenig * Added nested include test Signed-off-by: Nate Koenig * Updates Signed-off-by: Nate Koenig * useincludetag Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- include/sdf/Model.hh | 18 ++++++- src/Model.cc | 41 +++++++++++++-- src/Model_TEST.cc | 115 +++++++++++++++++++++++++++++++++++++++++++ 3 files changed, 170 insertions(+), 4 deletions(-) diff --git a/include/sdf/Model.hh b/include/sdf/Model.hh index 75ed0420d..ec8b5684f 100644 --- a/include/sdf/Model.hh +++ b/include/sdf/Model.hh @@ -348,8 +348,16 @@ namespace sdf /// \brief Create and return an SDF element filled with data from this /// model. + /// \param[in] _useIncludeTag When true, the model's URI is used to create + /// an SDF `` rather than a ``. The model's URI must be + /// first set using the `Model::SetUri` function. If the model's URI is + /// empty, then a `` element will be generated. The default is true + /// so that URI values are used when ToElement is called from a + /// World object. Make sure to use `Model::SetUri` even when the model + /// is loaded from an `` tag since the parser will + /// automatically expand an `` element to a `` element. /// \return SDF element pointer with updated model values. - public: sdf::ElementPtr ToElement() const; + public: sdf::ElementPtr ToElement(bool _useIncludeTag = true) const; /// \brief Add a link to the model. /// \param[in] _link Link to add. @@ -378,6 +386,14 @@ namespace sdf /// \brief Remove all models. public: void ClearModels(); + /// \brief Get the URI associated with this model + /// \return The model's URI, or empty string if it has not been set. + public: std::string Uri() const; + + /// \brief Set the URI associated with this model. + /// \param[in] _uri The model's URI. + public: void SetUri(const std::string &_uri); + /// \brief Give the scoped PoseRelativeToGraph to be used for resolving /// poses. This is private and is intended to be called by Root::Load or /// World::SetPoseRelativeToGraph if this is a standalone model and diff --git a/src/Model.cc b/src/Model.cc index b5cdbbcca..eedf320e4 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -94,6 +94,10 @@ class sdf::Model::Implementation /// \brief Scope name of parent Pose Relative-To Graph (world or __model__). public: std::string poseGraphScopeVertexName; + + /// \brief Optional URI string that specifies where this model was or + /// can be loaded from. + public: std::string uri = ""; }; ///////////////////////////////////////////////// @@ -792,11 +796,42 @@ const NestedInclude *Model::InterfaceModelNestedIncludeByIndex( } ///////////////////////////////////////////////// -sdf::ElementPtr Model::ToElement() const +std::string Model::Uri() const +{ + return this->dataPtr->uri; +} + +///////////////////////////////////////////////// +void Model::SetUri(const std::string &_uri) +{ + this->dataPtr->uri = _uri; +} + +///////////////////////////////////////////////// +sdf::ElementPtr Model::ToElement(bool _useIncludeTag) const { + if (_useIncludeTag && !this->dataPtr->uri.empty()) + { + sdf::ElementPtr worldElem(new sdf::Element); + sdf::initFile("world.sdf", worldElem); + + sdf::ElementPtr includeElem = worldElem->AddElement("include"); + includeElem->GetElement("uri")->Set(this->Uri()); + includeElem->GetElement("name")->Set(this->Name()); + includeElem->GetElement("pose")->Set(this->RawPose()); + if (!this->dataPtr->poseRelativeTo.empty()) + { + includeElem->GetElement("pose")->GetAttribute( + "relative_to")->Set(this->dataPtr->poseRelativeTo); + } + includeElem->GetElement("static")->Set(this->Static()); + includeElem->GetElement("placement_frame")->Set(this->PlacementFrameName()); + + return includeElem; + } + sdf::ElementPtr elem(new sdf::Element); sdf::initFile("model.sdf", elem); - elem->GetAttribute("name")->Set(this->Name()); if (!this->dataPtr->canonicalLink.empty()) @@ -834,7 +869,7 @@ sdf::ElementPtr Model::ToElement() const // Model for (const sdf::Model &model : this->dataPtr->models) - elem->InsertElement(model.ToElement(), true); + elem->InsertElement(model.ToElement(_useIncludeTag), true); return elem; } diff --git a/src/Model_TEST.cc b/src/Model_TEST.cc index e6ab9d5d5..f7406d01f 100644 --- a/src/Model_TEST.cc +++ b/src/Model_TEST.cc @@ -20,6 +20,8 @@ #include "sdf/Joint.hh" #include "sdf/Link.hh" #include "sdf/Model.hh" +#include "sdf/parser.hh" +#include "test_config.h" ///////////////////////////////////////////////// /// Test default construction of sdf::Model. @@ -363,3 +365,116 @@ TEST(DOMModel, ToElement) for (uint64_t i = 0; i < model2.ModelCount(); ++i) EXPECT_NE(nullptr, model2.ModelByIndex(i)); } + +///////////////////////////////////////////////// +TEST(DOMModel, Uri) +{ + sdf::Model model; + std::string name = "my-model"; + ignition::math::Pose3d pose(1, 2, 3, 0.1, 0.2, 0.3); + std::string uri = + "https://fuel.ignitionrobotics.org/1.0/openrobotics/models/my-model"; + + model.SetName(name); + model.SetRawPose(pose); + model.SetStatic(true); + model.SetPlacementFrameName("link0"); + model.SetPoseRelativeTo("other"); + model.SetUri(uri); + EXPECT_EQ(uri, model.Uri()); + + // ToElement using the URI, which should result in an + { + sdf::ElementPtr elem = model.ToElement(); + EXPECT_EQ("include", elem->GetName()); + + sdf::ElementPtr uriElem = elem->FindElement("uri"); + ASSERT_NE(nullptr, uriElem); + EXPECT_EQ(uri, uriElem->Get()); + + sdf::ElementPtr nameElem = elem->FindElement("name"); + ASSERT_NE(nullptr, nameElem); + EXPECT_EQ(name, nameElem->Get()); + + sdf::ElementPtr poseElem = elem->FindElement("pose"); + ASSERT_NE(nullptr, poseElem); + EXPECT_EQ(pose, poseElem->Get()); + EXPECT_EQ("other", poseElem->GetAttribute("relative_to")->GetAsString()); + + EXPECT_EQ("link0", + elem->FindElement("placement_frame")->Get()); + + sdf::ElementPtr staticElem = elem->FindElement("static"); + ASSERT_NE(nullptr, staticElem); + EXPECT_EQ(true, staticElem->Get()); + } + + // ToElement NOT using the URI, which should result in a + { + sdf::ElementPtr elem = model.ToElement(false); + elem->PrintValues(" "); + + // Should be a + EXPECT_EQ("model", elem->GetName()); + + // URI should not exist + sdf::ElementPtr uriElem = elem->FindElement("uri"); + ASSERT_EQ(nullptr, uriElem); + + sdf::ParamPtr nameAttr = elem->GetAttribute("name"); + ASSERT_NE(nullptr, nameAttr); + EXPECT_EQ(name, nameAttr->GetAsString()); + + sdf::ParamPtr placementFrameAttr = elem->GetAttribute("placement_frame"); + ASSERT_NE(nullptr, placementFrameAttr); + EXPECT_EQ("link0", placementFrameAttr->GetAsString()); + + sdf::ElementPtr poseElem = elem->FindElement("pose"); + ASSERT_NE(nullptr, poseElem); + EXPECT_EQ(pose, poseElem->Get()); + EXPECT_EQ("other", poseElem->GetAttribute("relative_to")->GetAsString()); + + sdf::ElementPtr staticElem = elem->FindElement("static"); + ASSERT_NE(nullptr, staticElem); + EXPECT_EQ(true, staticElem->Get()); + } +} + +///////////////////////////////////////////////// +TEST(DOMModel, ToElementNestedHasUri) +{ + sdf::Model model; + model.SetName("parent"); + EXPECT_EQ(0u, model.ModelCount()); + + sdf::Model nestedModel; + nestedModel.SetName("child"); + nestedModel.SetUri("child-uri"); + EXPECT_TRUE(model.AddModel(nestedModel)); + EXPECT_EQ(1u, model.ModelCount()); + + sdf::Model nestedModel2; + nestedModel2.SetName("child2"); + EXPECT_TRUE(model.AddModel(nestedModel2)); + EXPECT_EQ(2u, model.ModelCount()); + + sdf::ElementPtr elem = model.ToElement(); + + // The parent model does not have a URI, so the element name should be + // "model". + ASSERT_NE(nullptr, elem); + EXPECT_EQ("model", elem->GetName()); + + // Get the child element, which should exist because the nested + // model has a URI. + sdf::ElementPtr includeElem = elem->FindElement("include"); + ASSERT_NE(nullptr, includeElem); + ASSERT_NE(nullptr, includeElem->FindElement("uri")); + EXPECT_EQ("child-uri", includeElem->FindElement("uri")->Get()); + + // Get the child element, which should exist because one nested + // model does not have a URI. + sdf::ElementPtr modelElem = elem->FindElement("model"); + ASSERT_NE(nullptr, modelElem); + EXPECT_EQ("child2", modelElem->GetAttribute("name")->GetAsString()); +} From ef48530765297126ff3c3486a926f4ae650c1331 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Fri, 17 Dec 2021 15:09:02 -0800 Subject: [PATCH 15/28] Added plugin to SDF DOM (#788) * Added plugin to SDF DOM Signed-off-by: Nate Koenig * tweaks Signed-off-by: Nate Koenig * Fixed doxygen Signed-off-by: Nate Koenig * Updates Signed-off-by: Nate Koenig * Update plugin copy and tests Signed-off-by: Nate Koenig * Remove string and add move functions Signed-off-by: Nate Koenig * Fix build and tests Signed-off-by: Nate Koenig * Fix windows warnings Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- include/sdf/CMakeLists.txt | 1 + include/sdf/Gui.hh | 19 +++ include/sdf/Plugin.hh | 135 +++++++++++++++++++ sdf/1.9/plugin.sdf | 2 +- src/CMakeLists.txt | 2 + src/Gui.cc | 38 ++++++ src/Gui_TEST.cc | 21 +++ src/Plugin.cc | 204 ++++++++++++++++++++++++++++ src/Plugin_TEST.cc | 263 +++++++++++++++++++++++++++++++++++++ 9 files changed, 684 insertions(+), 1 deletion(-) create mode 100644 include/sdf/Plugin.hh create mode 100644 src/Plugin.cc create mode 100644 src/Plugin_TEST.cc diff --git a/include/sdf/CMakeLists.txt b/include/sdf/CMakeLists.txt index e1422b316..686bf7c8a 100644 --- a/include/sdf/CMakeLists.txt +++ b/include/sdf/CMakeLists.txt @@ -47,6 +47,7 @@ set (headers Pbr.hh Physics.hh Plane.hh + Plugin.hh PrintConfig.hh Root.hh Scene.hh diff --git a/include/sdf/Gui.hh b/include/sdf/Gui.hh index 37e8391e9..35f9f0b6a 100644 --- a/include/sdf/Gui.hh +++ b/include/sdf/Gui.hh @@ -19,6 +19,7 @@ #include #include "sdf/Element.hh" +#include "sdf/Plugin.hh" #include "sdf/Types.hh" #include "sdf/sdf_config.h" #include "sdf/system_util.hh" @@ -66,6 +67,24 @@ namespace sdf /// \return SDF element pointer with updated gui values. public: sdf::ElementPtr ToElement() const; + /// \brief Get the number of plugins. + /// \return Number of plugins contained in this Gui object. + public: uint64_t PluginCount() const; + + /// \brief Get a plugin based on an index. + /// \param[in] _index Index of the plugin. The index should be in the + /// range [0..PluginCount()). + /// \return Pointer to the plugin. Nullptr if the index does not exist. + /// \sa uint64_t PluginCount() const + public: const Plugin *PluginByIndex(const uint64_t _index) const; + + /// \brief Remove all plugins + public: void ClearPlugins(); + + /// \brief Add a plugin to the link. + /// \param[in] _plugin Plugin to add. + public: void AddPlugin(const Plugin &_plugin); + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/include/sdf/Plugin.hh b/include/sdf/Plugin.hh new file mode 100644 index 000000000..2026b8ae9 --- /dev/null +++ b/include/sdf/Plugin.hh @@ -0,0 +1,135 @@ +/* + * Copyright 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef SDF_PLUGIN_HH_ +#define SDF_PLUGIN_HH_ + +#include +#include +#include + +#include +#include +#include +#include "sdf/sdf_config.h" +#include "sdf/system_util.hh" + +#ifdef _WIN32 +// Disable warning C4251 which is triggered by +// std::unique_ptr +#pragma warning(push) +#pragma warning(disable: 4251) +#endif + +namespace sdf +{ + // Inline bracket to help doxygen filtering. + inline namespace SDF_VERSION_NAMESPACE { + // + class PluginPrivate; + + class SDFORMAT_VISIBLE Plugin + { + /// \brief Default constructor + public: Plugin(); + + /// \brief Default destructor + public: ~Plugin(); + + /// \brief Copy constructor. + /// \param[in] _plugin Plugin to copy. + public: Plugin(const Plugin &_plugin); + + /// \brief Move constructor. + /// \param[in] _plugin Plugin to copy. + public: Plugin(Plugin &&_plugin) noexcept; + + /// \brief Load the plugin based on a element pointer. This is *not* the + /// usual entry point. Typical usage of the SDF DOM is through the Root + /// object. + /// \param[in] _sdf The SDF Element pointer + /// \return Errors, which is a vector of Error objects. Each Error includes + /// an error code and message. An empty vector indicates no error. + public: Errors Load(ElementPtr _sdf); + + /// \brief Get the name of the plugin. + /// The name of the plugin should be unique within the scope of its + /// parent. + /// \return Name of the plugin. + public: std::string Name() const; + + /// \brief Set the name of the plugin. + /// The name of the plugin should be unique within the scope of its + /// parent. + /// \param[in] _name Name of the plugin. + public: void SetName(const std::string &_name); + + /// \brief Get the filename of the shared library. + /// \return Filename of the shared library associated with the plugin. + public: std::string Filename() const; + + /// \brief Remove the contents of the plugin, this is everything that + /// is a child element of the ``. + public: void ClearContents(); + + /// \brief Get the plugin contents. This is all the SDF elements that + /// are children of the ``. + /// \return The child elements of this plugin. + public: const std::vector &Contents() const; + + /// \brief Insert an element into the plugin content. This does not + /// modify the values in the sdf::ElementPtr returned by the `Element()` + /// function. + /// \param[in] _elem Element to insert. + public: void InsertContent(const sdf::ElementPtr _elem); + + /// \brief Set the filename of the shared library. + /// \param[in] _filename Filename of the shared library associated with + /// this plugin. + public: void SetFilename(const std::string &_filename); + + /// \brief Get a pointer to the SDF element that was used during + /// load. + /// \return SDF element pointer. The value will be nullptr if Load has + /// not been called. + public: sdf::ElementPtr Element() const; + + /// \brief Create and return an SDF element filled with data from this + /// plugin. + /// \return SDF element pointer with updated plugin values. + public: sdf::ElementPtr ToElement() const; + + /// \brief Copy assignment operator + /// \param[in] _plugin Plugin to copy + /// \return A reference to this plugin + public: Plugin &operator=(const Plugin &_plugin); + + /// \brief Move assignment operator + /// \param[in] _plugin Plugin to move + /// \return A reference to this plugin + public: Plugin &operator=(Plugin &&_plugin) noexcept; + + /// \brief Private data pointer. + std::unique_ptr dataPtr; + }; +} +} + +#ifdef _WIN32 +#pragma warning(pop) +#endif + +#endif diff --git a/sdf/1.9/plugin.sdf b/sdf/1.9/plugin.sdf index 236ea31af..81452b64c 100644 --- a/sdf/1.9/plugin.sdf +++ b/sdf/1.9/plugin.sdf @@ -2,7 +2,7 @@ A plugin is a dynamically loaded chunk of code. It can exist as a child of world, model, and sensor. - A unique name for the plugin, scoped to its parent. + A name for the plugin. Name of the shared library to load. If the filename is not a full path name, the file will be searched for in the configuration paths. diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index a36fe8eda..597c6f5d8 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -60,6 +60,7 @@ set (sources Pbr.cc Physics.cc Plane.cc + Plugin.cc PrintConfig.cc Root.cc Scene.cc @@ -134,6 +135,7 @@ if (BUILD_SDF_TEST) ParticleEmitter_TEST.cc Pbr_TEST.cc Physics_TEST.cc + Plugin_TEST.cc PrintConfig_TEST.cc Plane_TEST.cc Root_TEST.cc diff --git a/src/Gui.cc b/src/Gui.cc index 06620426b..dc0a9e3e0 100644 --- a/src/Gui.cc +++ b/src/Gui.cc @@ -28,6 +28,9 @@ class sdf::Gui::Implementation /// \brief The SDF element pointer used during load. public: sdf::ElementPtr sdf; + + /// \brief GUI plugins. + public: std::vector plugins; }; ///////////////////////////////////////////////// @@ -57,6 +60,10 @@ Errors Gui::Load(ElementPtr _sdf) this->dataPtr->fullscreen = _sdf->Get("fullscreen", this->dataPtr->fullscreen).first; + Errors pluginErrors = loadRepeated(_sdf, "plugin", + this->dataPtr->plugins); + errors.insert(errors.end(), pluginErrors.begin(), pluginErrors.end()); + // \todo(nkoenig) Parse all the elements in gui.sdf return errors; @@ -93,5 +100,36 @@ sdf::ElementPtr Gui::ToElement() const sdf::initFile("gui.sdf", elem); elem->GetAttribute("fullscreen")->Set(this->dataPtr->fullscreen); + + // Add in the plugins + for (const Plugin &plugin : this->dataPtr->plugins) + elem->InsertElement(plugin.ToElement(), true); + return elem; } + +///////////////////////////////////////////////// +uint64_t Gui::PluginCount() const +{ + return this->dataPtr->plugins.size(); +} + +///////////////////////////////////////////////// +const Plugin *Gui::PluginByIndex(const uint64_t _index) const +{ + if (_index < this->dataPtr->plugins.size()) + return &this->dataPtr->plugins[_index]; + return nullptr; +} + +///////////////////////////////////////////////// +void Gui::ClearPlugins() +{ + this->dataPtr->plugins.clear(); +} + +///////////////////////////////////////////////// +void Gui::AddPlugin(const Plugin &_plugin) +{ + this->dataPtr->plugins.push_back(_plugin); +} diff --git a/src/Gui_TEST.cc b/src/Gui_TEST.cc index aaef5ab26..f068d5034 100644 --- a/src/Gui_TEST.cc +++ b/src/Gui_TEST.cc @@ -131,6 +131,26 @@ TEST(DOMGui, ToElement) gui.SetFullscreen(true); + for (int j = 0; j <= 1; ++j) + { + for (int i = 0; i < 3; ++i) + { + sdf::Plugin plugin; + plugin.SetName("name" + std::to_string(i)); + plugin.SetFilename("filename" + std::to_string(i)); + gui.AddPlugin(plugin); + gui.AddPlugin(plugin); + } + if (j == 0) + { + EXPECT_EQ(6u, gui.PluginCount()); + gui.ClearPlugins(); + EXPECT_EQ(0u, gui.PluginCount()); + } + } + + + EXPECT_EQ(6u, gui.PluginCount()); sdf::ElementPtr elem = gui.ToElement(); ASSERT_NE(nullptr, elem); @@ -138,4 +158,5 @@ TEST(DOMGui, ToElement) gui2.Load(elem); EXPECT_EQ(gui.Fullscreen(), gui2.Fullscreen()); + EXPECT_EQ(6u, gui2.PluginCount()); } diff --git a/src/Plugin.cc b/src/Plugin.cc new file mode 100644 index 000000000..d59e6bb64 --- /dev/null +++ b/src/Plugin.cc @@ -0,0 +1,204 @@ +/* + * Copyright 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include "sdf/Plugin.hh" +#include "sdf/parser.hh" +#include "Utils.hh" + +using namespace sdf; + +class sdf::PluginPrivate +{ + /// \brief Name of the plugin + public: std::string name = ""; + + /// \brief Filename of the shared library + public: std::string filename = ""; + + /// \brief The SDF element pointer used during load. + public: sdf::ElementPtr sdf; + + /// \brief SDF elements inside the plugin. + public: std::vector contents; +}; + +///////////////////////////////////////////////// +Plugin::Plugin() + : dataPtr(std::make_unique()) +{ +} + +///////////////////////////////////////////////// +Plugin::~Plugin() = default; + +///////////////////////////////////////////////// +Plugin::Plugin(const Plugin &_plugin) + : dataPtr(std::make_unique()) +{ + // Copy + *this = _plugin; +} + +///////////////////////////////////////////////// +Plugin::Plugin(Plugin &&_plugin) noexcept +{ + this->dataPtr = std::move(_plugin.dataPtr); +} + +///////////////////////////////////////////////// +Errors Plugin::Load(ElementPtr _sdf) +{ + Errors errors; + + this->dataPtr->sdf = _sdf; + + // Check that sdf is a valid pointer + if (!_sdf) + { + errors.push_back({ErrorCode::ELEMENT_MISSING, + "Attempting to load a plugin, but the provided SDF " + "element is null."}); + return errors; + } + + // We need a plugin element + if (_sdf->GetName() != "plugin") + { + errors.push_back({ErrorCode::ELEMENT_INCORRECT_TYPE, + "Attempting to load a plugin, but the provided SDF " + "element is not a ."}); + return errors; + } + + // Read the models's name + if (!loadName(_sdf, this->dataPtr->name)) + { + errors.push_back({ErrorCode::ATTRIBUTE_MISSING, + "A plugin name is required, but the name is not set."}); + } + + // Read the filename + std::pair filenamePair = + _sdf->Get("filename", this->dataPtr->filename); + this->dataPtr->filename = filenamePair.first; + if (!filenamePair.second) + { + errors.push_back({ErrorCode::ATTRIBUTE_MISSING, + "A plugin filename is required, but the filename is not set."}); + } + + // Copy the contents of the plugin + for (sdf::ElementPtr innerElem = _sdf->GetFirstElement(); + innerElem; innerElem = innerElem->GetNextElement("")) + { + this->dataPtr->contents.push_back(innerElem->Clone()); + } + + return errors; +} + +///////////////////////////////////////////////// +std::string Plugin::Name() const +{ + return this->dataPtr->name; +} + +///////////////////////////////////////////////// +void Plugin::SetName(const std::string &_name) +{ + this->dataPtr->name = _name; +} + +///////////////////////////////////////////////// +std::string Plugin::Filename() const +{ + return this->dataPtr->filename; +} + +///////////////////////////////////////////////// +void Plugin::SetFilename(const std::string &_filename) +{ + this->dataPtr->filename = _filename; +} + +///////////////////////////////////////////////// +sdf::ElementPtr Plugin::Element() const +{ + return this->dataPtr->sdf; +} + +///////////////////////////////////////////////// +sdf::ElementPtr Plugin::ToElement() const +{ + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("plugin.sdf", elem); + + elem->GetAttribute("name")->Set(this->Name()); + elem->GetAttribute("filename")->Set(this->Filename()); + + // Insert plugin content + for (const sdf::ElementPtr content : this->dataPtr->contents) + elem->InsertElement(content, true); + + return elem; +} + +///////////////////////////////////////////////// +void Plugin::ClearContents() +{ + this->dataPtr->contents.clear(); +} + +///////////////////////////////////////////////// +const std::vector &Plugin::Contents() const +{ + return this->dataPtr->contents; +} + +///////////////////////////////////////////////// +void Plugin::InsertContent(const sdf::ElementPtr _elem) +{ + this->dataPtr->contents.push_back(_elem->Clone()); +} + +///////////////////////////////////////////////// +Plugin &Plugin::operator=(const Plugin &_plugin) +{ + if (!this->dataPtr) + this->dataPtr = std::make_unique(); + + this->dataPtr->name = _plugin.Name(); + this->dataPtr->filename = _plugin.Filename(); + if (_plugin.Element()) + this->dataPtr->sdf = _plugin.Element()->Clone(); + + this->dataPtr->contents.clear(); + // Copy the contents of the plugin + for (const sdf::ElementPtr content : _plugin.Contents()) + { + this->dataPtr->contents.push_back(content->Clone()); + } + + return *this; +} + +///////////////////////////////////////////////// +Plugin &Plugin::operator=(Plugin &&_plugin) noexcept +{ + this->dataPtr = std::move(_plugin.dataPtr); + return *this; +} diff --git a/src/Plugin_TEST.cc b/src/Plugin_TEST.cc new file mode 100644 index 000000000..00d5b6245 --- /dev/null +++ b/src/Plugin_TEST.cc @@ -0,0 +1,263 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include "sdf/parser.hh" +#include "sdf/Plugin.hh" +#include "sdf/Element.hh" + +///////////////////////////////////////////////// +TEST(DOMPlugin, Construction) +{ + sdf::Plugin plugin; + EXPECT_EQ(nullptr, plugin.Element()); + + EXPECT_TRUE(plugin.Name().empty()); + EXPECT_TRUE(plugin.Filename().empty()); + EXPECT_TRUE(plugin.Contents().empty()); + + plugin.SetName("my-plugin"); + EXPECT_EQ("my-plugin", plugin.Name()); + + plugin.SetFilename("filename.so"); + EXPECT_EQ("filename.so", plugin.Filename()); + + sdf::ElementPtr content(new sdf::Element); + content->SetName("an-element"); + plugin.InsertContent(content); + EXPECT_EQ(1u, plugin.Contents().size()); + + sdf::ElementPtr elem = plugin.ToElement(); + ASSERT_NE(nullptr, elem); + + ASSERT_NE(nullptr, elem->GetAttribute("name")); + EXPECT_EQ("my-plugin", elem->GetAttribute("name")->GetAsString()); + + ASSERT_NE(nullptr, elem->GetAttribute("filename")); + EXPECT_EQ("filename.so", elem->GetAttribute("filename")->GetAsString()); +} + +///////////////////////////////////////////////// +TEST(DOMPlugin, MoveConstructor) +{ + sdf::Plugin plugin; + plugin.SetName("pluginname"); + plugin.SetFilename("filename"); + + sdf::ElementPtr content(new sdf::Element); + content->SetName("an-element"); + plugin.InsertContent(content); + + sdf::Plugin plugin2(std::move(plugin)); + EXPECT_EQ("pluginname", plugin2.Name()); + EXPECT_EQ("filename", plugin2.Filename()); + ASSERT_EQ(1u, plugin2.Contents().size()); + EXPECT_EQ("an-element", plugin2.Contents()[0]->GetName()); +} + +///////////////////////////////////////////////// +TEST(DOMPlugin, CopyConstructor) +{ + sdf::Plugin plugin; + plugin.SetName("pluginname"); + plugin.SetFilename("filename"); + + sdf::Plugin plugin2(plugin); + EXPECT_EQ("pluginname", plugin2.Name()); + EXPECT_EQ("filename", plugin2.Filename()); + + EXPECT_EQ("pluginname", plugin.Name()); + EXPECT_EQ("filename", plugin.Filename()); +} + +///////////////////////////////////////////////// +TEST(DOMPlugin, CopyAssigmentOperator) +{ + sdf::Plugin plugin; + plugin.SetName("pluginname"); + plugin.SetFilename("filename"); + + sdf::Plugin plugin2; + plugin2 = plugin; + EXPECT_EQ("pluginname", plugin2.Name()); + EXPECT_EQ("filename", plugin2.Filename()); + + EXPECT_EQ("pluginname", plugin.Name()); + EXPECT_EQ("filename", plugin.Filename()); +} + +///////////////////////////////////////////////// +TEST(DOMPlugin, MoveAssignmentConstructor) +{ + sdf::Plugin plugin; + plugin.SetName("pluginname"); + plugin.SetFilename("filename"); + + sdf::Plugin plugin2; + plugin2 = std::move(plugin); + EXPECT_EQ("pluginname", plugin2.Name()); + EXPECT_EQ("filename", plugin2.Filename()); +} + +///////////////////////////////////////////////// +TEST(DOMPlugin, CopyAssignmentAfterMove) +{ + sdf::Plugin plugin; + plugin.SetName("pluginname"); + plugin.SetFilename("filename"); + + sdf::Plugin plugin2; + plugin2.SetName("pluginname2"); + plugin2.SetFilename("filename2"); + + // This is similar to what std::swap does except it uses std::move for each + // assignment + sdf::Plugin tmp = std::move(plugin); + plugin = plugin2; + plugin2 = tmp; + + EXPECT_EQ("pluginname", plugin2.Name()); + EXPECT_EQ("filename", plugin2.Filename()); + + EXPECT_EQ("pluginname2", plugin.Name()); + EXPECT_EQ("filename2", plugin.Filename()); +} + +///////////////////////////////////////////////// +TEST(DOMPlugin, Load) +{ + sdf::Plugin plugin; + sdf::Errors errors; + + // Null sdf + errors = plugin.Load(nullptr); + ASSERT_EQ(1u, errors.size()); + EXPECT_EQ(sdf::ErrorCode::ELEMENT_MISSING, errors[0].Code()); + + // Bad element name + sdf::ElementPtr sdf(new sdf::Element()); + sdf->SetName("bad"); + errors = plugin.Load(sdf); + ASSERT_EQ(1u, errors.size()); + EXPECT_EQ(sdf::ErrorCode::ELEMENT_INCORRECT_TYPE, errors[0].Code()); + EXPECT_NE(nullptr, plugin.Element()); + + sdf->SetName("plugin"); + + // Missing name and filename attribute + errors = plugin.Load(sdf); + ASSERT_EQ(2u, errors.size()); + EXPECT_EQ(sdf::ErrorCode::ATTRIBUTE_MISSING, errors[0].Code()); + EXPECT_EQ(sdf::ErrorCode::ATTRIBUTE_MISSING, errors[1].Code()); + + sdf->AddAttribute("name", "string", "__default__", true); + sdf->GetAttribute("name")->Set("my-plugin-name"); + + // Now just missing filename + errors = plugin.Load(sdf); + ASSERT_EQ(1u, errors.size()); + EXPECT_EQ(sdf::ErrorCode::ATTRIBUTE_MISSING, errors[0].Code()); + + sdf->AddAttribute("filename", "string", "__default__", true); + sdf->GetAttribute("filename")->Set("filename.so"); + + // No errors. + errors = plugin.Load(sdf); + ASSERT_TRUE(errors.empty()); +} + +///////////////////////////////////////////////// +TEST(DOMPlugin, LoadWithChildren) +{ + std::string pluginStr = R"( + + 3D View + false + docked + + ogre + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -6 0 6 0 0.5 0 + +)"; + + std::string pluginStrWithSdf = std::string("") + + pluginStr + ""; + sdf::ElementPtr elem(new sdf::Element); + sdf::initFile("plugin.sdf", elem); + sdf::readString(pluginStrWithSdf, elem); + + sdf::Plugin plugin; + sdf::Errors errors; + errors = plugin.Load(elem); + ASSERT_EQ(0u, errors.size()); + + EXPECT_EQ("3D View", plugin.Name()); + EXPECT_EQ("MinimalScene", plugin.Filename()); + + // The elements should be the same + EXPECT_EQ(elem->ToString(""), plugin.Element()->ToString("")); + + sdf::ElementPtr toElem = plugin.ToElement(); + + // The elements should be the same + EXPECT_EQ(elem->ToString(""), toElem->ToString("")); + EXPECT_EQ(pluginStr, toElem->ToString("")); + + // Test plugin copy + sdf::Plugin plugin3; + plugin3 = plugin; + plugin.ClearContents(); + sdf::Plugin plugin4(plugin3); + + toElem = plugin3.ToElement(); + EXPECT_EQ(6u, plugin3.Contents().size()); + EXPECT_EQ(pluginStr, toElem->ToString("")); + + toElem = plugin4.ToElement(); + EXPECT_EQ(6u, plugin4.Contents().size()); + EXPECT_EQ(pluginStr, toElem->ToString("")); +} + +///////////////////////////////////////////////// +TEST(DOMPlugin, ToElement) +{ + sdf::Plugin plugin; + plugin.SetName("my-plugin"); + EXPECT_EQ("my-plugin", plugin.Name()); + + plugin.SetFilename("filename.so"); + EXPECT_EQ("filename.so", plugin.Filename()); + + sdf::ElementPtr content(new sdf::Element); + content->SetName("an-element"); + plugin.InsertContent(content); + EXPECT_EQ(1u, plugin.Contents().size()); + + sdf::ElementPtr elem = plugin.ToElement(); + ASSERT_NE(nullptr, elem); + + sdf::Plugin plugin2; + plugin2.Load(elem); + + EXPECT_EQ(plugin.Name(), plugin2.Name()); + EXPECT_EQ(plugin.Filename(), plugin2.Filename()); + EXPECT_EQ(1u, plugin2.Contents().size()); + EXPECT_EQ("an-element", plugin2.Contents()[0]->GetName()); +} From 41ad07343c4a58ac800ebce9e496a9dee130d70f Mon Sep 17 00:00:00 2001 From: Jenn Nguyen Date: Fri, 17 Dec 2021 15:38:11 -0800 Subject: [PATCH 16/28] Fix loading nested include with custom attributes (#789) Signed-off-by: Jenn Nguyen --- src/parser.cc | 1 + .../model_with_custom_elements/model.config | 5 + .../model_with_custom_elements/model.sdf | 22 ++ test/integration/sdf_custom.cc | 283 ++++++++++++++++++ 4 files changed, 311 insertions(+) create mode 100644 test/integration/model/model_with_custom_elements/model.config create mode 100644 test/integration/model/model_with_custom_elements/model.sdf diff --git a/src/parser.cc b/src/parser.cc index 85c1837b8..afb781704 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -1373,6 +1373,7 @@ void addNestedModel(ElementPtr _sdf, ElementPtr _includeSDF, Errors &_errors) } _includeSDF->ClearElements(); + _includeSDF->RemoveAllAttributes(); readString(str, _includeSDF, _errors); elem = _includeSDF->GetElement("model")->GetFirstElement(); diff --git a/test/integration/model/model_with_custom_elements/model.config b/test/integration/model/model_with_custom_elements/model.config new file mode 100644 index 000000000..f374803a5 --- /dev/null +++ b/test/integration/model/model_with_custom_elements/model.config @@ -0,0 +1,5 @@ + + + model_with_custom_elements + model.sdf + diff --git a/test/integration/model/model_with_custom_elements/model.sdf b/test/integration/model/model_with_custom_elements/model.sdf new file mode 100644 index 000000000..d11a9291a --- /dev/null +++ b/test/integration/model/model_with_custom_elements/model.sdf @@ -0,0 +1,22 @@ + + + + + + + L1 + L2 + + + + + + transmission_interface/SimpleTransmission + + EffortJointInterface + + + + + + diff --git a/test/integration/sdf_custom.cc b/test/integration/sdf_custom.cc index 2b29d4f67..9f3ad54ab 100644 --- a/test/integration/sdf_custom.cc +++ b/test/integration/sdf_custom.cc @@ -82,3 +82,286 @@ TEST(SDFParser, CustomElements) tranJointElement->Get("mysim:hardwareInterface"); EXPECT_EQ("EffortJointInterface", tranHwInterface); } + +///////////////////////////////////////////////// +TEST(SDFParser, ReloadCustomElements) +{ + const std::string sdfTestFile = + sdf::testing::TestFile("integration", "custom_elems_attrs.sdf"); + + // load file with custom elements + sdf::Root root1; + sdf::Errors errors = root1.Load(sdfTestFile); + EXPECT_TRUE(errors.empty()); + + // reload string output of root1 + sdf::Root root2; + errors = root2.LoadSdfString(root1.Element()->ToString("")); + EXPECT_TRUE(errors.empty()); + + // check that root1 and root2 equal + const sdf::World *world1 = root1.WorldByIndex(0); + const sdf::World *world2 = root2.WorldByIndex(0); + ASSERT_NE(nullptr, world1); + ASSERT_NE(nullptr, world2); + + const sdf::Model *model1 = world1->ModelByIndex(0); + const sdf::Model *model2 = world2->ModelByIndex(0); + ASSERT_NE(nullptr, model1); + ASSERT_NE(nullptr, model2); + EXPECT_EQ(model1->Element()->ToString(""), model2->Element()->ToString("")); + + const sdf::Link *link1 = model1->LinkByIndex(0); + const sdf::Link *link2 = model2->LinkByIndex(0); + ASSERT_NE(nullptr, link1); + ASSERT_NE(nullptr, link2); + EXPECT_EQ(link1->Element()->ToString(""), link2->Element()->ToString("")); + + sdf::ElementPtr customElem1 = + model1->Element()->FindElement("mysim:transmission"); + sdf::ElementPtr customElem2 = + model2->Element()->FindElement("mysim:transmission"); + ASSERT_NE(nullptr, customElem1); + ASSERT_NE(nullptr, customElem2); + + const std::string customElemStr = +R"( + transmission_interface/SimpleTransmission + + EffortJointInterface + + +)"; + EXPECT_EQ(customElemStr, customElem1->ToString("")); + EXPECT_EQ(customElemStr, customElem2->ToString("")); + + sdf::ElementPtr customDesc1 = + world1->Element()->FindElement("mysim:description"); + sdf::ElementPtr customDesc2 = + world2->Element()->FindElement("mysim:description"); + ASSERT_NE(nullptr, customDesc1); + ASSERT_NE(nullptr, customDesc2); + + const std::string customDescStr = + "Description of this world\n"; + EXPECT_EQ(customDescStr, customDesc1->ToString("")); + EXPECT_EQ(customDescStr, customDesc2->ToString("")); +} + +///////////////////////////////////////////////// +TEST(SDFParser, ReloadIncludedCustomElements) +{ + const std::string modelPath = sdf::testing::TestFile("integration", "model"); + + sdf::setFindCallback( + [&](const std::string &_file) + { + return sdf::filesystem::append(modelPath, _file); + }); + + const std::string sdfStr = +R"( + + + model_with_custom_elements + + + +)"; + + // load included file with custom elements + sdf::Root root1; + sdf::Errors errors = root1.LoadSdfString(sdfStr); + EXPECT_TRUE(errors.empty()); + + // reload string output of root1 + sdf::Root root2; + errors = root2.LoadSdfString(root1.Element()->ToString("")); + EXPECT_TRUE(errors.empty()); + + // check that root1 and root2 equal + EXPECT_EQ(root1.Element()->ToString(""), root2.Element()->ToString("")); + + const sdf::World *world1 = root1.WorldByIndex(0); + const sdf::World *world2 = root2.WorldByIndex(0); + ASSERT_NE(nullptr, world1); + ASSERT_NE(nullptr, world2); + + // //model[@name=M1] + const sdf::Model *model11 = world1->ModelByIndex(0); + const sdf::Model *model12 = world2->ModelByIndex(0); + ASSERT_NE(nullptr, model11); + ASSERT_NE(nullptr, model12); + EXPECT_EQ(model11->Element()->ToString(""), model12->Element()->ToString("")); + + // //model[@name=M1]/link[@name=L1] + const sdf::Link *model11link1 = model11->LinkByIndex(0); + const sdf::Link *model12link2 = model12->LinkByIndex(0); + ASSERT_NE(nullptr, model11link1); + ASSERT_NE(nullptr, model12link2); + + const std::string linkCustomAttrStr = + "\n"; + EXPECT_EQ(linkCustomAttrStr, model11link1->Element()->ToString("")); + EXPECT_EQ(linkCustomAttrStr, model12link2->Element()->ToString("")); + + // //model[@name=M1]/model[@name=M2] + const sdf::Model *model21 = model11->ModelByIndex(0); + const sdf::Model *model22 = model12->ModelByIndex(0); + ASSERT_NE(nullptr, model21); + ASSERT_NE(nullptr, model22); + EXPECT_EQ(model21->Element()->ToString(""), model22->Element()->ToString("")); + + // //model[@name=M1]/model[@name=M2]/link[@name=L1] + const sdf::Link *model21link1 = model21->LinkByIndex(0); + const sdf::Link *model22link2 = model22->LinkByIndex(0); + ASSERT_NE(nullptr, model21link1); + ASSERT_NE(nullptr, model22link2); + EXPECT_EQ(model21link1->Element()->ToString(""), + model22link2->Element()->ToString("")); + + // check custom attributes + sdf::ParamPtr param1 = + model21link1->Element()->GetAttribute("mysim:custom_attr_str"); + sdf::ParamPtr param2 = + model22link2->Element()->GetAttribute("mysim:custom_attr_str"); + ASSERT_NE(nullptr, param1); + ASSERT_NE(nullptr, param2); + EXPECT_EQ("B", param1->GetAsString()); + EXPECT_EQ("B", param2->GetAsString()); + + // //model[@name=M1]/model[@name=M2]/link[@name=L1]/mysim:transmission + sdf::ElementPtr customElem1 = + model21link1->Element()->FindElement("mysim:transmission"); + sdf::ElementPtr customElem2 = + model22link2->Element()->FindElement("mysim:transmission"); + ASSERT_NE(nullptr, customElem1); + ASSERT_NE(nullptr, customElem2); + + const std::string customElemStr = +R"( + transmission_interface/SimpleTransmission + + EffortJointInterface + + +)"; + EXPECT_EQ(customElemStr, customElem1->ToString("")); + EXPECT_EQ(customElemStr, customElem2->ToString("")); +} + +///////////////////////////////////////////////// +TEST(SDFParser, ReloadNestedIncludedCustomElements) +{ + const std::string modelPath = sdf::testing::TestFile("integration", "model"); + + sdf::setFindCallback( + [&](const std::string &_file) + { + return sdf::filesystem::append(modelPath, _file); + }); + + const std::string sdfStr = +R"( + + + + model_with_custom_elements + + + + +)"; + + sdf::Root root1; + sdf::Errors errors = root1.LoadSdfString(sdfStr); + EXPECT_TRUE(errors.empty()); + + for (auto &e : errors) + std::cout << e.Message() << std::endl; + + sdf::Root root2; + errors = root2.LoadSdfString(root1.Element()->ToString("")); + EXPECT_TRUE(errors.empty()); + + // check that root1 and root2 equal + EXPECT_EQ(root1.Element()->ToString(""), root2.Element()->ToString("")); + + const sdf::World *world1 = root1.WorldByIndex(0); + const sdf::World *world2 = root2.WorldByIndex(0); + ASSERT_NE(nullptr, world1); + ASSERT_NE(nullptr, world2); + + // //model[@name=test] + const sdf::Model *model11 = world1->ModelByIndex(0); + const sdf::Model *model12 = world2->ModelByIndex(0); + ASSERT_NE(nullptr, model11); + ASSERT_NE(nullptr, model12); + EXPECT_EQ(model11->Element()->ToString(""), model12->Element()->ToString("")); + + // //model[@name=test]/frame[@name=M1::__model__] + const sdf::Frame *frame1 = model11->FrameByIndex(0); + const sdf::Frame *frame2 = model12->FrameByIndex(0); + ASSERT_NE(nullptr, frame1); + ASSERT_NE(nullptr, frame2); + EXPECT_EQ(frame1->Element()->ToString(""), frame2->Element()->ToString("")); + + // //model[@name=test]/link[@name=M1::L1] + const sdf::Link *model11link1 = model11->LinkByIndex(0); + const sdf::Link *model12link2 = model12->LinkByIndex(0); + ASSERT_NE(nullptr, model11link1); + ASSERT_NE(nullptr, model12link2); + + const std::string linkCustomAttrStr = +R"( + 0 0 0 0 -0 0 + +)"; + EXPECT_EQ(linkCustomAttrStr, model11link1->Element()->ToString("")); + EXPECT_EQ(linkCustomAttrStr, model12link2->Element()->ToString("")); + + // //model[@name=test]/model[@name=M1::M2] + const sdf::Model *model21 = model11->ModelByIndex(0); + const sdf::Model *model22 = model12->ModelByIndex(0); + ASSERT_NE(nullptr, model21); + ASSERT_NE(nullptr, model22); + EXPECT_EQ(model21->Element()->ToString(""), model22->Element()->ToString("")); + + // //model[@name=test]/model[@name=M1::M2]/link[@name=M1::L1] + const sdf::Link *model21link1 = model21->LinkByIndex(0); + const sdf::Link *model22link2 = model22->LinkByIndex(0); + ASSERT_NE(nullptr, model21link1); + ASSERT_NE(nullptr, model22link2); + EXPECT_EQ(model21link1->Element()->ToString(""), + model22link2->Element()->ToString("")); + + // check custom attributes + sdf::ParamPtr param1 = + model21link1->Element()->GetAttribute("mysim:custom_attr_str"); + sdf::ParamPtr param2 = + model22link2->Element()->GetAttribute("mysim:custom_attr_str"); + ASSERT_NE(nullptr, param1); + ASSERT_NE(nullptr, param2); + EXPECT_EQ("B", param1->GetAsString()); + EXPECT_EQ("B", param2->GetAsString()); + + // //model[@name=test]/model[@name=M1::M2]/link[@name=M1::L1] + // /mysim:transmission + sdf::ElementPtr customElem1 = + model21link1->Element()->FindElement("mysim:transmission"); + sdf::ElementPtr customElem2 = + model22link2->Element()->FindElement("mysim:transmission"); + ASSERT_NE(nullptr, customElem1); + ASSERT_NE(nullptr, customElem2); + + const std::string customElemStr = +R"( + transmission_interface/SimpleTransmission + + EffortJointInterface + + +)"; + EXPECT_EQ(customElemStr, customElem1->ToString("")); + EXPECT_EQ(customElemStr, customElem2->ToString("")); +} From de356cd6da967624a0f8a517499bcfad79f6f655 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Mon, 20 Dec 2021 14:02:51 -0600 Subject: [PATCH 17/28] Refactor FrameSemantics.cc (#764) The buildFrameAttachedToGraph and buildPoseRelativeToGraph have overloads for the type of parent element, but the code in each overload is very similar to each other. This refactors these functions so there's less code duplication. Signed-off-by: Addisu Z. Taddese Co-authored-by: Steve Peters --- src/FrameSemantics.cc | 1655 ++++++++++------------------- src/ign_TEST.cc | 10 +- test/integration/frame.cc | 4 +- test/integration/interface_api.cc | 2 +- 4 files changed, 582 insertions(+), 1089 deletions(-) diff --git a/src/FrameSemantics.cc b/src/FrameSemantics.cc index a07ac6906..4df943448 100644 --- a/src/FrameSemantics.cc +++ b/src/FrameSemantics.cc @@ -198,17 +198,6 @@ FindSinkVertex( return PairType(vertex, edges); } -///////////////////////////////////////////////// -std::pair - modelCanonicalLinkAndRelativeName(const Model *_model) -{ - if (nullptr == _model) - { - return std::make_pair(nullptr, ""); - } - return _model->CanonicalLinkAndRelativeName(); -} - ///////////////////////////////////////////////// /// \brief Resolve the pose of a model taking into account the placement frame /// attribute. This function is used to calculate the pose of the edge between a @@ -282,289 +271,535 @@ static Errors resolveModelPoseWithPlacementFrame( return errors; } -///////////////////////////////////////////////// -Errors buildFrameAttachedToGraph( - ScopedGraph &_out, const Model *_model, bool _isRoot) +/// \brief Base struct the contains a few common members. These structs provide +/// a common API used by the build*Graph functions to access the various +/// attributes and retrieve children of regular DOM objects and Interface +/// Elements. +struct WrapperBase { - Errors errors; + /// \brief Name of the entity + const std::string name; + /// \brief Element type, such as Model, Link, or Interface Frame. + const std::string elementType; + /// \brief Frame type used in the FrameAttachedTo or PoseRelativeTo graphs. + const FrameType frameType; +}; + +/// \brief Wrapper for sdf::Link and sdf::InterfaceLink +struct LinkWrapper : public WrapperBase +{ + /// \brief Constructor that takes an sdf::Link + explicit LinkWrapper(const sdf::Link &_link) + : WrapperBase{_link.Name(), "Link", FrameType::LINK}, + rawPose(_link.RawPose()), + rawRelativeTo(_link.PoseRelativeTo()), + relativeTo(rawRelativeTo) + { + } - if (!_model) + /// \brief Constructor that takes an sdf::InterfaceLink + explicit LinkWrapper(const sdf::InterfaceLink &_ifaceLink) + : WrapperBase{_ifaceLink.Name(), "Interface Link", FrameType::LINK}, + rawPose(_ifaceLink.PoseInModelFrame()), + rawRelativeTo("__model__"), + relativeTo(rawRelativeTo) { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid sdf::Model pointer."}); - return errors; } - else if (!_model->Element()) + + /// \brief Raw pose of the entity. + const ignition::math::Pose3d rawPose; + /// \brief The //pose/@relative_to attribute. + const std::string rawRelativeTo; + /// \brief The final @relative_to attribute. This is the same as rawRelativeTo + /// for links and interface links. + const std::string relativeTo; +}; + +/// \brief Wrapper for sdf::Frame and sdf::InterfaceFrame +struct FrameWrapper : public WrapperBase +{ + /// \brief Constructor that takes an sdf::Frame + explicit FrameWrapper(const sdf::Frame &_frame) + : WrapperBase{_frame.Name(), "Frame", FrameType::FRAME}, + rawPose(_frame.RawPose()), + rawRelativeTo(_frame.PoseRelativeTo()), + attachedTo(_frame.AttachedTo()), + relativeTo(rawRelativeTo.empty() ? attachedTo : rawRelativeTo) { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid model element in sdf::Model."}); - return errors; } - else if (_model->LinkCount() == 0 && _model->ModelCount() == 0 && - _model->InterfaceModelCount() == 0 && !_model->Static()) + + /// \brief Constructor that takes an sdf::InterfaceFrame + explicit FrameWrapper(const sdf::InterfaceFrame &_ifaceFrame) + : WrapperBase{_ifaceFrame.Name(), "Interface Frame", FrameType::FRAME}, + rawPose(_ifaceFrame.PoseInAttachedToFrame()), + rawRelativeTo(_ifaceFrame.AttachedTo()), + attachedTo(_ifaceFrame.AttachedTo()), + relativeTo(attachedTo) + { - errors.push_back({ErrorCode::MODEL_WITHOUT_LINK, - "A model must have at least one link."}); - return errors; } - auto frameType = - _model->Static() ? sdf::FrameType::STATIC_MODEL : sdf::FrameType::MODEL; + /// \brief Raw pose of the entity. + const ignition::math::Pose3d rawPose; + /// \brief The //pose/@relative_to attribute. + const std::string rawRelativeTo; + /// \brief The //frame/@attached_to attribute. + const std::string attachedTo; + /// \brief The final @relative_to attribute. For sdf::Frame, this is set to + /// the attachedTo if the rawRelativeTo is empty. For sdf::InterfaceFrame, + /// it's always set to attachedTo. + const std::string relativeTo; +}; - const std::string scopeContextName = "__model__"; +/// \brief Wrapper for sdf::Joint and sdf::InterfaceJoint +struct JointWrapper : public WrapperBase +{ + /// \brief Constructor that takes an sdf::Joint + explicit JointWrapper(const sdf::Joint &_joint) + : WrapperBase{_joint.Name(), "Joint", FrameType::JOINT}, + rawPose(_joint.RawPose()), + rawRelativeTo(_joint.PoseRelativeTo()), + childName(_joint.ChildLinkName()), + relativeTo(rawRelativeTo.empty() ? childName : rawRelativeTo) + { + } + + /// \brief Constructor that takes an sdf::InterfaceJoint + explicit JointWrapper(const sdf::InterfaceJoint &_ifaceJoint) + : WrapperBase{_ifaceJoint.Name(), "Interface Joint", FrameType::JOINT}, + rawPose(_ifaceJoint.PoseInChildFrame()), + rawRelativeTo(_ifaceJoint.ChildName()), + childName(_ifaceJoint.ChildName()), + relativeTo(childName) + { + } + + /// \brief Raw pose of the entity. + const ignition::math::Pose3d rawPose; + /// \brief The //pose/@relative_to attribute. + const std::string rawRelativeTo; + /// \brief The name of the child frame (i.e. content of //joint/child). + const std::string childName; + /// \brief The final @relative_to attribute. For sdf::Joint, this is set to + /// the childName if the rawRelativeTo is empty. For sdf::InterfaceJoint, it's + /// always set to childName. + const std::string relativeTo; +}; + +/// \brief Wrapper for sdf::Model and sdf::InterfaceModel +struct ModelWrapper : public WrapperBase +{ + /// \brief Constructor that takes an sdf::Model + explicit ModelWrapper(const sdf::Model &_model) + : WrapperBase{_model.Name(), "Model", + _model.Static() ? FrameType::STATIC_MODEL + : FrameType::MODEL}, + rawPose(_model.RawPose()), + rawRelativeTo(_model.PoseRelativeTo()), + relativeTo(rawRelativeTo), + canonicalLinkName(_model.CanonicalLinkAndRelativeName().second), + placementFrameName(_model.PlacementFrameName()), + isStatic(_model.Static()) + { + for (uint64_t i = 0; i < _model.LinkCount(); ++i) + { + this->links.emplace_back(*_model.LinkByIndex(i)); + } + for (uint64_t i = 0; i < _model.FrameCount(); ++i) + { + this->frames.emplace_back(*_model.FrameByIndex(i)); + } + for (uint64_t i = 0; i < _model.JointCount(); ++i) + { + this->joints.emplace_back(*_model.JointByIndex(i)); + } + for (uint64_t i = 0; i < _model.ModelCount(); ++i) + { + this->models.emplace_back(*_model.ModelByIndex(i)); + } + for (uint64_t i = 0; i < _model.InterfaceModelCount(); ++i) + { + this->models.emplace_back(*_model.InterfaceModelNestedIncludeByIndex(i), + *_model.InterfaceModelByIndex(i)); + } + } - auto rootId = ignition::math::graph::kNullId; - if (_isRoot) + /// \brief Constructor that takes an sdf::NestedInclude and + /// sdf::InterfaceModel. + explicit ModelWrapper(const NestedInclude &_nestedInclude, + const sdf::InterfaceModel &_ifaceModel) + : WrapperBase{_ifaceModel.Name(), "Interface Model", + _ifaceModel.Static() ? FrameType::STATIC_MODEL + : FrameType::MODEL}, + rawPose(_ifaceModel.ModelFramePoseInParentFrame()), + rawRelativeTo(_nestedInclude.IncludePoseRelativeTo().value_or("")), + relativeTo(rawRelativeTo), + canonicalLinkName(_ifaceModel.CanonicalLinkName()), + placementFrameName(_nestedInclude.PlacementFrame().value_or("")), + isStatic(_ifaceModel.Static()) { - // The __root__ vertex identifies the scope that contains a root level - // model. In the PoseRelativeTo graph, this vertex is connected to the model - // with an edge that holds the value of //model/pose. However, in the - // FrameAttachedTo graph, the vertex is disconnected because nothing is - // attached to it. Since only links and static models are allowed to be - // disconnected in this graph, the STATIC_MODEL was chosen as its frame - // type. A different frame type could potentially be used, but that adds - // more complexity to the validateFrameAttachedToGraph code. - _out = _out.AddScopeVertex( - "", "__root__", scopeContextName, sdf::FrameType::STATIC_MODEL); - rootId = _out.ScopeVertexId(); + this->AddInterfaceChildren(_ifaceModel); } - const auto modelId = _out.AddVertex(_model->Name(), frameType).Id(); + /// \brief Constructor that takes an sdf::InterfaceModel. These are + /// InterfaceModels nested under other InterfaceModels. + explicit ModelWrapper(const sdf::InterfaceModel &_ifaceModel) + : WrapperBase{_ifaceModel.Name(), "Interface Model", + _ifaceModel.Static() ? FrameType::STATIC_MODEL + : FrameType::MODEL}, + rawPose(_ifaceModel.ModelFramePoseInParentFrame()), + rawRelativeTo(""), + relativeTo(rawRelativeTo), + canonicalLinkName(_ifaceModel.CanonicalLinkName()), + placementFrameName(""), + isStatic(_ifaceModel.Static()) + { + this->AddInterfaceChildren(_ifaceModel); + } - auto outModel = _out.AddScopeVertex( - _model->Name(), scopeContextName, scopeContextName, frameType); - const auto modelFrameId = outModel.ScopeVertexId(); + /// \brief Raw pose of the entity. + const ignition::math::Pose3d rawPose; + /// \brief The //pose/@relative_to attribute. + const std::string rawRelativeTo; + /// \brief The final @relative_to attribute. This is set to rawRelativeTo for + /// sdf::Model and sdf::InterfaceModel. + const std::string relativeTo; + /// \brief The name of the resolved canonical link. + const std::string canonicalLinkName; + /// \brief The name of the placement frame. + const std::string placementFrameName; + /// \brief Whether the model/interface model is static. + const bool isStatic; - // Add an aliasing edge from the model vertex to the - // corresponding vertex in the FrameAttachedTo graph of the child model, - auto &edge = outModel.AddEdge({modelId, modelFrameId}, true); - // Set the edge weight to 0 to indicate that this is an aliasing edge. - edge.SetWeight(0); + /// \brief Children links and interface links. + std::vector links; + /// \brief Children frames and interface frames. + std::vector frames; + /// \brief Children joints and interface joints. + std::vector joints; + /// \brief Children nested models and interface models. + std::vector models; - // add link vertices - for (uint64_t l = 0; l < _model->LinkCount(); ++l) + /// \brief Helper function to add children of interface models. + private: void AddInterfaceChildren(const sdf::InterfaceModel &_ifaceModel) { - auto link = _model->LinkByIndex(l); - if (outModel.Count(link->Name()) > 0) + for (const auto &item : _ifaceModel.Links()) { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Link with non-unique name [" + link->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; + this->links.emplace_back(item); + } + for (const auto &item : _ifaceModel.Frames()) + { + this->frames.emplace_back(item); + } + for (const auto &item : _ifaceModel.Joints()) + { + this->joints.emplace_back(item); + } + for (const auto &item : _ifaceModel.NestedModels()) + { + this->models.emplace_back(*item); } - outModel.AddVertex(link->Name(), sdf::FrameType::LINK); } +}; - // add joint vertices - for (uint64_t j = 0; j < _model->JointCount(); ++j) +/// \brief Wrapper for sdf::World +struct WorldWrapper : public WrapperBase +{ + /// \brief Constructor that takes an sdf::World + explicit WorldWrapper(const sdf::World &_world) + : WrapperBase{_world.Name(), "World", FrameType::WORLD} { - auto joint = _model->JointByIndex(j); - if (outModel.Count(joint->Name()) > 0) + for (uint64_t i = 0; i < _world.FrameCount(); ++i) { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Joint with non-unique name [" + joint->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; + this->frames.emplace_back(*_world.FrameByIndex(i)); + } + for (uint64_t i = 0; i < _world.ModelCount(); ++i) + { + this->models.emplace_back(*_world.ModelByIndex(i)); + } + for (uint64_t i = 0; i < _world.InterfaceModelCount(); ++i) + { + this->models.emplace_back(*_world.InterfaceModelNestedIncludeByIndex(i), + *_world.InterfaceModelByIndex(i)); } - outModel.AddVertex(joint->Name(), sdf::FrameType::JOINT).Id(); } - // add frame vertices - for (uint64_t f = 0; f < _model->FrameCount(); ++f) + /// \brief Children frames. + std::vector frames; + /// \brief Children models and interface models. + std::vector models; +}; + +///////////////////////////////////////////////// +/// \brief Add vertices to either Frame attached to or Pose graph. If the child +/// element is a model, it calls the corresponding build*Graph function. +/// \tparam ElementT The type of Element. This must be a class that derives from +/// WrapperBase. +/// \tparam GraphT Type of Graph. Either PoseRelativeToGraph or +/// FrameAttachedToGraph. +/// \param[in,out] _out The graph to which vertices will be added. +/// \param[in] _items List of Elements such as links, joints, etc for which +/// vertices will be created in the graph. +/// \param[in] _parent Parent element of the items in `_items`. +/// \param[out] _errors Errors encountered while adding vertices. +template +void addVerticesToGraph(ScopedGraph &_out, + const std::vector &_items, + const WrapperBase &_parent, Errors &_errors) +{ + for (const auto &item : _items) { - auto frame = _model->FrameByIndex(f); - if (outModel.Count(frame->Name()) > 0) + if (_out.Count(item.name) > 0) { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Frame with non-unique name [" + frame->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); + _errors.emplace_back(ErrorCode::DUPLICATE_NAME, item.elementType + + " with non-unique name [" + item.name + "] detected in " + + lowercase(_parent.elementType) + " with name [" + + _parent.name + "]."); continue; } - outModel.AddVertex(frame->Name(), sdf::FrameType::FRAME).Id(); + if constexpr (std::is_same_v) + { + if constexpr (std::is_same_v) + { + auto nestedErrors = wrapperBuildFrameAttachedToGraph(_out, item, false); + _errors.insert(_errors.end(), nestedErrors.begin(), nestedErrors.end()); + } + else + { + auto nestedErrors = wrapperBuildPoseRelativeToGraph(_out, item, false); + _errors.insert(_errors.end(), nestedErrors.begin(), nestedErrors.end()); + } + } + else + { + _out.AddVertex(item.name, item.frameType); + } } +} - // add nested model vertices - for (uint64_t m = 0; m < _model->ModelCount(); ++m) +///////////////////////////////////////////////// +/// \brief Add edges to the PoseRelativeTo graph. +/// \tparam ElementT The type of Element. This must be a class that derives from +/// WrapperBase. +/// \param[in,out] _out The PoseRelativeTo graph to which edges will be added. +/// \param[in] _items List of Elements such as links, joints, etc for which +/// edges will be created in the graph. +/// \param[in] _parent Parent element of the items in `_items`. +/// \param[out] _errors Errors encountered while adding edges. +template +void addEdgesToGraph(ScopedGraph &_out, + const std::vector &_items, + const WrapperBase &_parent, Errors &_errors) +{ + for (const auto &item : _items) { - auto nestedModel = _model->ModelByIndex(m); - if (outModel.Count(nestedModel->Name()) > 0) + const std::string &relativeTo = item.relativeTo; + const ignition::math::Pose3d poseInRelativeTo = item.rawPose; + + auto itemId = _out.VertexIdByName(item.name); + auto relativeToId = _out.ScopeVertexId(); + std::string typeForErrorMsg = "relative_to"; + ErrorCode errorCode = ErrorCode::POSE_RELATIVE_TO_INVALID; + + if constexpr (std::is_same_v) { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Nested model with non-unique name [" + nestedModel->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; + if (item.rawRelativeTo.empty()) + { + typeForErrorMsg = "attached_to"; + errorCode = ErrorCode::FRAME_ATTACHED_TO_INVALID; + } } - auto nestedErrors = buildFrameAttachedToGraph(outModel, nestedModel, false); - errors.insert(errors.end(), nestedErrors.begin(), nestedErrors.end()); - } - // add nested interface model vertices - for (uint64_t m = 0; m < _model->InterfaceModelCount(); ++m) - { - auto nestedIfaceModel = _model->InterfaceModelByIndex(m); - if (outModel.Count(nestedIfaceModel->Name()) > 0) + if (!relativeTo.empty()) { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Nested interface model with non-unique name [" + - nestedIfaceModel->Name() + "] detected in model with name [" + - _model->Name() + "]."}); - continue; + // look for vertex in graph that matches relative_to value + if (_out.Count(relativeTo) != 1) + { + std::stringstream errMsg; + errMsg << typeForErrorMsg << " name[" << relativeTo << "] specified by " + << lowercase(item.elementType) << " with name[" << item.name + << "] does not match a"; + if (_parent.frameType == FrameType::WORLD) + { + errMsg << " model or frame name "; + } + else + { + errMsg << " nested model, link, joint, or frame name "; + } + errMsg << "in " + lowercase(_parent.elementType) + " with name[" + + _parent.name + "]."; + + _errors.push_back({errorCode, errMsg.str()}); + continue; + } + + relativeToId = _out.VertexIdByName(relativeTo); + if (item.name == relativeTo) + { + _errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, + "relative_to name[" + relativeTo + + "] is identical to " + lowercase(item.elementType) + " name[" + + item.name + "], causing a graph cycle in " + + lowercase(_parent.elementType) + " with name[" + + _parent.name + "]."}); + } + } + + if constexpr (std::is_same_v) + { + ignition::math::Pose3d resolvedModelPose = item.rawPose; + + sdf::Errors resolveErrors = resolveModelPoseWithPlacementFrame( + item.rawPose, item.placementFrameName, + _out.ChildModelScope(item.name), resolvedModelPose); + _errors.insert(_errors.end(), resolveErrors.begin(), resolveErrors.end()); + + _out.AddEdge({relativeToId, itemId}, resolvedModelPose); + } + else + { + _out.AddEdge({relativeToId, itemId}, poseInRelativeTo); } - auto nestedErrors = buildFrameAttachedToGraph(outModel, nestedIfaceModel); - errors.insert(errors.end(), nestedErrors.begin(), nestedErrors.end()); } +} - // add edges from joint to child frames - for (uint64_t j = 0; j < _model->JointCount(); ++j) +///////////////////////////////////////////////// +/// \brief Add Joint and InterfaceJoint edges to the FrameAttachedTo graph +/// \param[in,out] _out The FrameAttachedTo graph to which edges will be added. +/// \param[in] _joints List of joints for which edges will be created in the +/// graph. +/// \param[in] _model Parent model of the items in `_items`. +/// \param[out] _errors Errors encountered while adding edges. +void addEdgesToGraph(ScopedGraph &_out, + const std::vector &_joints, + const ModelWrapper &_model, Errors &_errors) +{ + for (const auto &joint : _joints) { - auto joint = _model->JointByIndex(j); - auto jointId = outModel.VertexIdByName(joint->Name()); - auto childFrameName = joint->ChildLinkName(); - if (outModel.Count(childFrameName) != 1) + auto jointId = _out.VertexIdByName(joint.name); + + if (_out.Count(joint.childName) != 1) { - errors.push_back({ErrorCode::JOINT_CHILD_LINK_INVALID, - "Child frame with name[" + childFrameName + - "] specified by joint with name[" + joint->Name() + - "] not found in model with name[" + _model->Name() + "]."}); + _errors.push_back( + {ErrorCode::JOINT_CHILD_LINK_INVALID, + "Child frame with name[" + joint.childName + "] specified by " + + lowercase(joint.elementType) + " with name[" + joint.name + + "] not found in model with name[" + _model.name + "]."}); continue; } - auto childFrameId = outModel.VertexIdByName(childFrameName); - outModel.AddEdge({jointId, childFrameId}, true); + auto childFrameId = _out.VertexIdByName(joint.childName); + _out.AddEdge({jointId, childFrameId}, true); } +} - // add frame edges - for (uint64_t f = 0; f < _model->FrameCount(); ++f) +///////////////////////////////////////////////// +/// \brief Add Frame and InterfaceFrame edges to the FrameAttachedTo graph +/// \param[in,out] _out The FrameAttachedTo graph to which edges will be added. +/// \param[in] _frames List of frames for which edges will be created in the +/// graph. +/// \param[in] _model Parent model of the items in `_items`. +/// \param[out] _errors Errors encountered while adding edges. +void addEdgesToGraph(ScopedGraph &_out, + const std::vector &_frames, + const WrapperBase &_parent, Errors &_errors) +{ + for (const auto &frame : _frames) { - auto frame = _model->FrameByIndex(f); - auto frameId = outModel.VertexIdByName(frame->Name()); + auto frameId = _out.VertexIdByName(frame.name); // look for vertex in graph that matches attached_to value - std::string attachedTo = frame->AttachedTo(); + std::string attachedTo = frame.attachedTo; if (attachedTo.empty()) { - // if the attached-to name is empty, use the scope context name - attachedTo = scopeContextName; - } - if (outModel.Count(attachedTo) != 1) - { - errors.push_back({ErrorCode::FRAME_ATTACHED_TO_INVALID, - "attached_to name[" + attachedTo + - "] specified by frame with name[" + frame->Name() + - "] does not match a nested model, link, joint, or frame name " - "in model with name[" + _model->Name() + "]."}); - continue; - } - auto attachedToId = outModel.VertexIdByName(attachedTo); - bool edgeData = true; - if (frame->Name() == frame->AttachedTo()) - { - // set edgeData to false if attaches to itself, since this is invalid - edgeData = false; - errors.push_back({ErrorCode::FRAME_ATTACHED_TO_CYCLE, - "attached_to name[" + attachedTo + - "] is identical to frame name[" + frame->Name() + - "], causing a graph cycle " - "in model with name[" + _model->Name() + "]."}); + // if the attached-to name is empty, use the default attachedTo + attachedTo = _out.ScopeContextName(); } - outModel.AddEdge({frameId, attachedToId}, edgeData); - } - // identify canonical link, which may be nested - const auto[canonicalLink, canonicalLinkName] = - modelCanonicalLinkAndRelativeName(_model); - if (!_model->Static()) - { - if (nullptr == canonicalLink) + if (_out.Count(attachedTo) != 1) { - if (canonicalLinkName.empty()) + std::stringstream errMsg; + errMsg << "attached_to name[" << attachedTo << "] specified by " + << lowercase(frame.elementType) << " with name[" << frame.name + << "] does not match a"; + if (_parent.frameType == FrameType::WORLD) { - if (_model->ModelCount() == 0 && _model->InterfaceModelCount() == 0) - { - errors.push_back({ErrorCode::MODEL_WITHOUT_LINK, - "A model must have at least one link."}); - } - else - { - // The canonical link was not found, but the model could have a - // descendant that has a static model, so simply create an edge to the - // first model and let the attached_to frame resolution take care of - // finding the canonical link - // - std::string firstChildModelName = ""; - if (_model->ModelCount() > 0) - { - firstChildModelName = _model->ModelByIndex(0)->Name(); - } - else - { - firstChildModelName = _model->InterfaceModelByIndex(0)->Name(); - } - auto firstChildModelId = outModel.VertexIdByName(firstChildModelName); - outModel.AddEdge({modelFrameId, firstChildModelId}, true); - } + errMsg << " model or frame name "; } else { - // Search for the vertex in case the canonical link is an InterfaceLink - auto canonicalLinkId = outModel.VertexIdByName(canonicalLinkName); - if (ignition::math::graph::kNullId != canonicalLinkId) - { - outModel.AddEdge({modelFrameId, canonicalLinkId}, true); - } - else - { - errors.push_back({ErrorCode::MODEL_CANONICAL_LINK_INVALID, - "canonical_link with name[" + canonicalLinkName + - "] not found in model with name[" + _model->Name() + "]."}); - } + errMsg << " nested model, link, joint, or frame name "; } - // return early - return errors; + errMsg << "in " + lowercase(_parent.elementType) + " with name[" + + _parent.name + "]."; + + _errors.push_back({ErrorCode::FRAME_ATTACHED_TO_INVALID, errMsg.str()}); + continue; } - else + + auto attachedToId = _out.VertexIdByName(attachedTo); + bool edgeData = true; + if (frame.name == frame.attachedTo) { - // Add an edge from the implicit model frame to the canonical link found. - auto linkId = outModel.VertexIdByName(canonicalLinkName); - outModel.AddEdge({modelFrameId, linkId}, true); + // set edgeData to false if attaches to itself, since this is invalid + edgeData = false; + _errors.push_back({ErrorCode::FRAME_ATTACHED_TO_CYCLE, + "attached_to name[" + attachedTo + + "] is identical to frame name[" + frame.attachedTo + + "], causing a graph cycle in " + lowercase(_parent.elementType) + + " with name[" + _parent.name + "]."}); } + _out.AddEdge({frameId, attachedToId}, edgeData); } - - return errors; } ///////////////////////////////////////////////// -Errors buildFrameAttachedToGraph(ScopedGraph &_out, - InterfaceModelConstPtr _model) +/// \brief Helper function that actually build a FrameAttachedToGraph given a +/// wrapped Model or Interface Model. +/// \param[out] _out Graph object to write. +/// \param[in] _model Wrapped Model or Interface model from which to build +/// attached_to graph. +/// \param[in] _isRoot True if the model is a standalone model, i.e, +/// //sdf/model. This is not relevant if the _model is a wrapped Interface +/// Model. +/// \return Errors. +Errors wrapperBuildFrameAttachedToGraph(ScopedGraph &_out, + const ModelWrapper &_model, + bool _isRoot) { Errors errors; - if (!_model) - { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid sdf::InterfaceModel pointer."}); - return errors; - } - else if (_model->Links().size() == 0u && _model->NestedModels().size() == 0 && - !_model->Static()) + if (_model.links.size() == 0u && _model.models.size() == 0 && + !_model.isStatic) { errors.push_back({ErrorCode::MODEL_WITHOUT_LINK, - "Model with name[" + _model->Name() + - "] must have at least one link."}); + "A model must have at least one link."}); return errors; } - auto frameType = - _model->Static() ? sdf::FrameType::STATIC_MODEL : sdf::FrameType::MODEL; + auto frameType = _model.frameType; const std::string scopeContextName = "__model__"; - const auto modelId = _out.AddVertex(_model->Name(), frameType).Id(); + auto rootId = ignition::math::graph::kNullId; + if (_isRoot) + { + // The __root__ vertex identifies the scope that contains a root level + // model. In the PoseRelativeTo graph, this vertex is connected to the model + // with an edge that holds the value of //model/pose. However, in the + // FrameAttachedTo graph, the vertex is disconnected because nothing is + // attached to it. Since only links and static models are allowed to be + // disconnected in this graph, the STATIC_MODEL was chosen as its frame + // type. A different frame type could potentially be used, but that adds + // more complexity to the validateFrameAttachedToGraph code. + _out = _out.AddScopeVertex( + "", "__root__", scopeContextName, sdf::FrameType::STATIC_MODEL); + rootId = _out.ScopeVertexId(); + } + + const auto modelId = _out.AddVertex(_model.name, frameType).Id(); auto outModel = _out.AddScopeVertex( - _model->Name(), scopeContextName, scopeContextName, frameType); + _model.name, scopeContextName, scopeContextName, frameType); const auto modelFrameId = outModel.ScopeVertexId(); // Add an aliasing edge from the model vertex to the @@ -574,128 +809,36 @@ Errors buildFrameAttachedToGraph(ScopedGraph &_out, edge.SetWeight(0); // add link vertices - for (const auto &link : _model->Links()) - { - if (outModel.Count(link.Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Link with non-unique name [" + link.Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - outModel.AddVertex(link.Name(), sdf::FrameType::LINK); - } + addVerticesToGraph(outModel, _model.links, _model, errors); // add joint vertices - for (const auto &joint : _model->Joints()) - { - if (outModel.Count(joint.Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Joint with non-unique name [" + joint.Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - outModel.AddVertex(joint.Name(), sdf::FrameType::JOINT); - } + addVerticesToGraph(outModel, _model.joints, _model, errors); // add frame vertices - for (const auto &frame : _model->Frames()) - { - if (outModel.Count(frame.Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Frame with non-unique name [" + frame.Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - outModel.AddVertex(frame.Name(), sdf::FrameType::FRAME); - } + addVerticesToGraph(outModel, _model.frames, _model, errors); // add nested model vertices - for (const auto &nestedIfaceModel : _model->NestedModels()) - { - if (outModel.Count(nestedIfaceModel->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Nested model with non-unique name [" + nestedIfaceModel->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - auto nestedErrors = buildFrameAttachedToGraph(outModel, nestedIfaceModel); - errors.insert(errors.end(), nestedErrors.begin(), nestedErrors.end()); - } + addVerticesToGraph(outModel, _model.models, _model, errors); // add edges from joint to child frames - for (const auto &joint : _model->Joints()) - { - auto jointId = outModel.VertexIdByName(joint.Name()); - const auto &childFrameName = joint.ChildName(); - if (outModel.Count(childFrameName) != 1) - { - errors.push_back({ErrorCode::JOINT_CHILD_LINK_INVALID, - "Child frame with name[" + childFrameName + - "] specified by joint with name[" + joint.Name() + - "] not found in model with name[" + _model->Name() + "]."}); - continue; - } - auto childFrameId = outModel.VertexIdByName(childFrameName); - outModel.AddEdge({jointId, childFrameId}, true); - } + addEdgesToGraph(outModel, _model.joints, _model, errors); // add frame edges - for (const auto &frame : _model->Frames()) - { - auto frameId = outModel.VertexIdByName(frame.Name()); - // look for vertex in graph that matches attached_to value - std::string attachedTo = frame.AttachedTo(); - if (attachedTo.empty()) - { - // if the attached-to name is empty, use the scope context name - attachedTo = scopeContextName; - } - if (outModel.Count(attachedTo) != 1) - { - errors.push_back({ErrorCode::FRAME_ATTACHED_TO_INVALID, - "attached_to name[" + attachedTo + - "] specified by frame with name[" + frame.Name() + - "] does not match a nested model, link, joint, or frame name " - "in model with name[" + _model->Name() + "]."}); - continue; - } - auto attachedToId = outModel.VertexIdByName(attachedTo); - bool edgeData = true; - if (frame.Name() == frame.AttachedTo()) - { - // set edgeData to false if attaches to itself, since this is invalid - edgeData = false; - errors.push_back({ErrorCode::FRAME_ATTACHED_TO_CYCLE, - "attached_to name[" + attachedTo + - "] is identical to frame name[" + frame.Name() + - "], causing a graph cycle " - "in model with name[" + _model->Name() + "]."}); - } - outModel.AddEdge({frameId, attachedToId}, edgeData); - } + addEdgesToGraph(outModel, _model.frames, _model, errors); // identify canonical link, which may be nested - const std::string canonicalLinkName = _model->CanonicalLinkName(); + const std::string canonicalLinkName = _model.canonicalLinkName; const auto canonicalLinkId = outModel.VertexIdByName(canonicalLinkName); - if (!_model->Static()) + if (!_model.isStatic) { if (ignition::math::graph::kNullId == canonicalLinkId) { if (canonicalLinkName.empty()) { - if (_model->NestedModels().size() == 0u) + if (_model.models.size() == 0u) { errors.push_back({ErrorCode::MODEL_WITHOUT_LINK, - "Interface model with name[" + _model->Name() + - "] must have at least one link."}); + "A model must have at least one link."}); } else { @@ -704,15 +847,15 @@ Errors buildFrameAttachedToGraph(ScopedGraph &_out, // first model and let the attached_to frame resolution take care of // finding the canonical link auto firstChildModelId = - outModel.VertexIdByName(_model->NestedModels().front()->Name()); - outModel.AddEdge({modelFrameId, firstChildModelId }, true); + outModel.VertexIdByName(_model.models.front().name); + outModel.AddEdge({modelFrameId, firstChildModelId}, true); } } else { errors.push_back({ErrorCode::MODEL_CANONICAL_LINK_INVALID, "canonical_link with name[" + canonicalLinkName + - "] not found in model with name[" + _model->Name() + "]."}); + "] not found in model with name[" + _model.name + "]."}); } // return early return errors; @@ -726,25 +869,40 @@ Errors buildFrameAttachedToGraph(ScopedGraph &_out, return errors; } - ///////////////////////////////////////////////// Errors buildFrameAttachedToGraph( - ScopedGraph &_out, const World *_world) + ScopedGraph &_out, const Model *_model, bool _isRoot) { - Errors errors; - - if (!_world) + if (!_model) { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid sdf::World pointer."}); - return errors; + return Errors{{ErrorCode::ELEMENT_INVALID, "Invalid sdf::Model pointer."}}; } - else if (!_world->Element()) + else if (!_model->Element()) { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid world element in sdf::World."}); - return errors; + return Errors{ + {ErrorCode::ELEMENT_INVALID, "Invalid model element in sdf::Model."}}; } + return wrapperBuildFrameAttachedToGraph(_out, ModelWrapper(*_model), _isRoot); +} + +///////////////////////////////////////////////// +Errors buildFrameAttachedToGraph(ScopedGraph &_out, + const InterfaceModel *_model) +{ + if (!_model) + { + return Errors{ + {ErrorCode::ELEMENT_INVALID, "Invalid sdf::InterfaceModel pointer."}}; + } + return wrapperBuildFrameAttachedToGraph(_out, ModelWrapper(*_model), false); +} + + +///////////////////////////////////////////////// +Errors buildFrameAttachedToGraph( + ScopedGraph &_out, const WorldWrapper &_world) +{ + Errors errors; // add implicit world frame vertex first const std::string scopeContextName = "world"; @@ -752,117 +910,49 @@ Errors buildFrameAttachedToGraph( "", scopeContextName, scopeContextName, sdf::FrameType::WORLD); // add model vertices - for (uint64_t m = 0; m < _world->ModelCount(); ++m) - { - auto model = _world->ModelByIndex(m); - if (_out.Count(model->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Model with non-unique name [" + model->Name() + - "] detected in world with name [" + _world->Name() + - "]."}); - continue; - } - auto modelErrors = buildFrameAttachedToGraph(_out, model, false); - errors.insert(errors.end(), modelErrors.begin(), modelErrors.end()); - } - - // add interface model vertices - for (uint64_t im = 0; im < _world->InterfaceModelCount(); ++im) - { - auto ifaceModel = _world->InterfaceModelByIndex(im); - if (_out.Count(ifaceModel->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Interface Model with non-unique name [" + ifaceModel->Name() + - "] detected in world with name [" + _world->Name() + - "]."}); - continue; - } - auto modelErrors = buildFrameAttachedToGraph(_out, ifaceModel); - errors.insert(errors.end(), modelErrors.begin(), modelErrors.end()); - } + addVerticesToGraph(_out, _world.models, _world, errors); // add frame vertices - for (uint64_t f = 0; f < _world->FrameCount(); ++f) - { - auto frame = _world->FrameByIndex(f); - if (_out.Count(frame->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Frame with non-unique name [" + frame->Name() + - "] detected in world with name [" + _world->Name() + - "]."}); - continue; - } - _out.AddVertex(frame->Name(), sdf::FrameType::FRAME).Id(); - } + addVerticesToGraph(_out, _world.frames, _world, errors); // add frame edges - for (uint64_t f = 0; f < _world->FrameCount(); ++f) - { - auto frame = _world->FrameByIndex(f); - auto frameId = _out.VertexIdByName(frame->Name()); - // look for vertex in graph that matches attached_to value - std::string attachedTo = frame->AttachedTo(); - if (attachedTo.empty()) - { - // if the attached-to name is empty, use the scope context name - attachedTo = scopeContextName; - if (_out.Count(scopeContextName) != 1) - { - errors.push_back({ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR, - "FrameAttachedToGraph error: scope frame[" + - scopeContextName + "] not found in map."}); - continue; - } - } - if (_out.Count(attachedTo) != 1) - { - errors.push_back({ErrorCode::FRAME_ATTACHED_TO_INVALID, - "attached_to name[" + attachedTo + - "] specified by frame with name[" + frame->Name() + - "] does not match a model or frame name " - "in world with name[" + _world->Name() + "]."}); - continue; - } - auto attachedToId = _out.VertexIdByName(attachedTo); - bool edgeData = true; - if (frame->Name() == frame->AttachedTo()) - { - // set edgeData to false if attaches to itself, since this is invalid - edgeData = false; - errors.push_back({ErrorCode::FRAME_ATTACHED_TO_CYCLE, - "attached_to name[" + attachedTo + - "] is identical to frame name[" + frame->Name() + - "], causing a graph cycle " - "in world with name[" + _world->Name() + "]."}); - } - _out.AddEdge({frameId, attachedToId}, edgeData); - } + addEdgesToGraph(_out, _world.frames, _world, errors); return errors; } ///////////////////////////////////////////////// -Errors buildPoseRelativeToGraph( - ScopedGraph &_out, const Model *_model, bool _isRoot) +Errors buildFrameAttachedToGraph( + ScopedGraph &_out, const World *_world) { - Errors errors; - - if (!_model) + if (!_world) { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid sdf::Model pointer."}); - return errors; + return Errors{{ErrorCode::ELEMENT_INVALID, "Invalid sdf::World pointer."}}; } - else if (!_model->Element()) + else if (!_world->Element()) { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid model element in sdf::Model."}); - return errors; + return Errors{ + {ErrorCode::ELEMENT_INVALID, "Invalid world element in sdf::World."}}; } + return buildFrameAttachedToGraph(_out, WorldWrapper(*_world)); +} + +///////////////////////////////////////////////// +/// \brief Helper function that actually builds the PoseRelativeToGraph given a +/// wrapped Model or Interface model. +/// \param[out] _out Graph object to write. +/// \param[in] _model Wrapped Model or Interface model from which to build +/// relative_to graph. +/// \param[in] _isRoot True if the model is a standalone model, i.e, +/// //sdf/model. This is not relevant if the _model is a wrapped Interface +/// Model. +/// \return Errors. +Errors wrapperBuildPoseRelativeToGraph(ScopedGraph &_out, + const ModelWrapper &_model, bool _isRoot) +{ + Errors errors; + const std::string scopeContextName = "__model__"; auto rootId = ignition::math::graph::kNullId; // add the model frame vertex first @@ -872,8 +962,8 @@ Errors buildPoseRelativeToGraph( "", "__root__", scopeContextName, sdf::FrameType::MODEL); rootId = _out.ScopeVertexId(); } - auto modelId = _out.AddVertex(_model->Name(), sdf::FrameType::MODEL).Id(); - auto outModel = _out.AddScopeVertex(_model->Name(), scopeContextName, + auto modelId = _out.AddVertex(_model.name, sdf::FrameType::MODEL).Id(); + auto outModel = _out.AddScopeVertex(_model.name, scopeContextName, scopeContextName, sdf::FrameType::MODEL); auto modelFrameId = outModel.ScopeVertexId(); @@ -884,311 +974,32 @@ Errors buildPoseRelativeToGraph( // Set the edge weight to 0 to indicate that this is an aliasing edge. edge.SetWeight(0); - // add link vertices and default edge if relative_to is empty - for (uint64_t l = 0; l < _model->LinkCount(); ++l) - { - auto link = _model->LinkByIndex(l); - if (outModel.Count(link->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Link with non-unique name [" + link->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - auto linkId = - outModel.AddVertex(link->Name(), sdf::FrameType::LINK).Id(); - - if (link->PoseRelativeTo().empty()) - { - // relative_to is empty, so add edge from implicit model frame to link - outModel.AddEdge({modelFrameId, linkId}, link->RawPose()); - } - } + // add link vertices + addVerticesToGraph(outModel, _model.links, _model, errors); // add joint vertices - for (uint64_t j = 0; j < _model->JointCount(); ++j) - { - auto joint = _model->JointByIndex(j); - if (outModel.Count(joint->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Joint with non-unique name [" + joint->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - outModel.AddVertex(joint->Name(), sdf::FrameType::JOINT).Id(); - } + addVerticesToGraph(outModel, _model.joints, _model, errors); - // add frame vertices and default edge if both - // relative_to and attached_to are empty - for (uint64_t f = 0; f < _model->FrameCount(); ++f) - { - auto frame = _model->FrameByIndex(f); - if (outModel.Count(frame->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Frame with non-unique name [" + frame->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - auto frameId = - outModel.AddVertex(frame->Name(), sdf::FrameType::FRAME).Id(); - - if (frame->PoseRelativeTo().empty() && frame->AttachedTo().empty()) - { - // add edge from implicit model frame to frame - outModel.AddEdge({modelFrameId, frameId}, frame->RawPose()); - } - } + // add frame vertices + addVerticesToGraph(outModel, _model.frames, _model, errors); // add nested model vertices - for (uint64_t m = 0; m < _model->ModelCount(); ++m) - { - auto nestedModel = _model->ModelByIndex(m); - if (outModel.Count(nestedModel->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Nested model with non-unique name [" + nestedModel->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - - auto nestedErrors = buildPoseRelativeToGraph(outModel, nestedModel, false); - errors.insert(errors.end(), nestedErrors.begin(), nestedErrors.end()); - } - - // add nested interface model vertices - for (uint64_t m = 0; m < _model->InterfaceModelCount(); ++m) - { - auto ifaceModel = _model->InterfaceModelByIndex(m); - if (outModel.Count(ifaceModel->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Nested model with non-unique name [" + ifaceModel->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - - auto nestedErrors = buildPoseRelativeToGraph(outModel, ifaceModel); - errors.insert(errors.end(), nestedErrors.begin(), nestedErrors.end()); - } + addVerticesToGraph(outModel, _model.models, _model, errors); // now that all vertices have been added to the graph, // add the edges that reference other vertices - for (uint64_t l = 0; l < _model->LinkCount(); ++l) - { - auto link = _model->LinkByIndex(l); - - // check if we've already added a default edge - const std::string &relativeTo = link->PoseRelativeTo(); - if (relativeTo.empty()) - { - continue; - } - - auto linkId = outModel.VertexIdByName(link->Name()); - - // look for vertex in graph that matches relative_to value - if (outModel.Count(relativeTo) != 1) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_INVALID, - "relative_to name[" + relativeTo + - "] specified by link with name[" + link->Name() + - "] does not match a nested model, link, joint, or frame name " - "in model with name[" + _model->Name() + "]."}); - continue; - } - auto relativeToId = outModel.VertexIdByName(relativeTo); - if (link->Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to link name[" + link->Name() + - "], causing a graph cycle " - "in model with name[" + _model->Name() + "]."}); - } - outModel.AddEdge({relativeToId, linkId}, link->RawPose()); - } - - for (uint64_t j = 0; j < _model->JointCount(); ++j) - { - auto joint = _model->JointByIndex(j); - - std::string relativeTo = joint->PoseRelativeTo(); - if (relativeTo.empty()) - { - // since nothing else was specified, use the joint's child frame - relativeTo = joint->ChildLinkName(); - } - - auto jointId = outModel.VertexIdByName(joint->Name()); - - // look for vertex in graph that matches relative_to value - if (outModel.Count(relativeTo) != 1) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_INVALID, - "relative_to name[" + relativeTo + - "] specified by joint with name[" + joint->Name() + - "] does not match a nested model, link, joint, or frame name " - "in model with name[" + _model->Name() + "]."}); - continue; - } - auto relativeToId = outModel.VertexIdByName(relativeTo); - if (joint->Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to joint name[" + joint->Name() + - "], causing a graph cycle " - "in model with name[" + _model->Name() + "]."}); - } - outModel.AddEdge({relativeToId, jointId}, joint->RawPose()); - } - - for (uint64_t f = 0; f < _model->FrameCount(); ++f) - { - auto frame = _model->FrameByIndex(f); - - // check if we've already added a default edge - if (frame->PoseRelativeTo().empty() && frame->AttachedTo().empty()) - { - continue; - } - - auto frameId = outModel.VertexIdByName(frame->Name()); - std::string relativeTo; - std::string typeForErrorMsg; - ErrorCode errorCode; - if (!frame->PoseRelativeTo().empty()) - { - relativeTo = frame->PoseRelativeTo(); - typeForErrorMsg = "relative_to"; - errorCode = ErrorCode::POSE_RELATIVE_TO_INVALID; - } - else - { - relativeTo = frame->AttachedTo(); - typeForErrorMsg = "attached_to"; - errorCode = ErrorCode::FRAME_ATTACHED_TO_INVALID; - } - - // look for vertex in graph that matches relative_to value - if (outModel.Count(relativeTo) != 1) - { - errors.push_back({errorCode, - typeForErrorMsg + " name[" + relativeTo + - "] specified by frame with name[" + frame->Name() + - "] does not match a nested model, link, joint, or frame name " - "in model with name[" + _model->Name() + "]."}); - continue; - } - auto relativeToId = outModel.VertexIdByName(relativeTo); - if (frame->Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to frame name[" + frame->Name() + - "], causing a graph cycle " - "in model with name[" + _model->Name() + "]."}); - } - outModel.AddEdge({relativeToId, frameId}, frame->RawPose()); - } - - for (uint64_t m = 0; m < _model->ModelCount(); ++m) - { - auto nestedModel = _model->ModelByIndex(m); - - auto nestedModelId = outModel.VertexIdByName(nestedModel->Name()); - // if relative_to is empty, add edge from implicit model frame to - // nestedModel - auto relativeToId = modelFrameId; - - const std::string &relativeTo = nestedModel->PoseRelativeTo(); - if (!relativeTo.empty()) - { - // look for vertex in graph that matches relative_to value - if (outModel.Count(relativeTo) != 1) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_INVALID, - "relative_to name[" + relativeTo + - "] specified by nested model with name[" + nestedModel->Name() + - "] does not match a nested model, link, joint, or frame name " - "in model with name[" + _model->Name() + "]."}); - continue; - } - - relativeToId = outModel.VertexIdByName(relativeTo); - if (nestedModel->Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to nested model name[" + nestedModel->Name() + - "], causing a graph cycle " - "in model with name[" + _model->Name() + "]."}); - } - } - - ignition::math::Pose3d resolvedModelPose = nestedModel->RawPose(); - sdf::Errors resolveErrors = resolveModelPoseWithPlacementFrame( - nestedModel->RawPose(), nestedModel->PlacementFrameName(), - outModel.ChildModelScope(nestedModel->Name()), resolvedModelPose); - errors.insert(errors.end(), resolveErrors.begin(), resolveErrors.end()); - - outModel.AddEdge({relativeToId, nestedModelId}, resolvedModelPose); - } - for (uint64_t m = 0; m < _model->InterfaceModelCount(); ++m) - { - auto ifaceModel = _model->InterfaceModelByIndex(m); - const auto *nestedInclude = _model->InterfaceModelNestedIncludeByIndex(m); - - auto nestedModelId = outModel.VertexIdByName(ifaceModel->Name()); - // if relative_to is empty, add edge from implicit model frame to - // nestedModel - auto relativeToId = modelFrameId; - - const std::string &relativeTo = - nestedInclude->IncludePoseRelativeTo().value_or(""); - if (!relativeTo.empty()) - { - // look for vertex in graph that matches relative_to value - if (outModel.Count(relativeTo) != 1) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_INVALID, - "relative_to name[" + relativeTo + - "] specified by nested model with name[" + ifaceModel->Name() + - "] does not match a nested model, link, joint, or frame name " - "in model with name[" + _model->Name() + "]."}); - continue; - } - - relativeToId = outModel.VertexIdByName(relativeTo); - if (ifaceModel->Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to nested model name[" + ifaceModel->Name() + - "], causing a graph cycle " - "in model with name[" + _model->Name() + "]."}); - } - } + // add link edges + addEdgesToGraph(outModel, _model.links, _model, errors); - ignition::math::Pose3d resolvedModelPose = - nestedInclude->IncludeRawPose().value_or(ignition::math::Pose3d()); + // add joint edges + addEdgesToGraph(outModel, _model.joints, _model, errors); - sdf::Errors resolveErrors = resolveModelPoseWithPlacementFrame( - nestedInclude->IncludeRawPose().value_or(ignition::math::Pose3d()), - nestedInclude->PlacementFrame().value_or(""), - outModel.ChildModelScope(ifaceModel->Name()), resolvedModelPose); - errors.insert(errors.end(), resolveErrors.begin(), resolveErrors.end()); + // add frame edges + addEdgesToGraph(outModel, _model.frames, _model, errors); - outModel.AddEdge({relativeToId, nestedModelId}, resolvedModelPose); - } + // add nested model edges + addEdgesToGraph(outModel, _model.models, _model, errors); if (_isRoot) { @@ -1197,199 +1008,51 @@ Errors buildPoseRelativeToGraph( // sdf::resolvePoseRelativeToRoot. We will later update the edge after the // pose is calculated. auto rootToModel = outModel.AddEdge({rootId, modelId}, {}); - ignition::math::Pose3d resolvedModelPose = _model->RawPose(); + ignition::math::Pose3d resolvedModelPose = _model.rawPose; sdf::Errors resolveErrors = - resolveModelPoseWithPlacementFrame(_model->RawPose(), - _model->PlacementFrameName(), outModel, resolvedModelPose); + resolveModelPoseWithPlacementFrame(_model.rawPose, + _model.placementFrameName, outModel, resolvedModelPose); errors.insert(errors.end(), resolveErrors.begin(), resolveErrors.end()); outModel.UpdateEdge(rootToModel, resolvedModelPose); } return errors; } - ///////////////////////////////////////////////// -Errors buildPoseRelativeToGraph(ScopedGraph &_out, - InterfaceModelConstPtr _model) +Errors buildPoseRelativeToGraph( + ScopedGraph &_out, const Model *_model, bool _isRoot) { - Errors errors; - if (!_model) { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid sdf::Model pointer."}); - return errors; - } - - const std::string scopeContextName = "__model__"; - // add the model frame vertex first - auto modelId = _out.AddVertex(_model->Name(), sdf::FrameType::MODEL).Id(); - auto outModel = _out.AddScopeVertex(_model->Name(), scopeContextName, - scopeContextName, sdf::FrameType::MODEL); - auto modelFrameId = outModel.ScopeVertexId(); - - // Add an aliasing edge from the model vertex to the - // corresponding vertex in the PoseRelativeTo graph of the child model, - // i.e, to the ::__model__ vertex. - auto &edge = _out.AddEdge({modelId, modelFrameId}, {}); - // Set the edge weight to 0 to indicate that this is an aliasing edge. - edge.SetWeight(0); - - // add link vertices and default edge if relative_to is empty - for (const auto &link : _model->Links()) - { - if (outModel.Count(link.Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Link with non-unique name [" + link.Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - auto linkId = - outModel.AddVertex(link.Name(), sdf::FrameType::LINK).Id(); - - // relative_to is empty, so add edge from implicit model frame to link - outModel.AddEdge({modelFrameId, linkId}, link.PoseInModelFrame()); - } - - // add joint vertices - for (const auto &joint : _model->Joints()) - { - if (outModel.Count(joint.Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Joint with non-unique name [" + joint.Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - outModel.AddVertex(joint.Name(), sdf::FrameType::JOINT); - } - - // add frame vertices and default edge if both - // relative_to and attached_to are empty - for (const auto &frame : _model->Frames()) - { - if (outModel.Count(frame.Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Frame with non-unique name [" + frame.Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - auto frameId = outModel.AddVertex(frame.Name(), sdf::FrameType::FRAME).Id(); - if (frame.AttachedTo().empty()) - { - // add edge from implicit model frame to frame - outModel.AddEdge({modelFrameId, frameId}, frame.PoseInAttachedToFrame()); - } + return Errors{{ErrorCode::ELEMENT_INVALID, "Invalid sdf::Model pointer."}}; } - - // add nested model vertices and default edge if relative_to is empty - for (const auto &nestedIfaceModel : _model->NestedModels()) + else if (!_model->Element()) { - if (outModel.Count(nestedIfaceModel->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Nested model with non-unique name [" + nestedIfaceModel->Name() + - "] detected in model with name [" + _model->Name() + - "]."}); - continue; - } - - auto nestedErrors = buildPoseRelativeToGraph(outModel, nestedIfaceModel); - errors.insert(errors.end(), nestedErrors.begin(), nestedErrors.end()); - auto nestedModelId = outModel.VertexIdByName(nestedIfaceModel->Name()); - outModel.AddEdge({modelFrameId, nestedModelId}, - nestedIfaceModel->ModelFramePoseInParentFrame()); + return Errors{ + {ErrorCode::ELEMENT_INVALID, "Invalid model element in sdf::Model."}}; } - for (const auto &joint : _model->Joints()) - { - const std::string &relativeTo = joint.ChildName(); - auto jointId = outModel.VertexIdByName(joint.Name()); - - // look for vertex in graph that matches relative_to value - if (outModel.Count(relativeTo) != 1) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_INVALID, - "relative_to name[" + relativeTo + - "] specified by joint with name[" + joint.Name() + - "] does not match a nested model, link, joint, or frame name " - "in model with name[" + _model->Name() + "]."}); - continue; - } - auto relativeToId = outModel.VertexIdByName(relativeTo); - if (joint.Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to joint name[" + joint.Name() + - "], causing a graph cycle " - "in model with name[" + _model->Name() + "]."}); - } - outModel.AddEdge({relativeToId, jointId}, joint.PoseInChildFrame()); - } + return wrapperBuildPoseRelativeToGraph(_out, ModelWrapper(*_model), _isRoot); +} - for (const auto &frame : _model->Frames()) +///////////////////////////////////////////////// +Errors buildPoseRelativeToGraph(ScopedGraph &_out, + const InterfaceModel *_model) +{ + if (!_model) { - if (frame.AttachedTo().empty()) - { - continue; - } - auto frameId = outModel.VertexIdByName(frame.Name()); - std::string relativeTo; - std::string typeForErrorMsg; - ErrorCode errorCode; - relativeTo = frame.AttachedTo(); - typeForErrorMsg = "attached_to"; - errorCode = ErrorCode::FRAME_ATTACHED_TO_INVALID; - - // look for vertex in graph that matches relative_to value - if (outModel.Count(relativeTo) != 1) - { - errors.push_back({errorCode, - "attached_to name[" + relativeTo + - "] specified by frame with name[" + frame.Name() + - "] does not match a nested model, link, joint, or frame name " - "in model with name[" + _model->Name() + "]."}); - continue; - } - auto relativeToId = outModel.VertexIdByName(relativeTo); - if (frame.Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to frame name[" + frame.Name() + - "], causing a graph cycle " - "in model with name[" + _model->Name() + "]."}); - } - outModel.AddEdge({relativeToId, frameId}, frame.PoseInAttachedToFrame()); + return Errors{ + {ErrorCode::ELEMENT_INVALID, "Invalid sdf::InterfaceModel pointer."}}; } - - return errors; + return wrapperBuildPoseRelativeToGraph(_out, ModelWrapper(*_model), false); } ///////////////////////////////////////////////// -Errors buildPoseRelativeToGraph( - ScopedGraph &_out, const World *_world) +Errors wrapperBuildPoseRelativeToGraph( + ScopedGraph &_out, const WorldWrapper &_world) { Errors errors; - if (!_world) - { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid sdf::World pointer."}); - return errors; - } - else if (!_world->Element()) - { - errors.push_back({ErrorCode::ELEMENT_INVALID, - "Invalid world element in sdf::World."}); - return errors; - } // add implicit world frame vertex first const std::string scopeContextName = "world"; @@ -1403,206 +1066,36 @@ Errors buildPoseRelativeToGraph( _out.AddEdge({rootId, worldFrameId}, {}); // add model vertices - for (uint64_t m = 0; m < _world->ModelCount(); ++m) - { - auto model = _world->ModelByIndex(m); - if (_out.Count(model->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Model with non-unique name [" + model->Name() + - "] detected in world with name [" + _world->Name() + - "]."}); - continue; - } - - auto modelErrors = buildPoseRelativeToGraph(_out , model, false); - errors.insert(errors.end(), modelErrors.begin(), modelErrors.end()); - } - - for (uint64_t m = 0; m < _world->InterfaceModelCount(); ++m) - { - auto ifaceModel = _world->InterfaceModelByIndex(m); - if (_out.Count(ifaceModel->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Model with non-unique name [" + ifaceModel->Name() + - "] detected in world with name [" + _world->Name() + - "]."}); - continue; - } + addVerticesToGraph(_out, _world.models, _world, errors); - auto modelErrors = - buildPoseRelativeToGraph(_out, ifaceModel); - errors.insert(errors.end(), modelErrors.begin(), modelErrors.end()); - } - - // add frame vertices and default edge if both - // relative_to and attached_to are empty - for (uint64_t f = 0; f < _world->FrameCount(); ++f) - { - auto frame = _world->FrameByIndex(f); - if (_out.Count(frame->Name()) > 0) - { - errors.push_back({ErrorCode::DUPLICATE_NAME, - "Frame with non-unique name [" + frame->Name() + - "] detected in world with name [" + _world->Name() + - "]."}); - continue; - } - auto frameId = - _out.AddVertex(frame->Name(), sdf::FrameType::FRAME).Id(); - - if (frame->PoseRelativeTo().empty() && frame->AttachedTo().empty()) - { - // add edge from implicit world frame to frame - _out.AddEdge({worldFrameId, frameId}, frame->RawPose()); - } - } + // add frame vertices + addVerticesToGraph(_out, _world.frames, _world, errors); // now that all vertices have been added to the graph, // add the edges that reference other vertices + // add model edges + addEdgesToGraph(_out, _world.models, _world, errors); - for (uint64_t m = 0; m < _world->ModelCount(); ++m) - { - auto model = _world->ModelByIndex(m); - - auto modelId = _out.VertexIdByName(model->Name()); - // if relative_to is empty, add edge from implicit model frame to - // world - auto relativeToId = worldFrameId; - - const std::string &relativeTo = model->PoseRelativeTo(); - if (!relativeTo.empty()) - { - // look for vertex in graph that matches relative_to value - if (_out.Count(relativeTo) != 1) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_INVALID, - "relative_to name[" + relativeTo + - "] specified by model with name[" + model->Name() + - "] does not match a model or frame name " - "in world with name[" + _world->Name() + "]."}); - continue; - } - - relativeToId = _out.VertexIdByName(relativeTo); - if (model->Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to model name[" + model->Name() + - "], causing a graph cycle " - "in world with name[" + _world->Name() + "]."}); - } - } - - ignition::math::Pose3d resolvedModelPose = model->RawPose(); - sdf::Errors resolveErrors = resolveModelPoseWithPlacementFrame( - model->RawPose(), model->PlacementFrameName(), - _out.ChildModelScope(model->Name()), resolvedModelPose); - errors.insert(errors.end(), resolveErrors.begin(), resolveErrors.end()); + // add frame edges + addEdgesToGraph(_out, _world.frames, _world, errors); - _out.AddEdge({relativeToId, modelId}, resolvedModelPose); - } + return errors; +} - for (uint64_t m = 0; m < _world->InterfaceModelCount(); ++m) +///////////////////////////////////////////////// +Errors buildPoseRelativeToGraph( + ScopedGraph &_out, const World *_world) +{ + if (!_world) { - auto ifaceModel = _world->InterfaceModelByIndex(m); - const auto *nestedInclude = _world->InterfaceModelNestedIncludeByIndex(m); - - auto modelId = _out.VertexIdByName(ifaceModel->Name()); - // if relative_to is empty, add edge from implicit model frame to - // world - auto relativeToId = worldFrameId; - - const std::string &relativeTo = - nestedInclude->IncludePoseRelativeTo().value_or(""); - if (!relativeTo.empty()) - { - // look for vertex in graph that matches relative_to value - if (_out.Count(relativeTo) != 1) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_INVALID, - "relative_to name[" + relativeTo + - "] specified by interface model with name[" + ifaceModel->Name() + - "] does not match a model or frame name " - "in world with name[" + _world->Name() + "]."}); - continue; - } - - relativeToId = _out.VertexIdByName(relativeTo); - if (ifaceModel->Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to interface model name[" + ifaceModel->Name() + - "], causing a graph cycle " - "in world with name[" + _world->Name() + "]."}); - } - } - - ignition::math::Pose3d resolvedModelPose = - nestedInclude->IncludeRawPose().value_or(ignition::math::Pose3d()); - - sdf::Errors resolveErrors = resolveModelPoseWithPlacementFrame( - nestedInclude->IncludeRawPose().value_or(ignition::math::Pose3d()), - nestedInclude->PlacementFrame().value_or(""), - _out.ChildModelScope(ifaceModel->Name()), resolvedModelPose); - errors.insert(errors.end(), resolveErrors.begin(), resolveErrors.end()); - - _out.AddEdge({relativeToId, modelId}, resolvedModelPose); + return Errors{{ErrorCode::ELEMENT_INVALID, "Invalid sdf::World pointer."}}; } - - for (uint64_t f = 0; f < _world->FrameCount(); ++f) + else if (!_world->Element()) { - auto frame = _world->FrameByIndex(f); - - // check if we've already added a default edge - if (frame->PoseRelativeTo().empty() && frame->AttachedTo().empty()) - { - continue; - } - - auto frameId = _out.VertexIdByName(frame->Name()); - std::string relativeTo; - std::string typeForErrorMsg; - ErrorCode errorCode; - if (!frame->PoseRelativeTo().empty()) - { - relativeTo = frame->PoseRelativeTo(); - typeForErrorMsg = "relative_to"; - errorCode = ErrorCode::POSE_RELATIVE_TO_INVALID; - } - else - { - relativeTo = frame->AttachedTo(); - typeForErrorMsg = "attached_to"; - errorCode = ErrorCode::FRAME_ATTACHED_TO_INVALID; - } - - // look for vertex in graph that matches relative_to value - if (_out.Count(relativeTo) != 1) - { - errors.push_back({errorCode, - typeForErrorMsg + " name[" + relativeTo + - "] specified by frame with name[" + frame->Name() + - "] does not match a model or frame name " - "in world with name[" + _world->Name() + "]."}); - continue; - } - auto relativeToId = _out.VertexIdByName(relativeTo); - if (frame->Name() == relativeTo) - { - errors.push_back({ErrorCode::POSE_RELATIVE_TO_CYCLE, - "relative_to name[" + relativeTo + - "] is identical to frame name[" + frame->Name() + - "], causing a graph cycle " - "in world with name[" + _world->Name() + "]."}); - } - _out.AddEdge({relativeToId, frameId}, frame->RawPose()); + return Errors{ + {ErrorCode::ELEMENT_INVALID, "Invalid world element in sdf::World."}}; } - - return errors; + return wrapperBuildPoseRelativeToGraph(_out, WorldWrapper(*_world)); } ///////////////////////////////////////////////// diff --git a/src/ign_TEST.cc b/src/ign_TEST.cc index 50e387d7d..249cecd3b 100644 --- a/src/ign_TEST.cc +++ b/src/ign_TEST.cc @@ -981,10 +981,10 @@ TEST(GraphCmd, IGN_UTILS_TEST_DISABLED_ON_WIN32(WorldPoseRelativeTo)) << " 16 [label=\"F7 (16)\"];\n" << " 0 -> 1 [label=1];\n" << " 2 -> 3 [label=0];\n" - << " 3 -> 4 [label=1];\n" - << " 3 -> 5 [label=1];\n" << " 8 -> 9 [label=0];\n" << " 9 -> 10 [label=1];\n" + << " 3 -> 4 [label=1];\n" + << " 3 -> 5 [label=1];\n" << " 5 -> 6 [label=1];\n" << " 5 -> 7 [label=1];\n" << " 3 -> 8 [label=1];\n" @@ -1041,12 +1041,11 @@ TEST(GraphCmd, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelPoseRelativeTo)) << " 29 [label=\"parent_model::M7::__model__ (29)\"];\n" << " 30 [label=\"parent_model::M7::L (30)\"];\n" << " 1 -> 2 [label=0];\n" - << " 2 -> 3 [label=1];\n" << " 4 -> 5 [label=0];\n" - << " 5 -> 6 [label=1];\n" - << " 5 -> 7 [label=1];\n" << " 10 -> 11 [label=0];\n" << " 11 -> 12 [label=1];\n" + << " 5 -> 6 [label=1];\n" + << " 5 -> 7 [label=1];\n" << " 7 -> 8 [label=1];\n" << " 7 -> 9 [label=1];\n" << " 5 -> 10 [label=1];\n" @@ -1062,6 +1061,7 @@ TEST(GraphCmd, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelPoseRelativeTo)) << " 26 -> 27 [label=1];\n" << " 28 -> 29 [label=0];\n" << " 29 -> 30 [label=1];\n" + << " 2 -> 3 [label=1];\n" << " 2 -> 4 [label=1];\n" << " 4 -> 13 [label=1];\n" << " 6 -> 16 [label=1];\n" diff --git a/test/integration/frame.cc b/test/integration/frame.cc index 90b15be93..ec2d112fc 100644 --- a/test/integration/frame.cc +++ b/test/integration/frame.cc @@ -489,7 +489,7 @@ TEST(DOMFrame, LoadModelFramesInvalidAttachedTo) for (auto e : errors) std::cout << e << std::endl; EXPECT_FALSE(errors.empty()); - EXPECT_EQ(10u, errors.size()); + ASSERT_EQ(10u, errors.size()); EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_INVALID); EXPECT_NE(std::string::npos, errors[0].Message().find( @@ -745,7 +745,7 @@ TEST(DOMFrame, LoadWorldFramesInvalidAttachedTo) for (auto e : errors) std::cout << e << std::endl; EXPECT_FALSE(errors.empty()); - EXPECT_EQ(11u, errors.size()); + ASSERT_EQ(11u, errors.size()); EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_INVALID); EXPECT_NE(std::string::npos, errors[0].Message().find( diff --git a/test/integration/interface_api.cc b/test/integration/interface_api.cc index badda1669..a250f5cef 100644 --- a/test/integration/interface_api.cc +++ b/test/integration/interface_api.cc @@ -269,7 +269,7 @@ TEST_F(InterfaceAPI, CustomParserPrecedence) this->config.RegisterCustomModelParser(createCustomParser(3)); sdf::Root root; sdf::Errors errors = root.LoadSdfString(testSdf, this->config); - EXPECT_TRUE(errors.empty()); + EXPECT_TRUE(errors.empty()) << errors; // Check that custom parsers are called in reverse order of registration. ASSERT_EQ(3u, customParserCallOrder.size()); // Parser 0 will not be visited because parser 1 will be successful. From 5e91938c45838714cf0a8a08255d97e2ffb36e25 Mon Sep 17 00:00:00 2001 From: Aaron Chong Date: Tue, 21 Dec 2021 19:36:59 +0800 Subject: [PATCH 18/28] Support printing sdf poses in degrees and allow snapping to commonly used angles (#689) * Ruby option to print in_degrees or snap_to_degrees Signed-off-by: Aaron Chong * Basic PrintConfig added Signed-off-by: Aaron Chong * PrintConfig gets passed into printing implementations of Element and Param Signed-off-by: Aaron Chong * Adding basic test for print options Signed-off-by: Aaron Chong * Reverting to PrintConfig with basic API Signed-off-by: Aaron Chong * Moved creation of PrintConfig into ign functions Signed-off-by: Aaron Chong * Param value GetPoseAsString and tests Signed-off-by: Aaron Chong * Moved attribute painting to its own function, fixed test strings Signed-off-by: Aaron Chong * Added basic tests for pose rotation input as quaternions Signed-off-by: Aaron Chong * Using different flags for ign sdf -p, allow snapping to different values Signed-off-by: Aaron Chong * Disabling test on windows, fixing comment Signed-off-by: Aaron Chong * Remove stale function, fixed linting Signed-off-by: Aaron Chong * Adding tolerance as a argument, added tests Signed-off-by: Aaron Chong * Use 3 spaces when changing rotation formats or snapping to degrees Signed-off-by: Aaron Chong * Added check for tolerance larger than snapping interval Signed-off-by: Aaron Chong * Moving PrintAttributes to ElementPrivate to remain ABI stability Signed-off-by: Aaron Chong * Using true/false instead of 1/0 Signed-off-by: Aaron Chong * Remove use of SDF_ASSERT in GetAsString Signed-off-by: Aaron Chong * Added tests for //include/pose Signed-off-by: Aaron Chong * Adding parsing passing test for empty quat_xyzw pose Signed-off-by: Aaron Chong * Added check for default string values to be modified when rotation_format is defined Signed-off-by: Aaron Chong * Added tests Signed-off-by: Aaron Chong * Reparsing translates default value into string to be used if values have not been assigned to param Signed-off-by: Aaron Chong * Using StringFromValueImpl for getting strings from all ParamVariants Signed-off-by: Aaron Chong * Refactor pose string from value into its own function Signed-off-by: Aaron Chong * Fixing casting erroerror, added documentation and tests for tolerance < interval Signed-off-by: Aaron Chong * Correcting stale comments Signed-off-by: Aaron Chong * Fixing snapToInterval math, added more tests Signed-off-by: Aaron Chong * Removed unneeded visibility macro Signed-off-by: Aaron Chong * Adding return documentation and using const reference to variant instead of pointer Signed-off-by: Aaron Chong * Returning string directly, removing stale _config, reverting strValue to nullopt Signed-off-by: Aaron Chong * Remove use of assertions Signed-off-by: Aaron Chong * Suggested changes to #729 (#748) Signed-off-by: Addisu Z. Taddese * Using three space delimiter between position and rotation if attributes are set Signed-off-by: Aaron Chong * Added comment regarding use of default PrintConfig in Reparse Signed-off-by: Aaron Chong * Adding equality comparison for PrintConfig Signed-off-by: Aaron Chong * Removed stale include Signed-off-by: Aaron Chong * Uniied string and value parsing behavior, and modified necessary tests Signed-off-by: Aaron Chong * Overloaded function to maintain ABI stability Signed-off-by: Aaron Chong * Fixing missing space in test for exec command Signed-off-by: Aaron Chong * Adding comment regarding attributeExceptions Signed-off-by: Aaron Chong * Indenting help message, adding test for shuffling command flags Signed-off-by: Aaron Chong * Modifying cmd flag shuffling test to handling flags with arguments too Signed-off-by: Aaron Chong * Removed Get from PrintConfig getter functions Signed-off-by: Aaron Chong * Using std optional's converting constructor Signed-off-by: Aaron Chong * Modified snapToInterval implementation, added test Signed-off-by: Aaron Chong * Added bool type specific value parser, values are parsed using ParamStreamer by default Signed-off-by: Aaron Chong * Reverting all unnecessary changes made in sdf12 to old tests Signed-off-by: Aaron Chong * Added comparison for PreserveIncludes Signed-off-by: Aaron Chong * Check for 'type' attribute in unknown elements as well, in order to parse booleans into true/false, instead of 1/0 Signed-off-by: Aaron Chong * Only checking for pose related PrintConfig options for returning string instead of default PrintConfig Signed-off-by: Aaron Chong * Added comment regarding sanitizing -0 in test outputs Signed-off-by: Aaron Chong Co-authored-by: Addisu Z. Taddese --- include/sdf/Element.hh | 12 +- include/sdf/Param.hh | 33 +- include/sdf/PrintConfig.hh | 40 +- src/CMakeLists.txt | 2 +- src/Element.cc | 62 +- src/Param.cc | 171 ++++- src/Plugin_TEST.cc | 2 +- src/PrintConfig.cc | 76 ++- src/PrintConfig_TEST.cc | 75 +++ src/cmd/cmdsdformat.rb.in | 48 +- src/ign.cc | 17 +- src/ign_TEST.cc | 625 ++++++++++++++++++ src/parser.cc | 22 +- test/integration/default_elements.cc | 36 +- .../include_custom_model_expected_output.sdf | 10 +- ...de_custom_nested_model_expected_output.sdf | 52 +- test/integration/pose_1_9_sdf.cc | 26 +- test/integration/print_config.cc | 3 + test/sdf/includes_rotations_in_degrees.sdf | 12 + .../sdf/includes_rotations_in_quaternions.sdf | 14 + test/sdf/includes_rotations_in_radians.sdf | 12 + test/sdf/rotations_in_degrees.sdf | 8 + ...tations_in_degrees_high_snap_tolerance.sdf | 8 + test/sdf/rotations_in_quaternions.sdf | 10 + test/sdf/rotations_in_radians.sdf | 8 + .../sdf/rotations_in_unnormalized_degrees.sdf | 8 + .../sdf/rotations_in_unnormalized_radians.sdf | 8 + 27 files changed, 1262 insertions(+), 138 deletions(-) create mode 100644 test/sdf/includes_rotations_in_degrees.sdf create mode 100644 test/sdf/includes_rotations_in_quaternions.sdf create mode 100644 test/sdf/includes_rotations_in_radians.sdf create mode 100644 test/sdf/rotations_in_degrees.sdf create mode 100644 test/sdf/rotations_in_degrees_high_snap_tolerance.sdf create mode 100644 test/sdf/rotations_in_quaternions.sdf create mode 100644 test/sdf/rotations_in_radians.sdf create mode 100644 test/sdf/rotations_in_unnormalized_degrees.sdf create mode 100644 test/sdf/rotations_in_unnormalized_radians.sdf diff --git a/include/sdf/Element.hh b/include/sdf/Element.hh index 99cc471c8..52ce5f7cb 100644 --- a/include/sdf/Element.hh +++ b/include/sdf/Element.hh @@ -199,7 +199,7 @@ namespace sdf /// \param[in] _prefix String value to prefix to the output. /// \param[in] _includeDefaultElements flag to include default elements. /// \param[in] _includeDefaultAttributes flag to include default attributes. - /// \param[in] _config Configuration for printing the values. + /// \param[in] _config Configuration for converting to string. /// \return The string representation. public: std::string ToString( const std::string &_prefix, @@ -589,7 +589,7 @@ namespace sdf /// \param[in] _includeDefaultElements flag to include default elements. /// \param[in] _includeDefaultAttributes flag to include default attributes. /// \param[in] _config Configuration for printing values. - /// \param[out] _out the std::ostreamstream to write output to. + /// \param[out] _out the std::ostringstream to write output to. private: void PrintValuesImpl(const std::string &_prefix, bool _includeDefaultElements, bool _includeDefaultAttributes, @@ -685,6 +685,14 @@ namespace sdf /// \brief XML path of this element. public: std::string xmlPath; + + /// \brief Generate the string (XML) for the attributes. + /// \param[in] _includeDefaultAttributes flag to include default attributes. + /// \param[in] _config Configuration for printing attributes. + /// \param[out] _out the std::ostringstream to write output to. + public: void PrintAttributes(bool _includeDefaultAttributes, + const PrintConfig &_config, + std::ostringstream &_out) const; }; /////////////////////////////////////////////// diff --git a/include/sdf/Param.hh b/include/sdf/Param.hh index d46204be3..827ba3f06 100644 --- a/include/sdf/Param.hh +++ b/include/sdf/Param.hh @@ -401,17 +401,34 @@ namespace sdf const std::string &_valueStr, ParamVariant &_valueToSet) const; - /// \brief Method used to get the string representation from a ParamVariant + /// \brief Method used to get the string representation from a ParamVariant, + /// or the string that was used to set it. /// \param[in] _config Print configuration for the string output /// \param[in] _typeName The data type of the value /// \param[in] _value The value - /// \param[in] _valueStr The string representation of the value - /// \return True if the string was successfully retrieved from the value, - /// false otherwise. - public: bool StringFromValueImpl(const PrintConfig &_config, - const std::string &_typeName, - const ParamVariant &_value, - std::string &_valueStr) const; + /// \param[out] _valueStr The output string. + /// \return True if the string was successfully retrieved, false otherwise. + public: bool StringFromValueImpl( + const PrintConfig &_config, + const std::string &_typeName, + const ParamVariant &_value, + std::string &_valueStr) const; + + /// \brief Method used to get the string representation from a ParamVariant, + /// or the string that was used to set it. + /// \param[in] _config Print configuration for the string output + /// \param[in] _typeName The data type of the value + /// \param[in] _value The value + /// \param[in] _orignalStr The original string that was used to set the + /// value. A nullopt can be passed in if it is not available. + /// \param[out] _valueStr The output string. + /// \return True if the string was successfully retrieved, false otherwise. + public: bool StringFromValueImpl( + const PrintConfig &_config, + const std::string &_typeName, + const ParamVariant &_value, + const std::optional &_originalStr, + std::string &_valueStr) const; /// \brief Data type to string mapping /// \return The type as a string, empty string if unknown type diff --git a/include/sdf/PrintConfig.hh b/include/sdf/PrintConfig.hh index 2e3b700de..8696339c3 100644 --- a/include/sdf/PrintConfig.hh +++ b/include/sdf/PrintConfig.hh @@ -17,6 +17,7 @@ #ifndef SDF_PRINTCONFIG_HH_ #define SDF_PRINTCONFIG_HH_ +#include #include #include "sdf/sdf_config.h" @@ -29,9 +30,41 @@ namespace sdf /// This class contains configuration options for printing elements. class SDFORMAT_VISIBLE PrintConfig { - /// \brief Default constructor. + /// \brief Default constructor. All options are set to false by default. public: PrintConfig(); + /// \brief Sets the option for printing pose rotations in degrees if true, + /// otherwise they will be printed as radians by default. + /// \param[in] _value Whether to print pose rotations in degrees. + public: void SetRotationInDegrees(bool _value); + + /// \brief Returns whether or not pose rotations should be printed in + /// degrees. + /// \return True if pose rotations are printed in degrees, false otherwise. + public: bool RotationInDegrees() const; + + /// \brief Sets the option for printing pose rotation in degrees as well as + /// snapping the rotation to the desired interval, with the provided + /// tolerance. + /// \param[in] _interval Degrees interval to snap to, this value must be + /// larger than 0, and less than or equal to 360. + /// \param[in] _tolerance Tolerance which snapping occurs, this value must + /// be larger than 0, less than 360, and less than the provided interval. + /// \return True, unless any of the provided values are not valid. + public: bool SetRotationSnapToDegrees(unsigned int _interval, + double _tolerance); + + /// \brief Returns the current degree value that pose rotations will snap to + /// when printed. + /// \return The assigned degrees interval value to snap to. If it has not + /// been assigned, a nullopt will be returned. + public: std::optional RotationSnapToDegrees() const; + + /// \brief Returns the tolerance for snapping degree values when printed. + /// \return The assigned tolerance value which allows snapping to happen. If + /// it has not been assigned, a nullopt will be returned. + public: std::optional RotationSnapTolerance() const; + /// \brief Set print config to preserve tags. /// \param[in] _preserve True to preserve tags. /// False to expand included model. @@ -42,6 +75,11 @@ namespace sdf /// False if they are to be expanded. public: bool PreserveIncludes() const; + /// \brief Return true if both PrintConfig objects contain the same values. + /// \param[in] _config PrintConfig to compare. + /// \return True if 'this' == _config. + public: bool operator==(const PrintConfig &_config) const; + /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) }; diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 597c6f5d8..fb25f7f4b 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -136,8 +136,8 @@ if (BUILD_SDF_TEST) Pbr_TEST.cc Physics_TEST.cc Plugin_TEST.cc - PrintConfig_TEST.cc Plane_TEST.cc + PrintConfig_TEST.cc Root_TEST.cc Scene_TEST.cc SemanticPose_TEST.cc diff --git a/src/Element.cc b/src/Element.cc index 168403b8c..68f65e1c5 100644 --- a/src/Element.cc +++ b/src/Element.cc @@ -499,6 +499,7 @@ void Element::PrintDocLeftPane(std::string &_html, int _spacing, _html += "\n"; } +///////////////////////////////////////////////// void Element::PrintValuesImpl(const std::string &_prefix, bool _includeDefaultElements, bool _includeDefaultAttributes, @@ -513,22 +514,7 @@ void Element::PrintValuesImpl(const std::string &_prefix, { _out << _prefix << "<" << this->dataPtr->name; - Param_V::const_iterator aiter; - for (aiter = this->dataPtr->attributes.begin(); - aiter != this->dataPtr->attributes.end(); ++aiter) - { - // Only print attribute values if they were set - // TODO(anyone): GetRequired is added here to support up-conversions where - // a new required attribute with a default value is added. We would have - // better separation of concerns if the conversion process set the - // required attributes with their default values. - if ((*aiter)->GetSet() || (*aiter)->GetRequired() || - _includeDefaultAttributes) - { - _out << " " << (*aiter)->GetKey() << "='" - << (*aiter)->GetAsString(_config) << "'"; - } - } + this->dataPtr->PrintAttributes(_includeDefaultAttributes, _config, _out); if (this->dataPtr->elements.size() > 0) { @@ -560,6 +546,50 @@ void Element::PrintValuesImpl(const std::string &_prefix, } } +///////////////////////////////////////////////// +void ElementPrivate::PrintAttributes(bool _includeDefaultAttributes, + const PrintConfig &_config, + std::ostringstream &_out) const +{ + // Attribute exceptions are used in the event of a non-default PrintConfig + // which modifies the Attributes of this Element that are printed out. The + // modifications to an Attribute by a PrintConfig will overwrite the original + // existing Attribute when this Element is printed. + std::set attributeExceptions; + if (this->name == "pose") + { + if (_config.RotationInDegrees() || _config.RotationSnapToDegrees()) + { + attributeExceptions.insert("degrees"); + _out << " " << "degrees='true'"; + + attributeExceptions.insert("rotation_format"); + _out << " " << "rotation_format='euler_rpy'"; + } + } + + Param_V::const_iterator aiter; + for (aiter = this->attributes.begin(); + aiter != this->attributes.end(); ++aiter) + { + // Only print attribute values if they were set + // TODO(anyone): GetRequired is added here to support up-conversions where + // a new required attribute with a default value is added. We would have + // better separation of concerns if the conversion process set the + // required attributes with their default values. + if ((*aiter)->GetSet() || (*aiter)->GetRequired() || + _includeDefaultAttributes) + { + const std::string key = (*aiter)->GetKey(); + const auto it = attributeExceptions.find(key); + if (it == attributeExceptions.end()) + { + _out << " " << key << "='" << (*aiter)->GetAsString(_config) << "'"; + } + } + } +} + ///////////////////////////////////////////////// void Element::PrintValues(std::string _prefix, const PrintConfig &_config) const { diff --git a/src/Param.cc b/src/Param.cc index 4c6ee2db1..0d370bd3c 100644 --- a/src/Param.cc +++ b/src/Param.cc @@ -308,13 +308,15 @@ void Param::Update() ////////////////////////////////////////////////// std::string Param::GetAsString(const PrintConfig &_config) const { - if (this->dataPtr->strValue.has_value() && !this->dataPtr->strValue->empty()) - { - return this->dataPtr->strValue.value(); - } - else if(!this->dataPtr->strValue.has_value()) + std::string valueStr; + if (this->GetSet() && + this->dataPtr->StringFromValueImpl(_config, + this->dataPtr->typeName, + this->dataPtr->value, + this->dataPtr->strValue, + valueStr)) { - return this->dataPtr->defaultStrValue; + return valueStr; } return this->GetDefaultAsString(_config); @@ -324,10 +326,12 @@ std::string Param::GetAsString(const PrintConfig &_config) const std::string Param::GetDefaultAsString(const PrintConfig &_config) const { std::string defaultStr; - if (this->dataPtr->StringFromValueImpl(_config, - this->dataPtr->typeName, - this->dataPtr->defaultValue, - defaultStr)) + if (this->dataPtr->StringFromValueImpl( + _config, + this->dataPtr->typeName, + this->dataPtr->defaultValue, + this->dataPtr->defaultStrValue, + defaultStr)) { return defaultStr; } @@ -785,13 +789,22 @@ bool ParamPrivate::ValueFromStringImpl(const std::string &_typeName, return true; } +////////////////////////////////////////////////// +/// \brief Helper function for StringFromValueImpl for pose. +/// \param[in] _config Printing configuration for the output string. +/// \param[in] _parentAttributes Parent Element Attributes. +/// \param[in] _value The variant value of this pose. +/// \param[in] _originalStr The original string used to set this pose value. +/// \param[out] _valueStr The pose as a string. +/// \return True if the string was successfully retrieved from the pose, false +/// otherwise. ///////////////////////////////////////////////// bool PoseStringFromValue(const PrintConfig &_config, const Param_V &_parentAttributes, const ParamPrivate::ParamVariant &_value, + const std::optional &_originalStr, std::string &_valueStr) { - (void)_config; StringStreamClassicLocale ss; const ignition::math::Pose3d *pose = @@ -802,20 +815,6 @@ bool PoseStringFromValue(const PrintConfig &_config, return false; } - auto sanitizeZero = [](double _number) - { - StringStreamClassicLocale stream; - if (std::fpclassify(_number) == FP_ZERO) - { - stream << 0; - } - else - { - stream << _number; - } - return stream.str(); - }; - const bool defaultInDegrees = false; bool inDegrees = defaultInDegrees; @@ -828,6 +827,10 @@ bool PoseStringFromValue(const PrintConfig &_config, const std::string threeSpacedDelimiter = " "; std::string posRotDelimiter = defaultPosRotDelimiter; + const bool defaultSnapDegreesToInterval = false; + bool snapDegreesToInterval = defaultSnapDegreesToInterval; + + // Checking parent Element Attributes for desired pose representations. for (const auto &p : _parentAttributes) { const std::string key = p->GetKey(); @@ -854,6 +857,39 @@ bool PoseStringFromValue(const PrintConfig &_config, } } + // Checking PrintConfig for desired pose representations. This overrides + // any parent Element Attributes. + if (_config.RotationInDegrees()) + { + inDegrees = true; + rotationFormat = "euler_rpy"; + posRotDelimiter = threeSpacedDelimiter; + } + if (_config.RotationSnapToDegrees().has_value() && + _config.RotationSnapTolerance().has_value()) + { + inDegrees = true; + rotationFormat = "euler_rpy"; + snapDegreesToInterval = true; + posRotDelimiter = threeSpacedDelimiter; + } + + // Helper function that sanitizes zero values like '-0' + auto sanitizeZero = [](double _number) + { + StringStreamClassicLocale stream; + if (std::fpclassify(_number) == FP_ZERO) + { + stream << 0; + } + else + { + stream << _number; + } + return stream.str(); + }; + + // Returning pose string representations based on desired configurations. if (rotationFormat == "quat_xyzw" && inDegrees) { sdferr << "Invalid pose with //pose[@degrees='true'] and " @@ -870,6 +906,36 @@ bool PoseStringFromValue(const PrintConfig &_config, _valueStr = ss.str(); return true; } + else if (rotationFormat == "euler_rpy" && inDegrees && snapDegreesToInterval) + { + // Helper function that returns a snapped value if it is within the + // tolerance of multiples of interval, otherwise the orginal value is + // returned. + auto snapToInterval = + [](double _val, unsigned int _interval, double _tolerance) + { + double closestQuotient = std::round(_val / _interval); + double distance = std::abs(_val - closestQuotient * _interval); + if (distance < _tolerance) + { + return _interval * closestQuotient; + } + return _val; + }; + + const unsigned int interval = _config.RotationSnapToDegrees().value(); + const double tolerance = _config.RotationSnapTolerance().value(); + + ss << pose->Pos() << posRotDelimiter + << sanitizeZero(snapToInterval( + IGN_RTOD(pose->Rot().Roll()), interval, tolerance)) << " " + << sanitizeZero(snapToInterval( + IGN_RTOD(pose->Rot().Pitch()), interval, tolerance)) << " " + << sanitizeZero(snapToInterval( + IGN_RTOD(pose->Rot().Yaw()), interval, tolerance)); + _valueStr = ss.str(); + return true; + } else if (rotationFormat == "euler_rpy" && inDegrees) { ss << pose->Pos() << posRotDelimiter @@ -880,6 +946,17 @@ bool PoseStringFromValue(const PrintConfig &_config, return true; } + // If no modification to the value is needed, the original string is returned. + if (!_config.RotationInDegrees() && + !_config.RotationSnapToDegrees().has_value() && + !_config.RotationSnapTolerance().has_value() && + _originalStr.has_value() && + !_originalStr->empty()) + { + _valueStr = _originalStr.value(); + return true; + } + ss << pose->Pos() << posRotDelimiter << sanitizeZero(pose->Rot().Roll()) << " " << sanitizeZero(pose->Rot().Pitch()) << " " @@ -889,12 +966,42 @@ bool PoseStringFromValue(const PrintConfig &_config, } ///////////////////////////////////////////////// -bool ParamPrivate::StringFromValueImpl(const PrintConfig &_config, - const std::string &_typeName, - const ParamVariant &_value, - std::string &_valueStr) const +bool ParamPrivate::StringFromValueImpl( + const PrintConfig &_config, + const std::string &_typeName, + const ParamVariant &_value, + std::string &_valueStr) const +{ + return this->StringFromValueImpl( + _config, + _typeName, + _value, + std::nullopt, + _valueStr); +} + +///////////////////////////////////////////////// +bool ParamPrivate::StringFromValueImpl( + const PrintConfig &_config, + const std::string &_typeName, + const ParamVariant &_value, + const std::optional &_originalStr, + std::string &_valueStr) const { - if (_typeName == "ignition::math::Pose3d" || + // This will be handled in a type specific manner + if (_typeName == "bool") + { + const bool *val = std::get_if(&_value); + if (!val) + { + sdferr << "Unable to get bool value from variant.\n"; + return false; + } + + _valueStr = *val ? "true" : "false"; + return true; + } + else if (_typeName == "ignition::math::Pose3d" || _typeName == "pose" || _typeName == "Pose") { @@ -902,9 +1009,9 @@ bool ParamPrivate::StringFromValueImpl(const PrintConfig &_config, if (!this->ignoreParentAttributes && p) { return PoseStringFromValue( - _config, p->GetAttributes(), _value, _valueStr); + _config, p->GetAttributes(), _value, _originalStr, _valueStr); } - return PoseStringFromValue(_config, {}, _value, _valueStr); + return PoseStringFromValue(_config, {}, _value, _originalStr, _valueStr); } StringStreamClassicLocale ss; diff --git a/src/Plugin_TEST.cc b/src/Plugin_TEST.cc index 00d5b6245..35f6aee0d 100644 --- a/src/Plugin_TEST.cc +++ b/src/Plugin_TEST.cc @@ -201,7 +201,7 @@ TEST(DOMPlugin, LoadWithChildren) pluginStr + ""; sdf::ElementPtr elem(new sdf::Element); sdf::initFile("plugin.sdf", elem); - sdf::readString(pluginStrWithSdf, elem); + ASSERT_TRUE(sdf::readString(pluginStrWithSdf, elem)); sdf::Plugin plugin; sdf::Errors errors; diff --git a/src/PrintConfig.cc b/src/PrintConfig.cc index 3770f5007..a36c441b5 100644 --- a/src/PrintConfig.cc +++ b/src/PrintConfig.cc @@ -16,14 +16,24 @@ */ #include "sdf/PrintConfig.hh" +#include "sdf/Console.hh" + +using namespace sdf; -namespace sdf -{ -inline namespace SDF_VERSION_NAMESPACE -{ ///////////////////////////////////////////////// class PrintConfig::Implementation { + /// \brief True if rotation in poses are to be printed in degrees. + public: bool rotationInDegrees = false; + + /// \brief The interval in degrees, which rotation in poses shall snap to, + /// if they are within the tolerance value of rotationSnapTolerance. + public: std::optional rotationSnapToDegrees = std::nullopt; + + /// \brief The tolerance which is used to determine whether snapping of + /// rotation in poses happen. + public: std::optional rotationSnapTolerance = std::nullopt; + /// \brief True to preserve tags, false to expand. public: bool preserveIncludes = false; }; @@ -34,6 +44,18 @@ PrintConfig::PrintConfig() { } +///////////////////////////////////////////////// +void PrintConfig::SetRotationInDegrees(bool _value) +{ + this->dataPtr->rotationInDegrees = _value; +} + +///////////////////////////////////////////////// +bool PrintConfig::RotationInDegrees() const +{ + return this->dataPtr->rotationInDegrees; +} + ///////////////////////////////////////////////// void PrintConfig::SetPreserveIncludes(bool _preserve) { @@ -46,5 +68,51 @@ bool PrintConfig::PreserveIncludes() const return this->dataPtr->preserveIncludes; } +///////////////////////////////////////////////// +bool PrintConfig::SetRotationSnapToDegrees(unsigned int _interval, + double _tolerance) +{ + if (_interval == 0 || _interval > 360) + { + sdferr << "Interval value to snap to must be larger than 0, and less than " + << "or equal to 360.\n"; + return false; + } + + if (_tolerance <= 0 || _tolerance > 360 || + _tolerance >= static_cast(_interval)) + { + sdferr << "Tolerance must be larger than 0, less than or equal to " + << "360, and less than the provided interval.\n"; + return false; + } + + this->dataPtr->rotationSnapToDegrees = _interval; + this->dataPtr->rotationSnapTolerance = _tolerance; + return true; +} + +///////////////////////////////////////////////// +std::optional PrintConfig::RotationSnapToDegrees() const +{ + return this->dataPtr->rotationSnapToDegrees; } + +///////////////////////////////////////////////// +std::optional PrintConfig::RotationSnapTolerance() const +{ + return this->dataPtr->rotationSnapTolerance; +} + +///////////////////////////////////////////////// +bool PrintConfig::operator==(const PrintConfig &_config) const +{ + if (this->RotationInDegrees() == _config.RotationInDegrees() && + this->RotationSnapToDegrees() == _config.RotationSnapToDegrees() && + this->RotationSnapTolerance() == _config.RotationSnapTolerance() && + this->PreserveIncludes() == _config.PreserveIncludes()) + { + return true; + } + return false; } diff --git a/src/PrintConfig_TEST.cc b/src/PrintConfig_TEST.cc index ff473bf5d..9ac523c9e 100644 --- a/src/PrintConfig_TEST.cc +++ b/src/PrintConfig_TEST.cc @@ -20,6 +20,81 @@ #include "sdf/PrintConfig.hh" #include "test_config.h" +///////////////////////////////////////////////// +TEST(PrintConfig, Construction) +{ + sdf::PrintConfig config; + EXPECT_FALSE(config.RotationInDegrees()); + EXPECT_FALSE(config.RotationSnapToDegrees()); + EXPECT_FALSE(config.PreserveIncludes()); +} + +///////////////////////////////////////////////// +TEST(PrintConfig, RotationInDegrees) +{ + sdf::PrintConfig config; + EXPECT_FALSE(config.RotationInDegrees()); + + config.SetRotationInDegrees(true); + EXPECT_TRUE(config.RotationInDegrees()); + + config.SetRotationInDegrees(false); + EXPECT_FALSE(config.RotationInDegrees()); +} + +///////////////////////////////////////////////// +TEST(PrintConfig, RotationSnapToDegrees) +{ + sdf::PrintConfig config; + EXPECT_FALSE(config.RotationSnapToDegrees().has_value()); + EXPECT_FALSE(config.RotationSnapTolerance().has_value()); + + EXPECT_TRUE(config.SetRotationSnapToDegrees(5, 0.01)); + ASSERT_TRUE(config.RotationSnapToDegrees().has_value()); + EXPECT_EQ(5u, config.RotationSnapToDegrees().value()); + ASSERT_TRUE(config.RotationSnapTolerance().has_value()); + EXPECT_DOUBLE_EQ(0.01, config.RotationSnapTolerance().value()); + + EXPECT_FALSE(config.SetRotationSnapToDegrees(0, 0.01)); + EXPECT_FALSE(config.SetRotationSnapToDegrees(360 + 1, 0.01)); + EXPECT_FALSE(config.SetRotationSnapToDegrees(5, -1e6)); + EXPECT_FALSE(config.SetRotationSnapToDegrees(5, 360 + 1e-6)); + + EXPECT_FALSE(config.SetRotationSnapToDegrees(5, 5 + 1e-6)); + EXPECT_TRUE(config.SetRotationSnapToDegrees(5, 5 - 1e-6)); + ASSERT_TRUE(config.RotationSnapToDegrees().has_value()); + EXPECT_EQ(5u, config.RotationSnapToDegrees().value()); + ASSERT_TRUE(config.RotationSnapTolerance().has_value()); + EXPECT_DOUBLE_EQ(5 - 1e-6, config.RotationSnapTolerance().value()); +} + +///////////////////////////////////////////////// +TEST(PrintConfig, Compare) +{ + sdf::PrintConfig first; + sdf::PrintConfig second; + EXPECT_TRUE(first == second); + EXPECT_TRUE(second == first); + + first.SetRotationInDegrees(true); + EXPECT_TRUE(first.RotationInDegrees()); + EXPECT_FALSE(second.RotationInDegrees()); + EXPECT_FALSE(first == second); + EXPECT_FALSE(second == first); + + second.SetRotationInDegrees(true); + EXPECT_TRUE(first == second); + EXPECT_TRUE(second == first); + + EXPECT_TRUE(first.SetRotationSnapToDegrees(5, 0.01)); + EXPECT_FALSE(first == second); + EXPECT_FALSE(second == first); + + EXPECT_TRUE(second.SetRotationSnapToDegrees(5, 0.01)); + EXPECT_TRUE(first == second); + EXPECT_TRUE(second == first); +} + ///////////////////////////////////////////////// TEST(PrintConfig, PreserveIncludes) { diff --git a/src/cmd/cmdsdformat.rb.in b/src/cmd/cmdsdformat.rb.in index 9d4d757c4..5de7a65b3 100644 --- a/src/cmd/cmdsdformat.rb.in +++ b/src/cmd/cmdsdformat.rb.in @@ -31,9 +31,9 @@ require 'optparse' LIBRARY_NAME = '@library_location@' LIBRARY_VERSION = '@SDF_VERSION_FULL@' COMMON_OPTIONS = - " -h [ --help ] Print this help message.\n"\ - " --force-version Use a specific library version.\n"\ - ' --versions Show the available versions.' + " -h [ --help ] Print this help message.\n"\ + " --force-version Use a specific library version.\n"\ + ' --versions Show the available versions.' COMMANDS = { 'sdf' => "Utilities for SDF files.\n\n"\ " ign sdf [options]\n\n"\ @@ -44,6 +44,12 @@ COMMANDS = { 'sdf' => " use only and the output may change without any promise of stability)\n" + " -p [ --print ] arg Print converted arg.\n" + " -i [ --preserve-includes ] Preserve included tags when printing converted arg (does not preserve merge-includes).\n" + + " --degrees Pose rotation angles are printed in degrees.\n" + + " --snap-to-degrees arg Snap pose rotation angles to this specified interval in degrees. This value must be\n" + + " larger than 0, less than or equal to 360, and larger than the defined snap tolerance.\n" + + " --snap-tolerance arg Used in conjunction with --snap-to-degrees, specifies the tolerance at which snapping\n" + + " occurs. This value must be larger than 0, less than 360, and less than the defined\n" + + " degrees value to snap to. If unspecified, its default value is 0.01.\n" + COMMON_OPTIONS } @@ -57,6 +63,8 @@ class Cmd # def parse(args) options = {} + options['degrees'] = 0 + options['snap_tolerance'] = 0.01 usage = COMMANDS[args[0]] @@ -82,6 +90,25 @@ class Cmd opts.on('-i', '--preserve-includes', 'Preserve included tags when printing converted arg (does not preserve merge-includes)') do options['preserve_includes'] = 1 end + opts.on('--degrees', 'Printed pose rotations are will be in degrees') do |degrees| + options['degrees'] = 1 + end + opts.on('--snap-to-degrees arg', Integer, + 'Printed rotations are snapped to specified degree intervals') do |arg| + if arg == 0 || arg > 360 + puts "Degree interval to snap to must be more than 0, and less than or equal to 360." + exit(-1) + end + options['snap_to_degrees'] = arg + end + opts.on('--snap-tolerance arg', Float, + 'Printed rotations are snapped if they are within this specified tolerance') do |arg| + if arg < 0 || arg > 360 + puts "Rotation snapping tolerance must be more than 0, and less than 360." + exit(-1) + end + options['snap_tolerance'] = arg + end opts.on('-g arg', '--graph type', String, 'Print PoseRelativeTo or FrameAttachedTo graph') do |graph_type| options['graph'] = {:type => graph_type} @@ -178,13 +205,22 @@ class Cmd Importer.extern 'int cmdDescribe(const char *)' exit(Importer.cmdDescribe(options['describe'])) elsif options.key?('print') + snap_to_degrees = 0 if options['preserve_includes'] Importer.extern 'int cmdPrintPreserveIncludes(const char *)' exit(Importer.cmdPrintPreserveIncludes(File.expand_path(options['print']))) - else - Importer.extern 'int cmdPrint(const char *)' - exit(Importer.cmdPrint(File.expand_path(options['print']))) + elsif options.key?('snap_to_degrees') + if options['snap_to_degrees'] < options['snap_tolerance'] + puts "Rotation snapping tolerance must be larger than the snapping tolerance." + exit(-1) + end + snap_to_degrees = options['snap_to_degrees'] end + Importer.extern 'int cmdPrint(const char *, int in_degrees, int snap_to_degrees, float snap_tolerance)' + exit(Importer.cmdPrint(File.expand_path(options['print']), + options['degrees'], + snap_to_degrees, + options['snap_tolerance'])) elsif options.key?('graph') Importer.extern 'int cmdGraph(const char *, const char *)' exit(Importer.cmdGraph(options['graph'][:type], File.expand_path(ARGV[1]))) diff --git a/src/ign.cc b/src/ign.cc index 16cdb0d24..23f9625e8 100644 --- a/src/ign.cc +++ b/src/ign.cc @@ -18,12 +18,14 @@ #include #include #include +#include #include #include "sdf/sdf_config.h" #include "sdf/Filesystem.hh" #include "sdf/Root.hh" #include "sdf/parser.hh" +#include "sdf/PrintConfig.hh" #include "sdf/system_util.hh" #include "FrameSemantics.hh" @@ -131,7 +133,8 @@ extern "C" SDFORMAT_VISIBLE int cmdDescribe(const char *_version) } ////////////////////////////////////////////////// -extern "C" SDFORMAT_VISIBLE int cmdPrint(const char *_path) +extern "C" SDFORMAT_VISIBLE int cmdPrint(const char *_path, + int inDegrees, int snapToDegrees, float snapTolerance) { if (!sdf::filesystem::exists(_path)) { @@ -153,8 +156,18 @@ extern "C" SDFORMAT_VISIBLE int cmdPrint(const char *_path) return -1; } - sdf->PrintValues(); + sdf::PrintConfig config; + if (inDegrees!= 0) + { + config.SetRotationInDegrees(true); + } + if (snapToDegrees > 0) + { + config.SetRotationSnapToDegrees(static_cast(snapToDegrees), + static_cast(snapTolerance)); + } + sdf->PrintValues(config); return 0; } diff --git a/src/ign_TEST.cc b/src/ign_TEST.cc index 249cecd3b..d93172742 100644 --- a/src/ign_TEST.cc +++ b/src/ign_TEST.cc @@ -948,6 +948,631 @@ TEST(print, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) } } +////////////////////////////////////////////////// +static bool contains(const std::string &_a, const std::string &_b) +{ + return _a.find(_b) != std::string::npos; +} + +///////////////////////////////////////////////// +TEST(print_rotations_in_degrees, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + const std::string path = + sdf::testing::TestFile("sdf", "rotations_in_degrees.sdf"); + + // Default printing + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "1 2 3 30.009 44.991 -60.009"); + + // Printing with in_degrees + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --degrees " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // Printing with snap_to_degrees 2 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 2 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 44.991 -60"); + + // Printing with snap_to_degrees 20 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 20 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.008 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.008 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.01 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.01 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); +} + +///////////////////////////////////////////////// +TEST(print_rotations_in_radians, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + const std::string path = + sdf::testing::TestFile("sdf", "rotations_in_radians.sdf"); + + // Default printing + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "1 2 3 0.523756 0.785241 -1.04735"); + + // Printing with in_degrees + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --degrees " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.0087"); + + // Printing with snap_to_degrees 5 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // Printing with snap_to_degrees 2 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 2 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 44.991 -60"); + + // Printing with snap_to_degrees 20 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 20 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.008 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.008 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.0087"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.01 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.01 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); +} + +///////////////////////////////////////////////// +TEST(print_rotations_in_quaternions, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + const auto path = sdf::testing::TestFile( + "sdf", "rotations_in_quaternions.sdf"); + + // Default printing + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 0.391948 0.200425 -0.532046 0.723279"); + + // Printing with in_degrees + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --degrees " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // Printing with snap_to_degrees 2 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 2 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 44.991 -60"); + + // Printing with snap_to_degrees 20 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 20 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.008 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.008 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.01 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.01 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); +} + +///////////////////////////////////////////////// +TEST(print_includes_rotations_in_degrees, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + // Set SDF_PATH so that included models can be found + sdf::testing::setenv( + "SDF_PATH", sdf::testing::SourceFile("test", "integration", "model")); + const std::string path = + sdf::testing::TestFile("sdf", "includes_rotations_in_degrees.sdf"); + + // Default printing + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "1 2 3 30.009 44.991 -60.009"); + + // Printing with in_degrees + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --degrees " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // Printing with snap_to_degrees 2 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 2 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 44.991 -60"); + + // Printing with snap_to_degrees 20 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 20 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.008 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.008 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.01 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.01 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); +} + +///////////////////////////////////////////////// +TEST(print_includes_rotations_in_radians, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + // Set SDF_PATH so that included models can be found + sdf::testing::setenv( + "SDF_PATH", sdf::testing::SourceFile("test", "integration", "model")); + const std::string path = + sdf::testing::TestFile("sdf", "includes_rotations_in_radians.sdf"); + + // Default printing + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "1 2 3 0.523756 0.785241 -1.04735"); + + // Printing with in_degrees + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --degrees " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.0087"); + + // Printing with snap_to_degrees 5 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // Printing with snap_to_degrees 2 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 2 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 44.991 -60"); + + // Printing with snap_to_degrees 20 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 20 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.008 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.008 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.0087"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.01 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.01 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); +} + +///////////////////////////////////////////////// +TEST(print_includes_rotations_in_quaternions, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + // Set SDF_PATH so that included models can be found + sdf::testing::setenv( + "SDF_PATH", sdf::testing::SourceFile("test", "integration", "model")); + const auto path = sdf::testing::TestFile( + "sdf", "includes_rotations_in_quaternions.sdf"); + + // Default printing + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 0.391948 0.200425 -0.532046 0.723279"); + + // Printing with in_degrees + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --degrees " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // Printing with snap_to_degrees 2 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 2 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 44.991 -60"); + + // Printing with snap_to_degrees 20 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 20 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.008 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.008 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.01 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.01 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); +} + +///////////////////////////////////////////////// +TEST(print_rotations_in_unnormalized_degrees, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + const std::string path = + sdf::testing::TestFile("sdf", "rotations_in_unnormalized_degrees.sdf"); + + // Default printing + // Unnormalized degree values cannot be returned as is, as its string is + // returned by parsing the pose value, whenever a parent Element Attribute, + // or PrintConfig is used. + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "1 2 3 30.009 44.991 -60.009"); + + // Printing with in_degrees + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --degrees " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // Printing with snap_to_degrees 2 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 2 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 44.991 -60"); + + // Printing with snap_to_degrees 20 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 20 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.008 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.008 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.991 -60.009"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.01 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.01 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); +} + +///////////////////////////////////////////////// +TEST(print_rotations_in_unnormalized_radians, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + const std::string path = + sdf::testing::TestFile("sdf", "rotations_in_unnormalized_radians.sdf"); + + // Default printing + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "1 2 3 -5.75943 -11.78112 5.23583"); + + // Printing with in_degrees + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --degrees " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.9915 -60.009"); + + // Printing with snap_to_degrees 5 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // Printing with snap_to_degrees 2 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 2 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 44.9915 -60"); + + // Printing with snap_to_degrees 20 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 20 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.9915 -60"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.008 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.008 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.9915 -60.009"); + + // Printing with snap_to_degrees 5, snap_tolerance 0.01 + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + "--snap-tolerance 0.01 " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); +} + +///////////////////////////////////////////////// +TEST(shuffled_cmd_flags, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + const std::string path = + sdf::testing::TestFile("sdf", "rotations_in_unnormalized_radians.sdf"); + + // -p PATH --degrees + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --degrees " + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.9915 -60.009"); + + // --degrees -p PATH + output = custom_exec_str( + IgnCommand() + " sdf --degrees -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30.009 44.9915 -60.009"); + + // -p PATH --snap-to-degrees ARG + output = custom_exec_str( + IgnCommand() + " sdf -p " + path + " --snap-to-degrees 5 " + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // -p --snap-to-degrees ARG PATH + output = custom_exec_str( + IgnCommand() + " sdf -p --snap-to-degrees 5 " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); + + // --snap-to-degrees ARG -p PATH + output = custom_exec_str( + IgnCommand() + " sdf --snap-to-degrees 5 -p " + path + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 45 -60"); +} + +///////////////////////////////////////////////// +TEST(print_snap_to_degrees_tolerance_too_high, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF)) +{ + const std::string path = sdf::testing::TestFile( + "sdf", + "rotations_in_degrees_high_snap_tolerance.sdf"); + + std::string output = custom_exec_str( + IgnCommand() + " sdf -p " + path + + " --snap-to-degrees 5 " + " --snap-tolerance 4" + + SdfVersion()); + ASSERT_FALSE(output.empty()); + EXPECT_PRED2(contains, output, + "" + "1 2 3 30 50 60"); +} + ///////////////////////////////////////////////// TEST(GraphCmd, IGN_UTILS_TEST_DISABLED_ON_WIN32(WorldPoseRelativeTo)) { diff --git a/src/parser.cc b/src/parser.cc index 0c45332b0..f4dc5758d 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -1942,19 +1942,27 @@ void copyChildren(ElementPtr _sdf, ElementPtr element(new Element); element->SetParent(_sdf); element->SetName(elem_name); - if (elemXml->GetText() != nullptr) - { - element->AddValue("string", elemXml->GetText(), "1"); - } - + std::optional typeName = std::nullopt; for (const tinyxml2::XMLAttribute *attribute = elemXml->FirstAttribute(); attribute; attribute = attribute->Next()) { - element->AddAttribute(attribute->Name(), "string", "", 1, ""); - element->GetAttribute(attribute->Name())->SetFromString( + const std::string attributeName(attribute->Name()); + if (attributeName == "type") + typeName = attribute->Value(); + + element->AddAttribute(attributeName, "string", "", 1, ""); + element->GetAttribute(attributeName)->SetFromString( attribute->Value()); } + if (elemXml->GetText() != nullptr) + { + if (typeName.has_value()) + element->AddValue(typeName.value(), elemXml->GetText(), true); + else + element->AddValue("string", elemXml->GetText(), true); + } + copyChildren(element, elemXml, _onlyUnknown); _sdf->InsertElement(element); } diff --git a/test/integration/default_elements.cc b/test/integration/default_elements.cc index fb8434db8..40767e6e2 100644 --- a/test/integration/default_elements.cc +++ b/test/integration/default_elements.cc @@ -187,27 +187,27 @@ TEST(ExplicitlySetInFile, ToString) << "\n" << " \n" << " \n" - << " 1.0\n" + << " 1\n" << " 0 0 0\n" << " \n" << " \n" << " EARTH_WGS84\n" - << " 0.0\n" - << " 0.0\n" - << " 0.0\n" - << " 0.0\n" + << " 0\n" + << " 0\n" + << " 0\n" + << " 0\n" << " \n" << " 0 0 -9.8\n" - << " 5.5645e-6 22.8758e-6 -42.3884e-6\n" + << " 6e-06 2.3e-05 -4.2e-05\n" << " \n" << " \n" << " 0.001\n" - << " 1.0\n" + << " 1\n" << " 1000\n" << " \n" << " \n" - << " 0.4 0.4 0.4 1.0\n" - << " .7 .7 .7 1\n" + << " 0.4 0.4 0.4 1\n" + << " 0.7 0.7 0.7 1\n" << " true\n" << " \n" << " \n" @@ -221,27 +221,27 @@ TEST(ExplicitlySetInFile, ToString) << "\n" << " \n" << " \n" - << " 1.0\n" + << " 1\n" << " 0 0 0\n" << " \n" << " \n" << " EARTH_WGS84\n" - << " 0.0\n" - << " 0.0\n" - << " 0.0\n" - << " 0.0\n" + << " 0\n" + << " 0\n" + << " 0\n" + << " 0\n" << " \n" << " 0 0 -9.8\n" - << " 5.5645e-6 22.8758e-6 -42.3884e-6\n" + << " 6e-06 2.3e-05 -4.2e-05\n" << " \n" << " \n" << " 0.001\n" - << " 1.0\n" + << " 1\n" << " 1000\n" << " \n" << " \n" - << " 0.4 0.4 0.4 1.0\n" - << " .7 .7 .7 1\n" + << " 0.4 0.4 0.4 1\n" + << " 0.7 0.7 0.7 1\n" << " true\n" << " \n" << " \n" diff --git a/test/integration/include_custom_model_expected_output.sdf b/test/integration/include_custom_model_expected_output.sdf index e4584cd98..f554228c8 100644 --- a/test/integration/include_custom_model_expected_output.sdf +++ b/test/integration/include_custom_model_expected_output.sdf @@ -211,7 +211,7 @@ - 1.0469999999999999 + 1.047 1280 @@ -457,16 +457,16 @@ 0 0 -9.8 - 5.5645e-6 22.8758e-6 -42.3884e-6 + 6e-06 2.3e-05 -4.2e-05 0.001 - 1.0 + 1 1000 - 0.4 0.4 0.4 1.0 - .7 .7 .7 1 + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 true diff --git a/test/integration/include_custom_nested_model_expected_output.sdf b/test/integration/include_custom_nested_model_expected_output.sdf index 959a6b2cc..e7b3115f2 100644 --- a/test/integration/include_custom_nested_model_expected_output.sdf +++ b/test/integration/include_custom_nested_model_expected_output.sdf @@ -11,7 +11,7 @@ 0.126164 0 0 - 0.416519 + 0.41651899999999997 0 0.481014 @@ -80,13 +80,13 @@ -1.06 0 0 0 0 3.14 - 1.047 + 1.0469999999999999 320 240 - 0.1 + 0.10000000000000001 100 @@ -158,13 +158,13 @@ - 1.047 + 1.0469999999999999 320 240 - 0.1 + 0.10000000000000001 100 @@ -181,7 +181,7 @@ -0.2 0 0.3 0 0 3.14 - 0.05 + 0.050000000000000003 @@ -203,10 +203,10 @@ 2 - 0.145833 + 0.14583299999999999 0 0 - 0.145833 + 0.14583299999999999 0 0.125 @@ -214,7 +214,7 @@ - 0.3 + 0.29999999999999999 @@ -226,7 +226,7 @@ - 0.3 + 0.29999999999999999 @@ -239,10 +239,10 @@ 2 - 0.145833 + 0.14583299999999999 0 0 - 0.145833 + 0.14583299999999999 0 0.125 @@ -250,7 +250,7 @@ - 0.3 + 0.29999999999999999 @@ -262,7 +262,7 @@ - 0.3 + 0.29999999999999999 @@ -275,10 +275,10 @@ 2 - 0.145833 + 0.14583299999999999 0 0 - 0.145833 + 0.14583299999999999 0 0.125 @@ -286,7 +286,7 @@ - 0.3 + 0.29999999999999999 @@ -298,7 +298,7 @@ - 0.3 + 0.29999999999999999 @@ -311,8 +311,8 @@ 0 0 1 - -1.79769e+308 - 1.79769e+308 + -1.7976900000000001e+308 + 1.7976900000000001e+308 @@ -322,8 +322,8 @@ 0 0 1 - -1.79769e+308 - 1.79769e+308 + -1.7976900000000001e+308 + 1.7976900000000001e+308 @@ -334,16 +334,16 @@ 0 0 -9.8 - 5.5645e-6 22.8758e-6 -42.3884e-6 + 6e-06 2.3e-05 -4.2e-05 0.001 - 1.0 + 1 1000 - 0.4 0.4 0.4 1.0 - .7 .7 .7 1 + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 true diff --git a/test/integration/pose_1_9_sdf.cc b/test/integration/pose_1_9_sdf.cc index c70a98037..492ff2cdc 100644 --- a/test/integration/pose_1_9_sdf.cc +++ b/test/integration/pose_1_9_sdf.cc @@ -788,7 +788,7 @@ TEST(Pose1_9, ToStringWithDegreesFalse) EXPECT_TRUE(poseValueParam->SetFromString("1 2 3 0.4 0.5 0.6")); std::string elemStr = poseElem->ToString(""); - EXPECT_PRED2(contains, elemStr, "degrees='0'"); + EXPECT_PRED2(contains, elemStr, "degrees='false'"); EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6"); } @@ -811,7 +811,7 @@ TEST(Pose1_9, ToStringWithDegreesTrue) EXPECT_TRUE(poseValueParam->SetFromString("1 2 3 0.4 0.5 0.6")); std::string elemStr = poseElem->ToString(""); - EXPECT_PRED2(contains, elemStr, "degrees='1'"); + EXPECT_PRED2(contains, elemStr, "degrees='true'"); EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6"); } @@ -863,7 +863,7 @@ TEST(Pose1_9, ToStringWithEulerRPYDegreesTrue) EXPECT_TRUE(poseValueParam->SetFromString("1 2 3 0.4 0.5 0.6")); std::string elemStr = poseElem->ToString(""); - EXPECT_PRED2(contains, elemStr, "degrees='1'"); + EXPECT_PRED2(contains, elemStr, "degrees='true'"); EXPECT_PRED2(contains, elemStr, "rotation_format='euler_rpy'"); EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6"); } @@ -887,9 +887,11 @@ TEST(Pose1_9, ToStringWithQuatXYZ) ASSERT_NE(nullptr, poseValueParam); EXPECT_TRUE(poseValueParam->SetFromString("1 2 3 0.7071068 0 0 0.7071068")); + // The string output has changed as it was parsed from the value, instead of + // the original string. std::string elemStr = poseElem->ToString(""); EXPECT_PRED2(contains, elemStr, "rotation_format='quat_xyzw'"); - EXPECT_PRED2(contains, elemStr, "0.7071068 0 0 0.7071068"); + EXPECT_PRED2(contains, elemStr, "0.707107 0 0 0.707107"); } ////////////////////////////////////////////////// @@ -915,10 +917,12 @@ TEST(Pose1_9, ToStringWithQuatXYZWDegreesFalse) ASSERT_NE(nullptr, poseValueParam); EXPECT_TRUE(poseValueParam->SetFromString("1 2 3 0.7071068 0 0 0.7071068")); + // The string output has changed as it was parsed from the value, instead of + // the original string. std::string elemStr = poseElem->ToString(""); - EXPECT_PRED2(contains, elemStr, "degrees='0'"); + EXPECT_PRED2(contains, elemStr, "degrees='false'"); EXPECT_PRED2(contains, elemStr, "rotation_format='quat_xyzw'"); - EXPECT_PRED2(contains, elemStr, "0.7071068 0 0 0.7071068"); + EXPECT_PRED2(contains, elemStr, "0.707107 0 0 0.707107"); } ////////////////////////////////////////////////// @@ -941,18 +945,22 @@ TEST(Pose1_9, ToStringAfterChangingDegreeAttribute) std::string elemStr = poseElem->ToString(""); EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6"); - // Changing to degrees + // Changing to attribute to degrees, however this does not modify the + // value of the underlying Param. Reparse needs to be called, which uses + // the input from SetFromString, to get a new value. sdf::ParamPtr degreesAttrib = poseElem->GetAttribute("degrees"); ASSERT_NE(nullptr, degreesAttrib); ASSERT_TRUE(degreesAttrib->Set(true)); + EXPECT_TRUE(valParam->Reparse()); + elemStr = poseElem->ToString(""); - EXPECT_PRED2(contains, elemStr, "degrees='1'"); + EXPECT_PRED2(contains, elemStr, "degrees='true'"); EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6"); // Changing back to radians ASSERT_TRUE(degreesAttrib->Set(false)); elemStr = poseElem->ToString(""); - EXPECT_PRED2(contains, elemStr, "degrees='0'"); + EXPECT_PRED2(contains, elemStr, "degrees='false'"); EXPECT_PRED2(contains, elemStr, "0.4 0.5 0.6"); } diff --git a/test/integration/print_config.cc b/test/integration/print_config.cc index a3cc9aba1..ded642ab2 100644 --- a/test/integration/print_config.cc +++ b/test/integration/print_config.cc @@ -187,6 +187,9 @@ R"( auto *includeMergedModel = world->ModelByIndex(0); ASSERT_NE(includeMergedModel, nullptr); + // The expected output pose string here still contains a -0 on the pitch value + // as it was set using ignition::math::Pose3d::operator<<, this test will have + // to be modified when we start using ignitionrobotics/ign-math#206. const std::string expectedIncludeMerge = R"( diff --git a/test/sdf/includes_rotations_in_degrees.sdf b/test/sdf/includes_rotations_in_degrees.sdf new file mode 100644 index 000000000..ae04da1d6 --- /dev/null +++ b/test/sdf/includes_rotations_in_degrees.sdf @@ -0,0 +1,12 @@ + + + + + + test_model + parent_model + 1 2 3 30.009 44.991 -60.009 + + + + diff --git a/test/sdf/includes_rotations_in_quaternions.sdf b/test/sdf/includes_rotations_in_quaternions.sdf new file mode 100644 index 000000000..08795bd22 --- /dev/null +++ b/test/sdf/includes_rotations_in_quaternions.sdf @@ -0,0 +1,14 @@ + + + + + + test_model + parent_model + + 1 2 3 0.391948 0.200425 -0.532046 0.723279 + + + + + diff --git a/test/sdf/includes_rotations_in_radians.sdf b/test/sdf/includes_rotations_in_radians.sdf new file mode 100644 index 000000000..ef91f408a --- /dev/null +++ b/test/sdf/includes_rotations_in_radians.sdf @@ -0,0 +1,12 @@ + + + + + + test_model + parent_model + 1 2 3 0.523756 0.785241 -1.04735 + + + + diff --git a/test/sdf/rotations_in_degrees.sdf b/test/sdf/rotations_in_degrees.sdf new file mode 100644 index 000000000..9dbba3c44 --- /dev/null +++ b/test/sdf/rotations_in_degrees.sdf @@ -0,0 +1,8 @@ + + + + + 1 2 3 30.009 44.991 -60.009 + + + diff --git a/test/sdf/rotations_in_degrees_high_snap_tolerance.sdf b/test/sdf/rotations_in_degrees_high_snap_tolerance.sdf new file mode 100644 index 000000000..273564354 --- /dev/null +++ b/test/sdf/rotations_in_degrees_high_snap_tolerance.sdf @@ -0,0 +1,8 @@ + + + + + 1 2 3 30 48.5 60 + + + diff --git a/test/sdf/rotations_in_quaternions.sdf b/test/sdf/rotations_in_quaternions.sdf new file mode 100644 index 000000000..2a8447f38 --- /dev/null +++ b/test/sdf/rotations_in_quaternions.sdf @@ -0,0 +1,10 @@ + + + + + + 1 2 3 0.391948 0.200425 -0.532046 0.723279 + + + + diff --git a/test/sdf/rotations_in_radians.sdf b/test/sdf/rotations_in_radians.sdf new file mode 100644 index 000000000..36a218bd8 --- /dev/null +++ b/test/sdf/rotations_in_radians.sdf @@ -0,0 +1,8 @@ + + + + + 1 2 3 0.523756 0.785241 -1.04735 + + + diff --git a/test/sdf/rotations_in_unnormalized_degrees.sdf b/test/sdf/rotations_in_unnormalized_degrees.sdf new file mode 100644 index 000000000..ba688c750 --- /dev/null +++ b/test/sdf/rotations_in_unnormalized_degrees.sdf @@ -0,0 +1,8 @@ + + + + + 1 2 3 390.009 764.991 -420.009 + + + diff --git a/test/sdf/rotations_in_unnormalized_radians.sdf b/test/sdf/rotations_in_unnormalized_radians.sdf new file mode 100644 index 000000000..4d9578932 --- /dev/null +++ b/test/sdf/rotations_in_unnormalized_radians.sdf @@ -0,0 +1,8 @@ + + + + + 1 2 3 -5.75943 -11.78112 5.23583 + + + From 92d20d2312e4df7f11e083c5f4febb0bc049e043 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 22 Dec 2021 14:56:54 -0800 Subject: [PATCH 19/28] Replace custom cmake code with ign-cmake2 (#780) This replaces most of the custom cmake code in libsdformat with the functionality provided by ignition-cmake2. The root CMakeLists.txt is much shorter now and most of the cmake folder has been deleted. This is made possible by the NO_IGNITION_PREFIX and REPLACE_IGNITION_INCLUDE_PATH parameters added to ign_configure_project in ign-cmake#190 and ign-cmake#191. Closes #181. Other details: * Use FindIgnURDFDOM from ign-cmake#193 * Use HIDE_SYMBOLS_BY_DEFAULT from ign-cmake#196 * Set LEGACY_PROJECT_PREFIX from ign-cmake#199 Signed-off-by: Steve Peters --- .github/ci/packages.apt | 2 +- CMakeLists.txt | 425 +- cmake/CodeCoverage.cmake | 135 - cmake/DefaultCFlags.cmake | 79 - cmake/FindSSE.cmake | 115 - cmake/HostCFlags.cmake | 27 - cmake/Modules/FindTinyXML2.cmake | 42 - cmake/SDFUtils.cmake | 251 - cmake/SearchForStuff.cmake | 120 - cmake/TargetArch.cmake | 158 - cmake/cmake_uninstall.cmake.in | 21 - cmake/cpack_options.cmake.in | 23 - cmake/sdf_config.cmake.in | 40 - cmake/sdf_cpack.cmake | 25 - cmake/sdformat_pc.in | 10 - cmake/upload_doc.sh.in | 6 +- conf/CMakeLists.txt | 10 +- conf/sdformat.yaml.in | 2 +- doc/sdf.in | 2 +- include/CMakeLists.txt | 1 + include/sdf/CMakeLists.txt | 69 +- .../sdf/config.hh.in | 27 +- include/sdf/sdf.hh | 25 + include/sdf/sdf_config.h | 25 + include/sdf/system_util.hh | 29 +- sdf/1.0/CMakeLists.txt | 2 +- sdf/1.2/CMakeLists.txt | 2 +- sdf/1.3/CMakeLists.txt | 2 +- sdf/1.4/CMakeLists.txt | 2 +- sdf/1.5/CMakeLists.txt | 4 +- sdf/1.6/CMakeLists.txt | 4 +- sdf/1.7/CMakeLists.txt | 4 +- sdf/CMakeLists.txt | 6 +- src/CMakeLists.txt | 271 +- src/Filesystem.cc | 1 + src/cmd/CMakeLists.txt | 8 +- src/cmd/cmdsdformat.rb.in | 2 +- test/CMakeLists.txt | 29 +- test/integration/CMakeLists.txt | 8 +- .../all_symbols_have_version.bash.in | 2 +- test/performance/CMakeLists.txt | 4 +- test/test_config.h.in | 2 +- tools/check_test_ran.py | 79 - tools/code_check.sh | 67 - tools/cpplint.py | 6923 ----------------- tools/cpplint_to_cppcheckxml.py | 53 - 46 files changed, 307 insertions(+), 8837 deletions(-) delete mode 100644 cmake/CodeCoverage.cmake delete mode 100644 cmake/DefaultCFlags.cmake delete mode 100644 cmake/FindSSE.cmake delete mode 100644 cmake/HostCFlags.cmake delete mode 100644 cmake/Modules/FindTinyXML2.cmake delete mode 100644 cmake/SDFUtils.cmake delete mode 100644 cmake/SearchForStuff.cmake delete mode 100644 cmake/TargetArch.cmake delete mode 100644 cmake/cmake_uninstall.cmake.in delete mode 100644 cmake/cpack_options.cmake.in delete mode 100644 cmake/sdf_config.cmake.in delete mode 100644 cmake/sdf_cpack.cmake delete mode 100644 cmake/sdformat_pc.in create mode 100644 include/CMakeLists.txt rename cmake/sdf_config.h.in => include/sdf/config.hh.in (59%) create mode 100644 include/sdf/sdf.hh create mode 100644 include/sdf/sdf_config.h delete mode 100755 tools/check_test_ran.py delete mode 100755 tools/code_check.sh delete mode 100644 tools/cpplint.py delete mode 100644 tools/cpplint_to_cppcheckxml.py diff --git a/.github/ci/packages.apt b/.github/ci/packages.apt index 9596b3ee0..31db08f14 100644 --- a/.github/ci/packages.apt +++ b/.github/ci/packages.apt @@ -4,5 +4,5 @@ libignition-tools-dev libtinyxml2-dev liburdfdom-dev libxml2-utils -python-psutil +python3-psutil ruby-dev diff --git a/CMakeLists.txt b/CMakeLists.txt index b8a53b9b4..cb413fbca 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -4,350 +4,125 @@ if(COMMAND CMAKE_POLICY) CMAKE_POLICY(SET CMP0003 NEW) CMAKE_POLICY(SET CMP0004 NEW) endif(COMMAND CMAKE_POLICY) -enable_testing() -# with -fPIC -if(UNIX AND NOT WIN32) - set (CMAKE_INSTALL_PREFIX "/usr" CACHE STRING "Install Prefix") - find_program(CMAKE_UNAME uname /bin /usr/bin /usr/local/bin ) - if(CMAKE_UNAME) - exec_program(uname ARGS -m OUTPUT_VARIABLE CMAKE_SYSTEM_PROCESSOR) - set(CMAKE_SYSTEM_PROCESSOR ${CMAKE_SYSTEM_PROCESSOR} CACHE INTERNAL - "processor type (i386 and x86_64)") - if(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - ADD_DEFINITIONS(-fPIC) - endif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - endif(CMAKE_UNAME) -endif() +project (sdformat10 VERSION 10.6.0) -project (sdformat10) - -# The protocol version has nothing to do with the package version set below. -# It represents the current version of sdformat implement by the software +# The protocol version has nothing to do with the package version. +# It represents the current version of SDFormat implemented by the software set (SDF_PROTOCOL_VERSION 1.7) -set (SDF_MAJOR_VERSION 10) -set (SDF_MINOR_VERSION 6) -set (SDF_PATCH_VERSION 0) - -set (SDF_VERSION ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}) -set (SDF_VERSION_FULL ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}.${SDF_PATCH_VERSION}) - -string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) -string(REGEX REPLACE "[0-9]+" "" PROJECT_NAME_NO_VERSION ${PROJECT_NAME}) -string(TOLOWER ${PROJECT_NAME_NO_VERSION} PROJECT_NAME_NO_VERSION_LOWER) -set(PROJECT_EXPORT_NAME ${PROJECT_NAME_LOWER}) -set(PROJECT_LIBRARY_TARGET_NAME ${PROJECT_NAME_LOWER}) - -set (project_cmake_dir ${PROJECT_SOURCE_DIR}/cmake - CACHE PATH "Location of CMake scripts") - -message (STATUS "${PROJECT_NAME} version ${SDF_VERSION_FULL}") -set (CMAKE_INCLUDE_DIRECTORIES_PROJECT_BEFORE ON) - -#============================================================================ -# We turn off extensions because (1) we do not ever want to use non-standard -# compiler extensions, and (2) this variable is on by default, causing cmake -# to choose the flag -std=gnu++14 instead of -std=c++14 when the C++14 -# features are requested. Explicitly turning this flag off will force cmake to -# choose -std=c++14. -# See https://github.com/ignitionrobotics/ign-cmake/issues/13 for more info. -set(CMAKE_CXX_EXTENSIONS off) - -# Include GNUInstallDirs to get canonical paths -include(GNUInstallDirs) - -# Default test type for test all over source -set(TEST_TYPE "UNIT") - -# developer's option to cache PKG_CONFIG_PATH and -# LD_LIBRARY_PATH for local installs -if(PKG_CONFIG_PATH) - set (ENV{PKG_CONFIG_PATH} ${PKG_CONFIG_PATH}:$ENV{PKG_CONFIG_PATH}) -endif() -if(LD_LIBRARY_PATH) - set (ENV{LD_LIBRARY_PATH} ${LD_LIBRARY_PATH}:$ENV{LD_LIBRARY_PATH}) -endif() - -set (INCLUDE_INSTALL_DIR "${CMAKE_INSTALL_INCLUDEDIR}/sdformat-${SDF_VERSION}/sdf") -set (LIB_INSTALL_DIR ${CMAKE_INSTALL_LIBDIR} CACHE STRING "Installation directory for libraries (relative to CMAKE_INSTALL_PREFIX)") -set (BIN_INSTALL_DIR ${CMAKE_INSTALL_BINDIR} CACHE STRING "Installation directory for binaries (relative to CMAKE_INSTALL_PREFIX)") -set (USE_FULL_RPATH OFF CACHE BOOL "Set to true to enable full rpath") - -set(PKG_NAME SDFormat) -set(sdf_target sdformat${SDF_MAJOR_VERSION}) -set(sdf_config_install_dir "${LIB_INSTALL_DIR}/cmake/${PROJECT_NAME_LOWER}/") -set(sdf_import_target_name ${PROJECT_EXPORT_NAME}::${sdf_target}) -set(sdf_target_output_filename "${sdf_target}-targets.cmake") - - OPTION(SDFORMAT_DISABLE_CONSOLE_LOGFILE "Disable the sdformat console logfile" OFF) -if (USE_FULL_RPATH) - # use, i.e. don't skip the full RPATH for the build tree - set(CMAKE_SKIP_BUILD_RPATH FALSE) - - # when building, don't use the install RPATH already - # (but later on when installing) - set(CMAKE_BUILD_WITH_INSTALL_RPATH FALSE) - - set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/${LIB_INSTALL_DIR}") - - # add the automatically determined parts of the RPATH - # which point to directories outside the build tree to the install RPATH - set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) - - # the RPATH to be used when installing, but only if its not a system directory - list(FIND CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES "${CMAKE_INSTALL_PREFIX}/${LIB_INSTALL_DIR}" isSystemDir) - if("${isSystemDir}" STREQUAL "-1") - set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/${LIB_INSTALL_DIR}") - endif("${isSystemDir}" STREQUAL "-1") -endif() - +# BUILD_SDF is preserved for backwards compatibility but can be removed on the main branch set (BUILD_SDF ON CACHE INTERNAL "Build SDF" FORCE) -set (build_errors "" CACHE INTERNAL "build errors" FORCE) -set (build_warnings "" CACHE INTERNAL "build warnings" FORCE) - -set (sdf_cmake_dir ${PROJECT_SOURCE_DIR}/cmake CACHE PATH - "Location of CMake scripts") - -message (STATUS "\n\n====== Finding 3rd Party Packages ======") -include (${sdf_cmake_dir}/SDFUtils.cmake) -include (${sdf_cmake_dir}/SearchForStuff.cmake) -message (STATUS "----------------------------------------\n") - -##################################### -# Set the default build type -if (NOT CMAKE_BUILD_TYPE) - set (CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING - "Choose the type of build, options are: Debug Release RelWithDebInfo Profile Check" FORCE) -endif (NOT CMAKE_BUILD_TYPE) -string(TOUPPER ${CMAKE_BUILD_TYPE} CMAKE_BUILD_TYPE_UPPERCASE) - -set (BUILD_TYPE_PROFILE FALSE) -set (BUILD_TYPE_RELEASE FALSE) -set (BUILD_TYPE_RELWITHDEBINFO FALSE) -set (BUILD_TYPE_DEBUG FALSE) - -if ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "PROFILE") - set (BUILD_TYPE_PROFILE TRUE) -elseif ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "RELEASE") - set (BUILD_TYPE_RELEASE TRUE) -elseif ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "RELWITHDEBINFO") - set (BUILD_TYPE_RELWITHDEBINFO TRUE) -elseif ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "DEBUG") - set (BUILD_TYPE_DEBUG TRUE) -elseif ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "COVERAGE") - include (${project_cmake_dir}/CodeCoverage.cmake) - set (BUILD_TYPE_DEBUG TRUE) - SETUP_TARGET_FOR_COVERAGE(coverage ctest coverage) -else() - # NONE is a valid CMAKE_BUILD_TYPE - if (NOT "${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "NONE") - build_error("CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE} unknown. Valid options are: Debug Release RelWithDebInfo Profile Coverage None") - endif() -endif() - -##################################### -# Handle CFlags -unset (CMAKE_C_FLAGS_ALL CACHE) - -# USE_HOST_CFLAGS (default TRUE) -# Will check building host machine for proper cflags -if(NOT DEFINED USE_HOST_CFLAGS OR USE_HOST_CFLAGS) - message(STATUS "Enable host CFlags") - include (${project_cmake_dir}/HostCFlags.cmake) -endif() - -# USE_UPSTREAM_CFLAGS (default TRUE) -# Will use predefined ignition developers cflags -if(NOT DEFINED USE_UPSTREAM_CFLAGS OR USE_UPSTREAM_CFLAGS) - message(STATUS "Enable upstream CFlags") - include(${project_cmake_dir}/DefaultCFlags.cmake) -endif() - -# Check if warning options are avaliable for the compiler and return WARNING_CXX_FLAGS variable -if (MSVC) - set(WARN_LEVEL "/W4") - - # Unable to be filtered flags (failing due to limitations in filter_valid_compiler_warnings) - # Handling exceptions rightly and ignore unknown pragmas - set(UNFILTERED_FLAGS "/EHsc /wd4068") -else() - # Equivalent to Wall (according to man gcc) but removed the unknown pragmas since we use - # MSVC only pragmas all over the code - list(APPEND WARN_LEVEL -Waddress -Warray-bounds -Wcomment -Wformat -Wnonnull) - list(APPEND WARN_LEVEL -Wparentheses -Wreorder -Wreturn-type) - list(APPEND WARN_LEVEL -Wsequence-point -Wsign-compare -Wstrict-aliasing) - list(APPEND WARN_LEVEL -Wstrict-overflow=1 -Wswitch -Wtrigraphs -Wuninitialized) - list(APPEND WARN_LEVEL -Wunused-function -Wunused-label -Wunused-value) - list(APPEND WARN_LEVEL -Wunused-variable -Wvolatile-register-var) - - # Unable to be filtered flags (failing due to limitations in filter_valid_compiler_warnings) - set(UNFILTERED_FLAGS "-Wc++17-compat") -endif() - -filter_valid_compiler_warnings(${WARN_LEVEL} -Wextra -Wno-long-long - -Wno-unused-value -Wno-unused-value -Wno-unused-value -Wno-unused-value - -Wfloat-equal -Wshadow -Winit-self -Wswitch-default - -Wmissing-include-dirs -pedantic -Wno-pragmas) -set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}${WARNING_CXX_FLAGS} ${UNFILTERED_FLAGS}") ################################################# -# OS Specific initialization -if (UNIX) - sdf_setup_unix() -endif () - -if (WIN32) - sdf_setup_windows() -endif () - -if (APPLE) - sdf_setup_apple() -endif () - -################################################# -# Print warnings and errors -if ( build_warnings ) - message(WARNING "-- BUILD WARNINGS") - foreach (msg ${build_warnings}) - message(WARNING "-- ${msg}") - endforeach () - message(WARNING "-- END BUILD WARNINGS\n") -endif (build_warnings) - -########### Add uninstall target ############### -configure_file( - "${CMAKE_CURRENT_SOURCE_DIR}/cmake/cmake_uninstall.cmake.in" - "${CMAKE_CURRENT_BINARY_DIR}/cmake/cmake_uninstall.cmake" - IMMEDIATE @ONLY) -add_custom_target(uninstall - "${CMAKE_COMMAND}" -P - "${CMAKE_CURRENT_BINARY_DIR}/cmake/cmake_uninstall.cmake") - -if (build_errors) - message(SEND_ERROR "-- BUILD ERRORS: These must be resolved before compiling.") - foreach (msg ${build_errors}) - message(SEND_ERROR "-- ${msg}") - endforeach () - message(SEND_ERROR "-- END BUILD ERRORS\n") - message (FATAL_ERROR "Errors encountered in build. Please see the BUILD ERRORS above.") - -else (build_errors) - - ######################################## - # Write the config.h file - configure_file (${sdf_cmake_dir}/sdf_config.h.in - ${PROJECT_BINARY_DIR}/sdf/sdf_config.h) - sdf_install_includes("" ${PROJECT_BINARY_DIR}/sdf/sdf_config.h) - - message (STATUS "C Flags:${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE}}") - message (STATUS "Build Type: ${CMAKE_BUILD_TYPE}") - message (STATUS "Install path: ${CMAKE_INSTALL_PREFIX}") - - if (BUILD_SDF) - include_directories(include - ${PROJECT_BINARY_DIR} - ${PROJECT_BINARY_DIR}/include - ) - - link_directories(${PROJECT_BINARY_DIR}/src) - - if (NOT DEFINED BUILD_TESTING OR BUILD_TESTING) - set(BUILD_SDF_TEST TRUE) - else() - set(BUILD_SDF_TEST FALSE) - endif() - - if (BUILD_SDF_TEST) - add_subdirectory(test) +# Find ign-cmake +find_package(ignition-cmake2 2.10 REQUIRED) +set(IGN_CMAKE_VER ${ignition-cmake2_VERSION_MAJOR}) + +if (BUILD_SDF) + ign_configure_project( + NO_IGNITION_PREFIX + REPLACE_IGNITION_INCLUDE_PATH sdf) + + ################################################# + # Find tinyxml2. + ign_find_package(TINYXML2 REQUIRED) + + ################################################ + # Find urdfdom parser. Logic: + # + # 1. if USE_INTERNAL_URDF is unset, try to use system installation, fallback to internal copy + # 2. if USE_INTERNAL_URDF is set to True, use the internal copy + # 3. if USE_INTERNAL_URDF is set to False, force to search system installation, fail on error + if (NOT DEFINED USE_INTERNAL_URDF OR NOT USE_INTERNAL_URDF) + ign_find_package(IgnURDFDOM VERSION 1.0 QUIET) + if (NOT IgnURDFDOM_FOUND) + if (NOT DEFINED USE_INTERNAL_URDF) + # fallback to internal urdf + set(USE_INTERNAL_URDF ON) + else() + ign_build_error("Couldn't find the urdfdom >= 1.0 system installation") + endif() endif() - add_subdirectory(src) - add_subdirectory(include/sdf) - add_subdirectory(sdf) - add_subdirectory(conf) - add_subdirectory(doc) - endif(BUILD_SDF) - - ######################################## - # Setup Codecheck - include (IgnCodeCheck) - set(CPPCHECK_DIRS - ${PROJECT_SOURCE_DIR}/src - ${PROJECT_SOURCE_DIR}/include - ${PROJECT_SOURCE_DIR}/test/integration - ${PROJECT_SOURCE_DIR}/test/performance) - - set(CPPCHECK_INCLUDE_DIRS - ${PROJECT_BINARY_DIR} - ${PROJECT_SOURCE_DIR}/include - ${PROJECT_SOURCE_DIR}/test/integration - ${PROJECT_SOURCE_DIR}/test/performance) + endif() - # Ignore vendored directories. - file(WRITE ${PROJECT_BINARY_DIR}/cppcheck.suppress - "*:${PROJECT_SOURCE_DIR}/src/urdf/*\n" - ) - ign_setup_target_for_codecheck() + if (USE_INTERNAL_URDF) + message(STATUS "Using internal URDF") + endif() - ######################################## - # Make the package config file - configure_file(${CMAKE_SOURCE_DIR}/cmake/sdformat_pc.in - ${CMAKE_CURRENT_BINARY_DIR}/cmake/${PROJECT_NAME_LOWER}.pc @ONLY) - install(FILES ${CMAKE_CURRENT_BINARY_DIR}/cmake/${PROJECT_NAME_LOWER}.pc DESTINATION - ${LIB_INSTALL_DIR}/pkgconfig COMPONENT pkgconfig) + ################################################# + # Find ign command line utility: + find_program(IGN_PROGRAM ign) + + ################################################# + # Copied from catkin/cmake/empy.cmake + include(IgnPython) + function(find_python_module module) + # cribbed from http://www.cmake.org/pipermail/cmake/2011-January/041666.html + string(TOUPPER ${module} module_upper) + if(NOT PY_${module_upper}) + if(ARGC GREATER 1 AND ARGV1 STREQUAL "REQUIRED") + set(${module}_FIND_REQUIRED TRUE) + endif() + # A module's location is usually a directory, but for + # binary modules + # it's a .so file. + execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" "import re, ${module}; print(re.compile('/__init__.py.*').sub('',${module}.__file__))" + RESULT_VARIABLE _${module}_status + OUTPUT_VARIABLE _${module}_location + ERROR_QUIET OUTPUT_STRIP_TRAILING_WHITESPACE) + if(NOT _${module}_status) + set(PY_${module_upper} ${_${module}_location} CACHE STRING "Location of Python module ${module}") + endif(NOT _${module}_status) + endif(NOT PY_${module_upper}) + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(PY_${module} DEFAULT_MSG PY_${module_upper}) + endfunction(find_python_module) + + ################################################ + # Find psutil python package for memory tests + find_python_module(psutil) + if (NOT PY_PSUTIL) + ign_build_warning("Python psutil package not found. Memory leak tests will be skipped") + endif() - ######################################## - # Configure documentation uploader - configure_file("${CMAKE_SOURCE_DIR}/cmake/upload_doc.sh.in" - ${CMAKE_BINARY_DIR}/upload_doc.sh @ONLY) + ################################################ + # Find ruby executable to produce xml schemas + find_program(RUBY ruby) + if (NOT RUBY) + ign_build_error ("Ruby version 1.9 is needed to build xml schemas") + else() + message(STATUS "Found ruby executable: ${RUBY}") + endif() ######################################## - # Make the cmake config files - set(sdf_config_input "${CMAKE_CURRENT_SOURCE_DIR}/cmake/sdf_config.cmake.in") - set(sdf_config_output "cmake/${sdf_target}-config.cmake") - set(sdf_version_output "cmake/${sdf_target}-config-version.cmake") - set(sdf_config_install_dir "${LIB_INSTALL_DIR}/cmake/${PROJECT_NAME_LOWER}/") + # Find ignition math + # Set a variable for generating ProjectConfig.cmake + ign_find_package(ignition-math6 VERSION REQUIRED) + set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR}) - include(CMakePackageConfigHelpers) - #-------------------------------------- - # Configure and install the config file - configure_package_config_file( - ${sdf_config_input} - ${sdf_config_output} - INSTALL_DESTINATION ${sdf_config_install_dir} - NO_CHECK_REQUIRED_COMPONENTS_MACRO) - #-------------------------------------- - # Configure and install the version file - write_basic_package_version_file( - ${CMAKE_CURRENT_BINARY_DIR}/${sdf_version_output} - VERSION "${SDF_VERSION_FULL}" - COMPATIBILITY SameMajorVersion) + ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS) + ign_create_packages() - install(FILES - ${CMAKE_CURRENT_BINARY_DIR}/${sdf_config_output} - ${CMAKE_CURRENT_BINARY_DIR}/${sdf_version_output} - DESTINATION ${sdf_config_install_dir} - COMPONENT cmake) + add_subdirectory(sdf) + add_subdirectory(conf) + add_subdirectory(doc) +endif(BUILD_SDF) - ######################################## - # Package Creation: - include (${sdf_cmake_dir}/sdf_cpack.cmake) - set (CPACK_PACKAGE_VERSION "${SDF_VERSION_FULL}") - set (CPACK_PACKAGE_VERSION_MAJOR "${SDF_MAJOR_VERSION}") - set (CPACK_PACKAGE_VERSION_MINOR "${SDF_MINOR_VERSION}") - set (CPACK_PACKAGE_VERSION_PATCH "${SDF_PATCH_VERSION}") +######################################## +# Setup Codecheck - if (CPACK_GENERATOR) - message(STATUS "Found CPack generators: ${CPACK_GENERATOR}") +# Ignore vendored directories. +file(WRITE ${PROJECT_BINARY_DIR}/cppcheck.suppress + "*:${PROJECT_SOURCE_DIR}/src/urdf/*\n" + ) - configure_file("${sdf_cmake_dir}/cpack_options.cmake.in" - ${SDF_CPACK_CFG_FILE} @ONLY) - set(CPACK_PROJECT_CONFIG_FILE ${SDF_CPACK_CFG_FILE}) - include (CPack) - endif() +######################################## +# Configure documentation uploader +configure_file("${CMAKE_SOURCE_DIR}/cmake/upload_doc.sh.in" + ${CMAKE_BINARY_DIR}/upload_doc.sh @ONLY) - message(STATUS "Configuration successful. Type make to compile sdf") -endif(build_errors) +message(STATUS "Configuration successful. Type make to compile sdf") diff --git a/cmake/CodeCoverage.cmake b/cmake/CodeCoverage.cmake deleted file mode 100644 index 7eb4f7c56..000000000 --- a/cmake/CodeCoverage.cmake +++ /dev/null @@ -1,135 +0,0 @@ -# -# 2012-01-31, Lars Bilke -# - Enable Code Coverage -# -# 2013-09-17, Joakim Söderberg -# - Added support for Clang. -# - Some additional usage instructions. -# -# USAGE: -# 1. Copy this file into your cmake modules path. -# -# 2. Add the following line to your CMakeLists.txt: -# INCLUDE(CodeCoverage) -# -# 3. Set compiler flags to turn off optimization and enable coverage: -# SET(CMAKE_CXX_FLAGS "-g -O0 -fprofile-arcs -ftest-coverage") -# SET(CMAKE_C_FLAGS "-g -O0 -fprofile-arcs -ftest-coverage") -# -# 3. Use the function SETUP_TARGET_FOR_COVERAGE to create a custom make target -# which runs your test executable and produces a lcov code coverage report: -# Example: -# SETUP_TARGET_FOR_COVERAGE( -# my_coverage_target # Name for custom target. -# test_driver # Name of the test driver executable that runs the tests. -# # NOTE! This should always have a ZERO as exit code -# # otherwise the coverage generation will not complete. -# coverage # Name of output directory. -# ) -# -# 4. Build a Debug build: -# cmake -DCMAKE_BUILD_TYPE=Debug .. -# make -# make my_coverage_target -# -# - -# Check prereqs - -FIND_PROGRAM( GCOV_PATH NAMES gcov-8 gcov ) -FIND_PROGRAM( LCOV_PATH lcov ) -FIND_PROGRAM( GREP_PATH grep ) -FIND_PROGRAM( GENHTML_PATH genhtml ) -FIND_PROGRAM( GCOVR_PATH gcovr PATHS ${CMAKE_SOURCE_DIR}/tests) - -IF(NOT GCOV_PATH) - MESSAGE(FATAL_ERROR "gcov not found! Aborting...") -ENDIF() # NOT GCOV_PATH - -IF(NOT CMAKE_COMPILER_IS_GNUCXX) - # Clang version 3.0.0 and greater now supports gcov as well. - MESSAGE(WARNING "Compiler is not GNU gcc! Clang Version 3.0.0 and greater supports gcov as well, but older versions don't.") - - IF(NOT "${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") - MESSAGE(FATAL_ERROR "Compiler is not GNU gcc! Aborting...") - ENDIF() -ENDIF() # NOT CMAKE_COMPILER_IS_GNUCXX - -SET(CMAKE_CXX_FLAGS_COVERAGE - "-g -O0 --coverage -fprofile-arcs -ftest-coverage" - CACHE STRING "Flags used by the C++ compiler during coverage builds." - FORCE ) -SET(CMAKE_C_FLAGS_COVERAGE - "-g -O0 --coverage -fprofile-arcs -ftest-coverage" - CACHE STRING "Flags used by the C compiler during coverage builds." - FORCE ) -SET(CMAKE_EXE_LINKER_FLAGS_COVERAGE - "" - CACHE STRING "Flags used for linking binaries during coverage builds." - FORCE ) -SET(CMAKE_SHARED_LINKER_FLAGS_COVERAGE - "" - CACHE STRING "Flags used by the shared libraries linker during coverage builds." - FORCE ) -MARK_AS_ADVANCED( - CMAKE_CXX_FLAGS_COVERAGE - CMAKE_C_FLAGS_COVERAGE - CMAKE_EXE_LINKER_FLAGS_COVERAGE - CMAKE_SHARED_LINKER_FLAGS_COVERAGE ) - -IF ( NOT (CMAKE_BUILD_TYPE STREQUAL "Debug" OR CMAKE_BUILD_TYPE STREQUAL "Coverage")) - MESSAGE( WARNING "Code coverage results with an optimized (non-Debug) build may be misleading" ) -ENDIF() # NOT CMAKE_BUILD_TYPE STREQUAL "Debug" - - -# Param _targetname The name of new the custom make target -# Param _testrunner The name of the target which runs the tests. -# MUST return ZERO always, even on errors. -# If not, no coverage report will be created! -# Param _outputname lcov output is generated as _outputname.info -# HTML report is generated in _outputname/index.html -# Optional fourth parameter is passed as arguments to _testrunner -# Pass them in list form, e.g.: "-j;2" for -j 2 -FUNCTION(SETUP_TARGET_FOR_COVERAGE _targetname _testrunner _outputname) - - IF(NOT LCOV_PATH) - MESSAGE(FATAL_ERROR "lcov not found! Aborting...") - ENDIF() # NOT LCOV_PATH - - IF(NOT GENHTML_PATH) - MESSAGE(FATAL_ERROR "genhtml not found! Aborting...") - ENDIF() # NOT GENHTML_PATH - - IF(NOT GREP_PATH) - MESSAGE(FATAL_ERROR "grep not found! Run code coverage on linux or mac.") - ENDIF() - - # Setup target - ADD_CUSTOM_TARGET(${_targetname} - - COMMAND ${CMAKE_COMMAND} -E remove ${_outputname}.info.cleaned - ${_outputname}.info - # Capturing lcov counters and generating report - COMMAND ${LCOV_PATH} -q --no-checksum --directory ${PROJECT_BINARY_DIR} - --gcov-tool ${GCOV_PATH} --capture --output-file ${_outputname}.info 2>/dev/null - COMMAND ${LCOV_PATH} -q --remove ${_outputname}.info - --gcov-tool ${GCOV_PATH} '*/test/*' '/usr/*' '*_TEST*' --output-file ${_outputname}.info.cleaned - COMMAND ${GENHTML_PATH} -q --legend -o ${_outputname} - ${_outputname}.info.cleaned - COMMAND ${LCOV_PATH} --summary ${_outputname}.info.cleaned 2>&1 | grep "lines" | cut -d ' ' -f 4 | cut -d '%' -f 1 > coverage/lines.txt - COMMAND ${LCOV_PATH} --summary ${_outputname}.info.cleaned 2>&1 | grep "functions" | cut -d ' ' -f 4 | cut -d '%' -f 1 > coverage/functions.txt - COMMAND ${CMAKE_COMMAND} -E rename ${_outputname}.info.cleaned - ${_outputname}.info - - WORKING_DIRECTORY ${CMAKE_BINARY_DIR} - COMMENT "Resetting code coverage counters to zero.\n" - "Processing code coverage counters and generating report." - ) - - # Show info where to find the report - ADD_CUSTOM_COMMAND(TARGET ${_targetname} POST_BUILD - COMMAND COMMAND ${LCOV_PATH} -q --zerocounters --directory ${PROJECT_BINARY_DIR}; - COMMENT "Open ./${_outputname}/index.html in your browser to view the coverage report." - ) - -ENDFUNCTION() # SETUP_TARGET_FOR_COVERAGE diff --git a/cmake/DefaultCFlags.cmake b/cmake/DefaultCFlags.cmake deleted file mode 100644 index be57d0a3d..000000000 --- a/cmake/DefaultCFlags.cmake +++ /dev/null @@ -1,79 +0,0 @@ -# Build type link flags -set (CMAKE_LINK_FLAGS_RELEASE " " CACHE INTERNAL "Link flags for release" FORCE) -set (CMAKE_LINK_FLAGS_RELWITHDEBINFO " " CACHE INTERNAL "Link flags for release with debug support" FORCE) -set (CMAKE_LINK_FLAGS_DEBUG " " CACHE INTERNAL "Link flags for debug" FORCE) -set (CMAKE_LINK_FLAGS_PROFILE " -pg" CACHE INTERNAL "Link flags for profile" FORCE) -set (CMAKE_LINK_FLAGS_COVERAGE " --coverage" CACHE INTERNAL "Link flags for static code coverage" FORCE) - -set (CMAKE_C_FLAGS_RELEASE "") -if (NOT "${CMAKE_CXX_COMPILER_ID} " STREQUAL "Clang " AND NOT MSVC) - # -s doesn't work with clang or Visual Studio, see alternative in link below: - # http://stackoverflow.com/questions/6085491/gcc-vs-clang-symbol-strippingu - set (CMAKE_C_FLAGS_RELEASE "-s") -endif() - -if (NOT MSVC) - set (CMAKE_C_FLAGS_RELEASE " ${CMAKE_C_FLAGS_RELEASE} -O3 -DNDEBUG ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for release" FORCE) - set (CMAKE_CXX_FLAGS_RELEASE ${CMAKE_C_FLAGS_RELEASE}) - - set (CMAKE_C_FLAGS_RELWITHDEBINFO " -g -O2 ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for release with debug support" FORCE) - set (CMAKE_CXX_FLAGS_RELWITHDEBINFO ${CMAKE_C_FLAGS_RELWITHDEBINFO}) - - set (CMAKE_C_FLAGS_DEBUG " -ggdb3 ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for debug" FORCE) - set (CMAKE_CXX_FLAGS_DEBUG ${CMAKE_C_FLAGS_DEBUG}) - - set (CMAKE_C_FLAGS_PROFILE " -fno-omit-frame-pointer -g -pg ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for profile" FORCE) - set (CMAKE_CXX_FLAGS_PROFILE ${CMAKE_C_FLAGS_PROFILE}) - - set (CMAKE_C_FLAGS_COVERAGE " -g -O0 -Wformat=2 --coverage -fno-inline ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for static code coverage" FORCE) - set (CMAKE_CXX_FLAGS_COVERAGE "${CMAKE_C_FLAGS_COVERAGE}") - foreach(flag - -fno-default-inline - -fno-elide-constructors - -fno-implicit-inline-templates) - CHECK_CXX_COMPILER_FLAG(${flag} R${flag}) - if (R${flag}) - set (CMAKE_CXX_FLAGS_COVERAGE "${CMAKE_CXX_FLAGS_COVERAGE} ${flag}") - endif() - endforeach() -endif() - -##################################### -# Set all the global build flags -set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${CMAKE_C_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") -set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") -set (CMAKE_CXX_EXTENSIONS off) -set (CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") -set (CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} ${CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") -set (CMAKE_MODULE_LINKER_FLAGS "${CMAKE_MODULE_LINKER_FLAGS} ${CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") - -set(CMAKE_CXX_STANDARD 17) -set(CMAKE_CXX_STANDARD_REQUIRED ON) - -if (UNIX) - # Add visibility in UNIX - check_gcc_visibility() - if (GCC_SUPPORTS_VISIBILITY) - SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fvisibility=hidden") - endif() -endif() - -# Compiler-specific C++17 activation. -if ("${CMAKE_CXX_COMPILER_ID} " MATCHES "GNU ") - execute_process( - COMMAND ${CMAKE_CXX_COMPILER} -dumpversion OUTPUT_VARIABLE GCC_VERSION) - if (NOT (GCC_VERSION VERSION_GREATER_EQUAL 7.0)) - message(STATUS "Found version ${GCC_VERSION}") - message(FATAL_ERROR "${PROJECT_NAME} requires g++ 7.0 or greater.") - endif () -elseif ("${CMAKE_CXX_COMPILER_ID} " MATCHES "Clang ") - if(APPLE) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -stdlib=libc++") - endif() -elseif ("${CMAKE_CXX_COMPILER_ID} " STREQUAL "MSVC ") - if (MSVC_VERSION LESS 1914) - message(FATAL_ERROR "${PROJECT_NAME} requires VS 2017 or greater.") - endif() -else () - message(FATAL_ERROR "Your C++ compiler does not support C++17.") -endif () diff --git a/cmake/FindSSE.cmake b/cmake/FindSSE.cmake deleted file mode 100644 index cdbcfcc3d..000000000 --- a/cmake/FindSSE.cmake +++ /dev/null @@ -1,115 +0,0 @@ -# Check if SSE instructions are available on the machine where -# the project is compiled. - -IF (ARCH MATCHES "i386" OR ARCH MATCHES "x86_64") - IF(CMAKE_SYSTEM_NAME MATCHES "Linux") - EXEC_PROGRAM(cat ARGS "/proc/cpuinfo" OUTPUT_VARIABLE CPUINFO) - - STRING(REGEX REPLACE "^.*(sse2).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "sse2" "${SSE_THERE}" SSE2_TRUE) - IF (SSE2_TRUE) - set(SSE2_FOUND true CACHE BOOL "SSE2 available on host") - ELSE (SSE2_TRUE) - set(SSE2_FOUND false CACHE BOOL "SSE2 available on host") - ENDIF (SSE2_TRUE) - - # /proc/cpuinfo apparently omits sse3 :( - STRING(REGEX REPLACE "^.*[^s](sse3).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "sse3" "${SSE_THERE}" SSE3_TRUE) - IF (NOT SSE3_TRUE) - STRING(REGEX REPLACE "^.*(T2300).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "T2300" "${SSE_THERE}" SSE3_TRUE) - ENDIF (NOT SSE3_TRUE) - - STRING(REGEX REPLACE "^.*(ssse3).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "ssse3" "${SSE_THERE}" SSSE3_TRUE) - IF (SSE3_TRUE OR SSSE3_TRUE) - set(SSE3_FOUND true CACHE BOOL "SSE3 available on host") - ELSE (SSE3_TRUE OR SSSE3_TRUE) - set(SSE3_FOUND false CACHE BOOL "SSE3 available on host") - ENDIF (SSE3_TRUE OR SSSE3_TRUE) - IF (SSSE3_TRUE) - set(SSSE3_FOUND true CACHE BOOL "SSSE3 available on host") - ELSE (SSSE3_TRUE) - set(SSSE3_FOUND false CACHE BOOL "SSSE3 available on host") - ENDIF (SSSE3_TRUE) - - STRING(REGEX REPLACE "^.*(sse4_1).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "sse4_1" "${SSE_THERE}" SSE41_TRUE) - IF (SSE41_TRUE) - set(SSE4_1_FOUND true CACHE BOOL "SSE4.1 available on host") - ELSE (SSE41_TRUE) - set(SSE4_1_FOUND false CACHE BOOL "SSE4.1 available on host") - ENDIF (SSE41_TRUE) - - STRING(REGEX REPLACE "^.*(sse4_2).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "sse4_2" "${SSE_THERE}" SSE42_TRUE) - IF (SSE42_TRUE) - set(SSE4_2_FOUND true CACHE BOOL "SSE4.2 available on host") - ELSE (SSE42_TRUE) - set(SSE4_2_FOUND false CACHE BOOL "SSE4.2 available on host") - ENDIF (SSE42_TRUE) - - ELSEIF(CMAKE_SYSTEM_NAME MATCHES "Darwin") - EXEC_PROGRAM("/usr/sbin/sysctl -n machdep.cpu.features" OUTPUT_VARIABLE - CPUINFO) - - STRING(REGEX REPLACE "^.*[^S](SSE2).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "SSE2" "${SSE_THERE}" SSE2_TRUE) - IF (SSE2_TRUE) - set(SSE2_FOUND true CACHE BOOL "SSE2 available on host") - ELSE (SSE2_TRUE) - set(SSE2_FOUND false CACHE BOOL "SSE2 available on host") - ENDIF (SSE2_TRUE) - - STRING(REGEX REPLACE "^.*[^S](SSE3).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "SSE3" "${SSE_THERE}" SSE3_TRUE) - IF (SSE3_TRUE) - set(SSE3_FOUND true CACHE BOOL "SSE3 available on host") - ELSE (SSE3_TRUE) - set(SSE3_FOUND false CACHE BOOL "SSE3 available on host") - ENDIF (SSE3_TRUE) - - STRING(REGEX REPLACE "^.*(SSSE3).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "SSSE3" "${SSE_THERE}" SSSE3_TRUE) - IF (SSSE3_TRUE) - set(SSSE3_FOUND true CACHE BOOL "SSSE3 available on host") - ELSE (SSSE3_TRUE) - set(SSSE3_FOUND false CACHE BOOL "SSSE3 available on host") - ENDIF (SSSE3_TRUE) - - STRING(REGEX REPLACE "^.*(SSE4.1).*$" "\\1" SSE_THERE ${CPUINFO}) - STRING(COMPARE EQUAL "SSE4.1" "${SSE_THERE}" SSE41_TRUE) - IF (SSE41_TRUE) - set(SSE4_1_FOUND true CACHE BOOL "SSE4.1 available on host") - ELSE (SSE41_TRUE) - set(SSE4_1_FOUND false CACHE BOOL "SSE4.1 available on host") - ENDIF (SSE41_TRUE) - ELSEIF(CMAKE_SYSTEM_NAME MATCHES "Windows") - # TODO - set(SSE2_FOUND true CACHE BOOL "SSE2 available on host") - set(SSE3_FOUND false CACHE BOOL "SSE3 available on host") - set(SSSE3_FOUND false CACHE BOOL "SSSE3 available on host") - set(SSE4_1_FOUND false CACHE BOOL "SSE4.1 available on host") - ELSE(CMAKE_SYSTEM_NAME MATCHES "Linux") - set(SSE2_FOUND true CACHE BOOL "SSE2 available on host") - set(SSE3_FOUND false CACHE BOOL "SSE3 available on host") - set(SSSE3_FOUND false CACHE BOOL "SSSE3 available on host") - set(SSE4_1_FOUND false CACHE BOOL "SSE4.1 available on host") - ENDIF(CMAKE_SYSTEM_NAME MATCHES "Linux") -ENDIF(ARCH MATCHES "i386" OR ARCH MATCHES "x86_64") - -if(NOT SSE2_FOUND) - MESSAGE(STATUS "Could not find hardware support for SSE2 on this machine.") -endif(NOT SSE2_FOUND) -if(NOT SSE3_FOUND) - MESSAGE(STATUS "Could not find hardware support for SSE3 on this machine.") -endif(NOT SSE3_FOUND) -if(NOT SSSE3_FOUND) - MESSAGE(STATUS "Could not find hardware support for SSSE3 on this machine.") -endif(NOT SSSE3_FOUND) -if(NOT SSE4_1_FOUND) - MESSAGE(STATUS "Could not find hardware support for SSE4.1 on this machine.") -endif(NOT SSE4_1_FOUND) - -mark_as_advanced(SSE2_FOUND SSE3_FOUND SSSE3_FOUND SSE4_1_FOUND) diff --git a/cmake/HostCFlags.cmake b/cmake/HostCFlags.cmake deleted file mode 100644 index f38d8d7fd..000000000 --- a/cmake/HostCFlags.cmake +++ /dev/null @@ -1,27 +0,0 @@ -include (${project_cmake_dir}/FindSSE.cmake) - -if (SSE2_FOUND) - set (CMAKE_C_FLAGS_ALL "-msse -msse2 ${CMAKE_C_FLAGS_ALL}") - if (NOT APPLE) - set (CMAKE_C_FLAGS_ALL "-mfpmath=sse ${CMAKE_C_FLAGS_ALL}") - endif() -endif() - -if (SSE3_FOUND) - set (CMAKE_C_FLAGS_ALL "-msse3 ${CMAKE_C_FLAGS_ALL}") -endif() -if (SSSE3_FOUND) - set (CMAKE_C_FLAGS_ALL "-mssse3 ${CMAKE_C_FLAGS_ALL}") -endif() - -if (SSE4_1_FOUND OR SSE4_2_FOUND) - if (SSE4_1_FOUND) - set (CMAKE_C_FLAGS_ALL "-msse4.1 ${CMAKE_C_FLAGS_ALL}") - endif() - if (SSE4_2_FOUND) - set (CMAKE_C_FLAGS_ALL "-msse4.2 ${CMAKE_C_FLAGS_ALL}") - endif() -else() - message(STATUS "\nSSE4 disabled.\n") -endif() - diff --git a/cmake/Modules/FindTinyXML2.cmake b/cmake/Modules/FindTinyXML2.cmake deleted file mode 100644 index fd3571e9b..000000000 --- a/cmake/Modules/FindTinyXML2.cmake +++ /dev/null @@ -1,42 +0,0 @@ -# CMake Logic to find system TinyXML2, sourced from: -# ros2/tinyxml2_vendor -# https://github.com/ros2/tinyxml2_vendor/commit/fde8000d31d68ff555431d63af3c324afba9f117#diff-120198e331f1dd3e7806c31af0cfb425 - -# The CMake Logic here is licensed under Apache License 2.0 -# TinyXML2 itself is licensed under the zlib License - -# TinyXML2_FOUND -# TinyXML2_INCLUDE_DIRS -# TinyXML2_LIBRARIES - -# try to find the CMake config file for TinyXML2 first -find_package(TinyXML2 CONFIG NAMES tinyxml2 QUIET) -if(TinyXML2_FOUND) - message(STATUS "Found TinyXML2 via Config file: ${TinyXML2_DIR}") - if(NOT TINYXML2_LIBRARY) - # in this case, we're probably using TinyXML2 version 5.0.0 or greater - # in which case tinyxml2 is an exported target and we should use that - if(TARGET tinyxml2) - set(TINYXML2_LIBRARY tinyxml2) - elseif(TARGET tinyxml2::tinyxml2) - set(TINYXML2_LIBRARY tinyxml2::tinyxml2) - endif() - endif() -else() - find_path(TINYXML2_INCLUDE_DIR NAMES tinyxml2.h) - - find_library(TINYXML2_LIBRARY tinyxml2) - - include(FindPackageHandleStandardArgs) - find_package_handle_standard_args(TinyXML2 DEFAULT_MSG TINYXML2_LIBRARY TINYXML2_INCLUDE_DIR) - - mark_as_advanced(TINYXML2_INCLUDE_DIR TINYXML2_LIBRARY) -endif() - -# Set mixed case INCLUDE_DIRS and LIBRARY variables from upper case ones. -if(NOT TinyXML2_INCLUDE_DIRS) - set(TinyXML2_INCLUDE_DIRS ${TINYXML2_INCLUDE_DIR}) -endif() -if(NOT TinyXML2_LIBRARIES) - set(TinyXML2_LIBRARIES ${TINYXML2_LIBRARY}) -endif() diff --git a/cmake/SDFUtils.cmake b/cmake/SDFUtils.cmake deleted file mode 100644 index 525c4d4c6..000000000 --- a/cmake/SDFUtils.cmake +++ /dev/null @@ -1,251 +0,0 @@ -################################################################################ -#APPEND_TO_CACHED_STRING(_string _cacheDesc [items...]) -# Appends items to a cached list. -MACRO (APPEND_TO_CACHED_STRING _string _cacheDesc) - FOREACH (newItem ${ARGN}) - SET (${_string} "${${_string}} ${newItem}" CACHE INTERNAL ${_cacheDesc} FORCE) - ENDFOREACH (newItem ${ARGN}) - #STRING(STRIP ${${_string}} ${_string}) -ENDMACRO (APPEND_TO_CACHED_STRING) - -################################################################################ -# APPEND_TO_CACHED_LIST (_list _cacheDesc [items...] -# Appends items to a cached list. -MACRO (APPEND_TO_CACHED_LIST _list _cacheDesc) - SET (tempList ${${_list}}) - FOREACH (newItem ${ARGN}) - LIST (APPEND tempList ${newItem}) - ENDFOREACH (newItem ${newItem}) - SET (${_list} ${tempList} CACHE INTERNAL ${_cacheDesc} FORCE) -ENDMACRO(APPEND_TO_CACHED_LIST) - -################################################# -# Macro to turn a list into a string (why doesn't CMake have this built-in?) -MACRO (LIST_TO_STRING _string _list) - SET (${_string}) - FOREACH (_item ${_list}) - SET (${_string} "${${_string}} ${_item}") - ENDFOREACH (_item) - #STRING(STRIP ${${_string}} ${_string}) -ENDMACRO (LIST_TO_STRING) - -################################################# -# BUILD ERROR macro -macro (BUILD_ERROR) - foreach (str ${ARGN}) - SET (msg "\t${str}") - MESSAGE (STATUS ${msg}) - APPEND_TO_CACHED_LIST(build_errors "build errors" ${msg}) - endforeach () -endmacro (BUILD_ERROR) - -################################################# -# BUILD WARNING macro -macro (BUILD_WARNING) - foreach (str ${ARGN}) - SET (msg "\t${str}" ) - MESSAGE (STATUS ${msg} ) - APPEND_TO_CACHED_LIST(build_warnings "build warning" ${msg}) - endforeach (str ${ARGN}) -endmacro (BUILD_WARNING) - -################################################# -macro (sdf_add_library _name) - set(LIBS_DESTINATION ${PROJECT_BINARY_DIR}/src) - set_source_files_properties(${ARGN} PROPERTIES COMPILE_DEFINITIONS "BUILDING_DLL") - add_library(${_name} SHARED ${ARGN}) - set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${LIBS_DESTINATION}) - if (MSVC) - set_target_properties( ${_name} PROPERTIES ARCHIVE_OUTPUT_DIRECTORY ${LIBS_DESTINATION}) - set_target_properties( ${_name} PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_DEBUG ${LIBS_DESTINATION}) - set_target_properties( ${_name} PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_RELEASE ${LIBS_DESTINATION}) - endif () -endmacro () - -################################################# -macro (sdf_add_executable _name) - add_executable(${_name} ${ARGN}) -endmacro () - - -################################################# -macro (sdf_install_includes _subdir) - install(FILES ${ARGN} DESTINATION ${INCLUDE_INSTALL_DIR}/${_subdir} COMPONENT headers) -endmacro() - -################################################# -macro (sdf_install_library _name) - set_target_properties(${_name} PROPERTIES SOVERSION ${SDF_MAJOR_VERSION} VERSION ${SDF_VERSION_FULL}) - install ( - TARGETS ${_name} - EXPORT ${_name} - ARCHIVE DESTINATION ${LIB_INSTALL_DIR} - LIBRARY DESTINATION ${LIB_INSTALL_DIR} - RUNTIME DESTINATION ${BIN_INSTALL_DIR} - COMPONENT shlib) - -# Export and install target -export( - EXPORT ${_name} - FILE ${PROJECT_BINARY_DIR}/cmake/${sdf_target_output_filename} - NAMESPACE ${PROJECT_EXPORT_NAME}::) - -install( - EXPORT ${_name} - DESTINATION ${sdf_config_install_dir} - FILE ${sdf_target_output_filename} - NAMESPACE ${PROJECT_EXPORT_NAME}::) - -endmacro () - -################################################# -macro (sdf_install_executable _name) - set_target_properties(${_name} PROPERTIES VERSION ${SDF_VERSION_FULL}) - install (TARGETS ${_name} DESTINATION ${BIN_INSTALL_DIR}) -endmacro () - -################################################# -macro (sdf_setup_unix) -endmacro() - -################################################# -macro (sdf_setup_windows) - # Need for M_PI constant - add_definitions(-D_USE_MATH_DEFINES -DWINDOWS_LEAN_AND_MEAN) - # And force linking to MSVC dynamic runtime - set(CMAKE_C_FLAGS_DEBUG "/MDd ${CMAKE_C_FLAGS_DEBUG}") - set(CMAKE_C_FLAGS_RELEASE "/MD ${CMAKE_C_FLAGS_RELEASE}") -endmacro() - -################################################# -macro (sdf_setup_apple) - set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -Wl,-undefined -Wl,dynamic_lookup") -endmacro() - -################################################# -# VAR: SDF_BUILD_TESTS_EXTRA_EXE_SRCS -# Hack: extra sources to build binaries can be supplied to gz_build_tests in -# the variable SDF_BUILD_TESTS_EXTRA_EXE_SRCS. This variable will be clean up -# at the end of the function -# -include_directories(${PROJECT_SOURCE_DIR}/test/gtest/include) -macro (sdf_build_tests) - # Build all the tests - foreach(GTEST_SOURCE_file ${ARGN}) - string(REGEX REPLACE ".cc" "" BINARY_NAME ${GTEST_SOURCE_file}) - set(BINARY_NAME ${TEST_TYPE}_${BINARY_NAME}) - - add_executable(${BINARY_NAME} - ${GTEST_SOURCE_file} - ${SDF_BUILD_TESTS_EXTRA_EXE_SRCS} - ) - - add_dependencies(${BINARY_NAME} - gtest gtest_main ${sdf_target} - ) - - link_directories(${IGNITION-MATH_LIBRARY_DIRS}) - target_link_libraries(${BINARY_NAME} ${tinyxml2_LIBRARIES}) - - if (UNIX) - target_link_libraries(${BINARY_NAME} PRIVATE - libgtest.a - libgtest_main.a - ${sdf_target} - pthread - ${IGNITION-MATH_LIBRARIES} - ) - elseif(WIN32) - target_link_libraries(${BINARY_NAME} PRIVATE - gtest.lib - gtest_main.lib - ${sdf_target} - ${IGNITION-MATH_LIBRARIES} - ) - - # Copy in sdformat library - add_custom_command(TARGET ${BINARY_NAME} - COMMAND ${CMAKE_COMMAND} -E copy_if_different - $ - $ VERBATIM) - - endif() - - add_test(${BINARY_NAME} ${CMAKE_CURRENT_BINARY_DIR}/${BINARY_NAME} - --gtest_output=xml:${CMAKE_BINARY_DIR}/test_results/${BINARY_NAME}.xml) - - set (_env_vars) - set (sdf_paths) - - # Get all the sdf protocol directory names - file(GLOB dirs RELATIVE "${PROJECT_SOURCE_DIR}/sdf" - "${PROJECT_SOURCE_DIR}/sdf/*") - list(SORT dirs) - - # Add each sdf protocol to the sdf_path variable - foreach(dir ${dirs}) - if (IS_DIRECTORY ${PROJECT_SOURCE_DIR}/sdf/${dir}) - set(sdf_paths "${PROJECT_SOURCE_DIR}/sdf/${dir}:${sdf_paths}") - endif() - endforeach() - - # Set the SDF_PATH environment variable - list(APPEND _env_vars "SDF_PATH=${sdf_paths}") - - set_tests_properties(${BINARY_NAME} PROPERTIES - TIMEOUT 240 - ENVIRONMENT "${_env_vars}") - - if(PYTHONINTERP_FOUND) - # Check that the test produced a result and create a failure if it didn't. - # Guards against crashed and timed out tests. - add_test(check_${BINARY_NAME} ${PYTHON_EXECUTABLE} ${PROJECT_SOURCE_DIR}/tools/check_test_ran.py - ${CMAKE_BINARY_DIR}/test_results/${BINARY_NAME}.xml) - endif() - - if(SDFORMAT_RUN_VALGRIND_TESTS AND VALGRIND_PROGRAM) - add_test(memcheck_${BINARY_NAME} ${VALGRIND_PROGRAM} --leak-check=full - --error-exitcode=1 --show-leak-kinds=all ${CMAKE_CURRENT_BINARY_DIR}/${BINARY_NAME}) - endif() - endforeach() - - set(GZ_BUILD_TESTS_EXTRA_EXE_SRCS "") -endmacro() - -################################################# -# Macro to setup supported compiler warnings -# Based on work of Florent Lamiraux, Thomas Moulard, JRL, CNRS/AIST. -include(CheckCXXCompilerFlag) - -macro(filter_valid_compiler_warnings) - foreach(flag ${ARGN}) - CHECK_CXX_COMPILER_FLAG(${flag} R${flag}) - if(${R${flag}}) - set(WARNING_CXX_FLAGS "${WARNING_CXX_FLAGS} ${flag}") - endif() - endforeach() -endmacro() - -################################################# -# Copied from catkin/cmake/empy.cmake -function(find_python_module module) - # cribbed from http://www.cmake.org/pipermail/cmake/2011-January/041666.html - string(TOUPPER ${module} module_upper) - if(NOT PY_${module_upper}) - if(ARGC GREATER 1 AND ARGV1 STREQUAL "REQUIRED") - set(${module}_FIND_REQUIRED TRUE) - endif() - # A module's location is usually a directory, but for - # binary modules - # it's a .so file. - execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" "import re, ${module}; print(re.compile('/__init__.py.*').sub('',${module}.__file__))" - RESULT_VARIABLE _${module}_status - OUTPUT_VARIABLE _${module}_location - ERROR_QUIET OUTPUT_STRIP_TRAILING_WHITESPACE) - if(NOT _${module}_status) - set(PY_${module_upper} ${_${module}_location} CACHE STRING "Location of Python module ${module}") - endif(NOT _${module}_status) - endif(NOT PY_${module_upper}) - include(FindPackageHandleStandardArgs) - find_package_handle_standard_args(PY_${module} DEFAULT_MSG PY_${module_upper}) -endfunction(find_python_module) diff --git a/cmake/SearchForStuff.cmake b/cmake/SearchForStuff.cmake deleted file mode 100644 index b46ead127..000000000 --- a/cmake/SearchForStuff.cmake +++ /dev/null @@ -1,120 +0,0 @@ -include (FindPkgConfig) - -# Detect the architecture -include (${project_cmake_dir}/TargetArch.cmake) -target_architecture(ARCH) -message(STATUS "Building for arch: ${ARCH}") - -################################################# -# Find tinyxml2. -list(INSERT CMAKE_MODULE_PATH 0 "${CMAKE_CURRENT_SOURCE_DIR}/cmake/Modules") -find_package(TinyXML2 REQUIRED) - -################################################ -# Find urdfdom parser. Logic: -# -# 1. if USE_INTERNAL_URDF is unset, try to use system installation, fallback to internal copy -# 2. if USE_INTERNAL_URDF is set to True, use the internal copy -# 3. if USE_INTERNAL_URDF is set to False, force to search system installation, fail on error - -if (NOT PKG_CONFIG_FOUND) - if (NOT DEFINED USE_INTERNAL_URDF) - BUILD_WARNING("Couldn't find pkg-config for urdfdom, using internal copy") - set(USE_INTERNAL_URDF true) - elseif(NOT USE_INTERNAL_URDF) - BUILD_ERROR("Couldn't find pkg-config for urdfdom") - endif() -endif() - -if (NOT DEFINED USE_INTERNAL_URDF OR NOT USE_INTERNAL_URDF) - # check for urdfdom with pkg-config - pkg_check_modules(URDF urdfdom>=1.0) - - if (NOT URDF_FOUND) - find_package(urdfdom) - if (urdfdom_FOUND) - set(URDF_INCLUDE_DIRS ${urdfdom_INCLUDE_DIRS}) - # ${urdfdom_LIBRARIES} already contains absolute library filenames - set(URDF_LIBRARY_DIRS "") - set(URDF_LIBRARIES ${urdfdom_LIBRARIES}) - elseif (NOT DEFINED USE_INTERNAL_URDF) - message(STATUS "Couldn't find urdfdom >= 1.0, using internal copy") - set(USE_INTERNAL_URDF true) - else() - BUILD_ERROR("Couldn't find the urdfdom >= 1.0 system installation") - endif() - else() - # what am I doing here? pkg-config and cmake - set(URDF_INCLUDE_DIRS ${URDF_INCLUDEDIR}) - set(URDF_LIBRARY_DIRS ${URDF_LIBDIR}) - endif() -endif() - -################################################# -# Find ign command line utility: -find_package(ignition-tools) -if (IGNITION-TOOLS_BINARY_DIRS) - message(STATUS "Looking for ignition-tools-config.cmake - found") -else() - BUILD_WARNING ("ignition-tools not found, for command line utilities and for \ -generating aggregated SDFormat descriptions for sdformat.org, please install \ -ignition-tools.") -endif() - -################################################ -# Find the Python interpreter for running the -# check_test_ran.py script -find_package(PythonInterp 3 QUIET) - -################################################ -# Find psutil python package for memory tests -find_python_module(psutil) -if(NOT PY_PSUTIL) - BUILD_WARNING("Python psutil package not found. Memory leak tests will be skipped") -endif() - -################################################ -# Find Valgrind for checking memory leaks in the -# tests -find_program(VALGRIND_PROGRAM NAMES valgrind PATH ${VALGRIND_ROOT}/bin) -option(SDFORMAT_RUN_VALGRIND_TESTS "Run sdformat tests with Valgrind" FALSE) -mark_as_advanced(SDFORMAT_RUN_VALGRIND_TESTS) -if (SDFORMAT_RUN_VALGRIND_TESTS AND NOT VALGRIND_PROGRAM) - BUILD_WARNING("valgrind not found. Memory check tests will be skipped.") -endif() - -################################################ -# Find ruby executable to produce xml schemas -find_program(RUBY ruby) -if (NOT RUBY) - BUILD_ERROR ("Ruby version 1.9 is needed to build xml schemas") -else() - message(STATUS "Found ruby executable: ${RUBY}") -endif() - -################################################# -# Macro to check for visibility capability in compiler -# Original idea from: https://gitorious.org/ferric-cmake-stuff/ -macro (check_gcc_visibility) - include (CheckCXXCompilerFlag) - check_cxx_compiler_flag(-fvisibility=hidden GCC_SUPPORTS_VISIBILITY) -endmacro() - -######################################## -# Find ignition cmake2 -# Only for using the testing macros and creating the codecheck target, not -# really being use to configure the whole project -find_package(ignition-cmake2 2.3 REQUIRED) -set(IGN_CMAKE_VER ${ignition-cmake2_VERSION_MAJOR}) - -######################################## -# Find ignition math -# Set a variable for generating ProjectConfig.cmake -find_package(ignition-math6 QUIET) -if (NOT ignition-math6_FOUND) - message(STATUS "Looking for ignition-math6-config.cmake - not found") - BUILD_ERROR ("Missing: Ignition math (libignition-math6-dev)") -else() - set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR}) - message(STATUS "Looking for ignition-math${IGN_MATH_VER}-config.cmake - found") -endif() diff --git a/cmake/TargetArch.cmake b/cmake/TargetArch.cmake deleted file mode 100644 index d50073c82..000000000 --- a/cmake/TargetArch.cmake +++ /dev/null @@ -1,158 +0,0 @@ -# Copyright (c) 2012 Petroules Corporation. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# Redistributions of source code must retain the above copyright notice, this -# list of conditions and the following disclaimer. Redistributions in binary -# form must reproduce the above copyright notice, this list of conditions and -# the following disclaimer in the documentation and/or other materials -# provided with the distribution. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND -# ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED -# WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR -# ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -# (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON -# ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT -# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS -# SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - -# Based on the Qt 5 processor detection code, so should be very accurate -# https://qt.gitorious.org/qt/qtbase/blobs/master/src/corelib/global/qprocessordetection.h -# Currently handles arm (v5, v6, v7), x86 (32/64), ia64, and ppc (32/64) - -# Regarding POWER/PowerPC, just as is noted in the Qt source, -# "There are many more known variants/revisions that we do not handle/detect." - - - -set(archdetect_c_code " -#if defined(__arm__) || defined(__TARGET_ARCH_ARM) - #if defined(__ARM_ARCH_7__) \\ - || defined(__ARM_ARCH_7A__) \\ - || defined(__ARM_ARCH_7R__) \\ - || defined(__ARM_ARCH_7M__) \\ - || (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 7) - #error cmake_ARCH armv7 - #elif defined(__ARM_ARCH_6__) \\ - || defined(__ARM_ARCH_6J__) \\ - || defined(__ARM_ARCH_6T2__) \\ - || defined(__ARM_ARCH_6Z__) \\ - || defined(__ARM_ARCH_6K__) \\ - || defined(__ARM_ARCH_6ZK__) \\ - || defined(__ARM_ARCH_6M__) \\ - || (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 6) - #error cmake_ARCH armv6 - #elif defined(__ARM_ARCH_5TEJ__) \\ - || (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 5) - #error cmake_ARCH armv5 - #else - #error cmake_ARCH arm - #endif -#elif defined(__i386) || defined(__i386__) || defined(_M_IX86) - #error cmake_ARCH i386 -#elif defined(__x86_64) || defined(__x86_64__) || defined(__amd64) || defined(_M_X64) - #error cmake_ARCH x86_64 -#elif defined(__ia64) || defined(__ia64__) || defined(_M_IA64) - #error cmake_ARCH ia64 -#elif defined(__ppc__) || defined(__ppc) || defined(__powerpc__) \\ - || defined(_ARCH_COM) || defined(_ARCH_PWR) || defined(_ARCH_PPC) \\ - || defined(_M_MPPC) || defined(_M_PPC) - #if defined(__ppc64__) || defined(__powerpc64__) || defined(__64BIT__) - #error cmake_ARCH ppc64 - #else - #error cmake_ARCH ppc - #endif -#endif - -#error cmake_ARCH unknown -") - -# Set ppc_support to TRUE before including this file or ppc and ppc64 -# will be treated as invalid architectures since they are no longer supported by Apple - -function(target_architecture output_var) - if(APPLE AND CMAKE_OSX_ARCHITECTURES) - # On OS X we use CMAKE_OSX_ARCHITECTURES *if* it was set - # First let's normalize the order of the values - - # Note that it's not possible to compile PowerPC applications if you are using - # the OS X SDK version 10.6 or later - you'll need 10.4/10.5 for that, so we - # disable it by default - # See this page for more information: - # http://stackoverflow.com/questions/5333490/how-can-we-restore-ppc-ppc64-as-well-as-full-10-4-10-5-sdk-support-to-xcode-4 - - # Architecture defaults to i386 or ppc on OS X 10.5 and earlier, depending on the CPU type detected at runtime. - # On OS X 10.6+ the default is x86_64 if the CPU supports it, i386 otherwise. - - foreach(osx_arch ${CMAKE_OSX_ARCHITECTURES}) - if("${osx_arch}" STREQUAL "ppc" AND ppc_support) - set(osx_arch_ppc TRUE) - elseif("${osx_arch}" STREQUAL "i386") - set(osx_arch_i386 TRUE) - elseif("${osx_arch}" STREQUAL "x86_64") - set(osx_arch_x86_64 TRUE) - elseif("${osx_arch}" STREQUAL "ppc64" AND ppc_support) - set(osx_arch_ppc64 TRUE) - else() - message(FATAL_ERROR "Invalid OS X arch name: ${osx_arch}") - endif() - endforeach() - - # Now add all the architectures in our normalized order - if(osx_arch_ppc) - list(APPEND ARCH ppc) - endif() - - if(osx_arch_i386) - list(APPEND ARCH i386) - endif() - - if(osx_arch_x86_64) - list(APPEND ARCH x86_64) - endif() - - if(osx_arch_ppc64) - list(APPEND ARCH ppc64) - endif() - else() - file(WRITE "${CMAKE_BINARY_DIR}/arch.c" "${archdetect_c_code}") - - enable_language(C) - - # Detect the architecture in a rather creative way... - # This compiles a small C program which is a series of ifdefs that selects a - # particular #error preprocessor directive whose message string contains the - # target architecture. The program will always fail to compile (both because - # file is not a valid C program, and obviously because of the presence of the - # #error preprocessor directives... but by exploiting the preprocessor in this - # way, we can detect the correct target architecture even when cross-compiling, - # since the program itself never needs to be run (only the compiler/preprocessor) - try_run( - run_result_unused - compile_result_unused - "${CMAKE_BINARY_DIR}" - "${CMAKE_BINARY_DIR}/arch.c" - COMPILE_OUTPUT_VARIABLE ARCH - CMAKE_FLAGS CMAKE_OSX_ARCHITECTURES=${CMAKE_OSX_ARCHITECTURES} - ) - - # Parse the architecture name from the compiler output - string(REGEX MATCH "cmake_ARCH ([a-zA-Z0-9_]+)" ARCH "${ARCH}") - - # Get rid of the value marker leaving just the architecture name - string(REPLACE "cmake_ARCH " "" ARCH "${ARCH}") - - # If we are compiling with an unknown architecture this variable should - # already be set to "unknown" but in the case that it's empty (i.e. due - # to a typo in the code), then set it to unknown - if (NOT ARCH) - set(ARCH unknown) - endif() - endif() - - set(${output_var} "${ARCH}" PARENT_SCOPE) -endfunction() diff --git a/cmake/cmake_uninstall.cmake.in b/cmake/cmake_uninstall.cmake.in deleted file mode 100644 index 2037e3653..000000000 --- a/cmake/cmake_uninstall.cmake.in +++ /dev/null @@ -1,21 +0,0 @@ -if(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") - message(FATAL_ERROR "Cannot find install manifest: @CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") -endif(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") - -file(READ "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt" files) -string(REGEX REPLACE "\n" ";" files "${files}") -foreach(file ${files}) - message(STATUS "Uninstalling $ENV{DESTDIR}${file}") - if(IS_SYMLINK "$ENV{DESTDIR}${file}" OR EXISTS "$ENV{DESTDIR}${file}") - exec_program( - "@CMAKE_COMMAND@" ARGS "-E remove \"$ENV{DESTDIR}${file}\"" - OUTPUT_VARIABLE rm_out - RETURN_VALUE rm_retval - ) - if(NOT "${rm_retval}" STREQUAL 0) - message(FATAL_ERROR "Problem when removing $ENV{DESTDIR}${file}") - endif(NOT "${rm_retval}" STREQUAL 0) - else(IS_SYMLINK "$ENV{DESTDIR}${file}" OR EXISTS "$ENV{DESTDIR}${file}") - message(STATUS "File $ENV{DESTDIR}${file} does not exist.") - endif(IS_SYMLINK "$ENV{DESTDIR}${file}" OR EXISTS "$ENV{DESTDIR}${file}") -endforeach(file) diff --git a/cmake/cpack_options.cmake.in b/cmake/cpack_options.cmake.in deleted file mode 100644 index b5cb6d5c1..000000000 --- a/cmake/cpack_options.cmake.in +++ /dev/null @@ -1,23 +0,0 @@ -set(CPACK_PACKAGE_NAME "@PROJECT_NAME_NO_VERSION@") -set(CPACK_PACKAGE_VENDOR "sdformat.org") -set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "Scene Description Format (SDF)") -set(CPACK_PACKAGE_INSTALL_DIRECTORY "@PROJECT_NAME_NO_VERSION_LOWER@") -set(CPACK_RESOURCE_FILE_LICENSE "@CMAKE_CURRENT_SOURCE_DIR@/LICENSE") -set(CPACK_RESOURCE_FILE_README "@CMAKE_CURRENT_SOURCE_DIR@/README.md") -set(CPACK_PACKAGE_DESCRIPTION_FILE "@CMAKE_CURRENT_SOURCE_DIR@/README.md") -set(CPACK_PACKAGE_MAINTAINER "Nate Koenig ") -set(CPACK_PACKAGE_CONTACT "Nate Koenig ") - -set(CPACK_DEBIAN_PACKAGE_ARCHITECTURE "@DPKG_ARCH@") -set(CPACK_DEBIAN_PACKAGE_DEPENDS "@DEBIAN_PACKAGE_DEPENDS@") -set(CPACK_DEBIAN_PACKAGE_SECTION "devel") -set(CPACK_DEBIAN_PACKAGE_PRIORITY "optional") -set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) -set(CPACK_DEBIAN_PACKAGE_DESCRIPTION "Format and parser for scene description files.") - -set(CPACK_RPM_PACKAGE_ARCHITECTURE "@DPKG_ARCH@") -set(CPACK_RPM_PACKAGE_REQUIRES "@DEBIAN_PACKAGE_DEPENDS@") -set(CPACK_RPM_PACKAGE_DESCRIPTION "Format and parser for scene description files.") - -set (CPACK_PACKAGE_FILE_NAME "@PROJECT_NAME_NO_VERSION_LOWER@-@SDF_VERSION_FULL@") -set (CPACK_SOURCE_PACKAGE_FILE_NAME "@PROJECT_NAME_NO_VERSION_LOWER@-@SDF_VERSION_FULL@") diff --git a/cmake/sdf_config.cmake.in b/cmake/sdf_config.cmake.in deleted file mode 100644 index f4c511fa9..000000000 --- a/cmake/sdf_config.cmake.in +++ /dev/null @@ -1,40 +0,0 @@ -# We explicitly set the desired cmake version to ensure that the policy settings -# of users or of toolchains do not result in the wrong behavior for our modules. -# Note that the call to find_package(~) will PUSH a new policy stack before -# taking on these version settings, and then that stack will POP after the -# find_package(~) has exited, so this will not affect the cmake policy settings -# of a caller. -cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) - -if(@PKG_NAME@_CONFIG_INCLUDED) - return() -endif() -set(@PKG_NAME@_CONFIG_INCLUDED TRUE) - -@PACKAGE_INIT@ - -if(NOT TARGET @sdf_import_target_name@) - include("${CMAKE_CURRENT_LIST_DIR}/@sdf_target_output_filename@") -endif() - -list(APPEND @PKG_NAME@_INCLUDE_DIRS "@CMAKE_INSTALL_PREFIX@/include/sdformat-@SDF_VERSION@") - -list(APPEND @PKG_NAME@_CFLAGS "-I@CMAKE_INSTALL_PREFIX@/include/sdformat-@SDF_VERSION@") -if (NOT WIN32) - list(APPEND @PKG_NAME@_CXX_FLAGS "${@PKG_NAME@_CFLAGS} -std=c++17") -endif() - -list(APPEND @PKG_NAME@_LIBRARY_DIRS "@CMAKE_INSTALL_PREFIX@/@CMAKE_INSTALL_LIBDIR@") - -set(@PKG_NAME@_LIBRARIES @sdf_import_target_name@) - -# These variables are used by ignition-cmake to automatically configure the -# pkgconfig files for ignition projects. -set(@PROJECT_NAME_LOWER@_PKGCONFIG_ENTRY "@PROJECT_NAME_LOWER@") -set(@PROJECT_NAME_LOWER@_PKGCONFIG_TYPE PKGCONFIG_REQUIRES) - -find_package(ignition-math@IGN_MATH_VER@) -list(APPEND @PKG_NAME@_INCLUDE_DIRS ${IGNITION-MATH_INCLUDE_DIRS}) -list(APPEND @PKG_NAME@_LIBRARY_DIRS ${IGNITION-MATH_LIBRARY_DIRS}) - -list(APPEND @PKG_NAME@_LDFLAGS "-L@CMAKE_INSTALL_PREFIX@/@LIB_INSTALL_DIR@") diff --git a/cmake/sdf_cpack.cmake b/cmake/sdf_cpack.cmake deleted file mode 100644 index 6267aae34..000000000 --- a/cmake/sdf_cpack.cmake +++ /dev/null @@ -1,25 +0,0 @@ -################################################################################ -#Find available package generators - -# DEB -if ("${CMAKE_SYSTEM}" MATCHES "Linux") - find_program(DPKG_PROGRAM dpkg) - if (EXISTS ${DPKG_PROGRAM}) - list (APPEND CPACK_GENERATOR "DEB") - endif(EXISTS ${DPKG_PROGRAM}) - - find_program(RPMBUILD_PROGRAM rpmbuild) -endif() - -list (APPEND CPACK_SOURCE_GENERATOR "TBZ2") -list (APPEND CPACK_SOURCE_GENERATOR "ZIP") -list (APPEND CPACK_SOURCE_IGNORE_FILES ";TODO;/.hg/;.swp$;/build/") - -include (InstallRequiredSystemLibraries) - -#execute_process(COMMAND dpkg --print-architecture _NPROCE) -set (DEBIAN_PACKAGE_DEPENDS "libtinyxml-dev") - -set (RPM_PACKAGE_DEPENDS "libtinyxml-dev") - -set (SDF_CPACK_CFG_FILE "${PROJECT_BINARY_DIR}/cpack_options.cmake") diff --git a/cmake/sdformat_pc.in b/cmake/sdformat_pc.in deleted file mode 100644 index c95a781e2..000000000 --- a/cmake/sdformat_pc.in +++ /dev/null @@ -1,10 +0,0 @@ -prefix="@CMAKE_INSTALL_PREFIX@" -libdir=${prefix}/@LIB_INSTALL_DIR@ -includedir=${prefix}/@CMAKE_INSTALL_INCLUDEDIR@ - -Name: SDF -Description: Robot Modeling Language (SDF) -Version: @SDF_VERSION_FULL@ -Requires: ignition-math@IGN_MATH_VER@ -Libs: -L${libdir} -lsdformat@SDF_MAJOR_VERSION@ -CFlags: -I${includedir}/sdformat-@SDF_VERSION@ -std=c++17 diff --git a/cmake/upload_doc.sh.in b/cmake/upload_doc.sh.in index 41a088b9a..04a58ddc0 100644 --- a/cmake/upload_doc.sh.in +++ b/cmake/upload_doc.sh.in @@ -18,7 +18,7 @@ make sdf_descriptions # Date/time stamp sdf descriptions for f in @CMAKE_BINARY_DIR@/sdf/full_*.sdf; do - cp ${f} ${f%.sdf}_@SDF_VERSION_FULL@_$(date +%Y%m%d_%H%M%S).sdf + cp ${f} ${f%.sdf}_@PROJECT_VERSION_FULL@_$(date +%Y%m%d_%H%M%S).sdf done # Upload sdf descriptions @@ -39,11 +39,11 @@ if [ ! -f "@CMAKE_BINARY_DIR@/doxygen/html/index.html" ]; then fi # The code API -s3cmd sync @CMAKE_BINARY_DIR@/doxygen/html/* s3://osrf-distributions/sdformat/api/@SDF_VERSION_FULL@/ --dry-run -v +s3cmd sync @CMAKE_BINARY_DIR@/doxygen/html/* s3://osrf-distributions/sdformat/api/@PROJECT_VERSION_FULL@/ --dry-run -v echo -n "Upload code API(Y/n)? " read ans if [ "$ans" = "y" ] || [ "$ans" = "Y" ]; then - s3cmd sync @CMAKE_BINARY_DIR@/doxygen/html/* s3://osrf-distributions/sdformat/api/@SDF_VERSION_FULL@/ -v + s3cmd sync @CMAKE_BINARY_DIR@/doxygen/html/* s3://osrf-distributions/sdformat/api/@PROJECT_VERSION_FULL@/ -v fi diff --git a/conf/CMakeLists.txt b/conf/CMakeLists.txt index 001e28ee5..fd3b6d278 100644 --- a/conf/CMakeLists.txt +++ b/conf/CMakeLists.txt @@ -1,23 +1,23 @@ # Used only for internal testing. -set(ign_library_path "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmd${sdf_target}") +set(ign_library_path "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmd${PROJECT_NAME}") # Generate a configuration file for internal testing. # Note that the major version of the library is included in the name. # Ex: sdformat0.yaml configure_file( "${PROJECT_NAME_NO_VERSION_LOWER}.yaml.in" - "${CMAKE_BINARY_DIR}/test/conf/${sdf_target}.yaml" @ONLY) + "${CMAKE_BINARY_DIR}/test/conf/${PROJECT_NAME}.yaml" @ONLY) # Used for the installed version. -set(ign_library_path "${CMAKE_INSTALL_PREFIX}/lib/ruby/ignition/cmd${sdf_target}") +set(ign_library_path "${CMAKE_INSTALL_PREFIX}/lib/ruby/ignition/cmd${PROJECT_NAME}") # Generate the configuration file that is installed. # Note that the major version of the library is included in the name. # Ex: sdformat0.yaml configure_file( "${PROJECT_NAME_NO_VERSION_LOWER}.yaml.in" - "${CMAKE_CURRENT_BINARY_DIR}/${sdf_target}.yaml" @ONLY) + "${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.yaml" @ONLY) # Install the yaml configuration files in an unversioned location. -install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${sdf_target}.yaml +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.yaml DESTINATION ${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_DATAROOTDIR}/ignition/) diff --git a/conf/sdformat.yaml.in b/conf/sdformat.yaml.in index e570ac97e..579e91bab 100644 --- a/conf/sdformat.yaml.in +++ b/conf/sdformat.yaml.in @@ -1,7 +1,7 @@ --- # Subcommands available inside sdformat. format: 1.0.0 library_name: @PROJECT_NAME_NO_VERSION@ -library_version: @SDF_VERSION_FULL@ +library_version: @PROJECT_VERSION_FULL@ library_path: @ign_library_path@ commands: - sdf : Utilities for SDF files. diff --git a/doc/sdf.in b/doc/sdf.in index 39b19d004..5361dfc95 100644 --- a/doc/sdf.in +++ b/doc/sdf.in @@ -32,7 +32,7 @@ PROJECT_NAME = SDF # This could be handy for archiving the generated documentation or # if some version control system is used. -PROJECT_NUMBER = @SDF_VERSION_FULL@ +PROJECT_NUMBER = @PROJECT_VERSION_FULL@ # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt new file mode 100644 index 000000000..722dbe56c --- /dev/null +++ b/include/CMakeLists.txt @@ -0,0 +1 @@ +add_subdirectory(sdf) diff --git a/include/sdf/CMakeLists.txt b/include/sdf/CMakeLists.txt index 0a62d171d..94f57dcfe 100644 --- a/include/sdf/CMakeLists.txt +++ b/include/sdf/CMakeLists.txt @@ -1,63 +1,8 @@ -include (${sdf_cmake_dir}/SDFUtils.cmake) - -set (headers - Actor.hh - AirPressure.hh - Altimeter.hh - Assert.hh - Atmosphere.hh - Box.hh - Camera.hh - Collision.hh - Console.hh - Cylinder.hh - Element.hh - Error.hh - Exception.hh - Filesystem.hh - ForceTorque.hh - Frame.hh - Geometry.hh - Gui.hh - Heightmap.hh - Imu.hh - Joint.hh - JointAxis.hh - Lidar.hh - Light.hh - Link.hh - Magnetometer.hh - Material.hh - Mesh.hh - Model.hh - NavSat.hh - Noise.hh - Param.hh - parser.hh - ParticleEmitter.hh - Pbr.hh - Physics.hh - Plane.hh - Root.hh - Scene.hh - SDFImpl.hh - SemanticPose.hh - Sensor.hh - Sky.hh - Sphere.hh - Surface.hh - Types.hh - system_util.hh - Visual.hh - World.hh +# Exlcude some files so that they are not added to the master header. +ign_install_all_headers(EXCLUDE_FILES sdf.hh sdf_config.h) +install( + FILES + sdf.hh + sdf_config.h + DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL}/${PROJECT_INCLUDE_DIR} ) - -set (sdf_headers "" CACHE INTERNAL "SDF headers" FORCE) -foreach (hdr ${headers}) - set(sdf_headers "${sdf_headers}#include \n") -endforeach() -configure_file (${CMAKE_CURRENT_SOURCE_DIR}/sdf.hh.in - ${CMAKE_CURRENT_BINARY_DIR}/sdf.hh) - -sdf_install_includes("" ${headers} - ${CMAKE_CURRENT_BINARY_DIR}/sdf.hh) diff --git a/cmake/sdf_config.h.in b/include/sdf/config.hh.in similarity index 59% rename from cmake/sdf_config.h.in rename to include/sdf/config.hh.in index 524088664..cf9482c43 100644 --- a/cmake/sdf_config.h.in +++ b/include/sdf/config.hh.in @@ -1,4 +1,7 @@ -/* config.h. Generated by CMake for @PROJECT_NAME@. */ +/* config.hh. Generated by CMake for @PROJECT_NAME@. */ + +#ifndef SDF_CONFIG_HH_ +#define SDF_CONFIG_HH_ /* Protocol version */ #define SDF_PROTOCOL_VERSION "${SDF_PROTOCOL_VERSION}" @@ -11,18 +14,18 @@ #define SDF_VERSION "${SDF_PROTOCOL_VERSION}" /* Package version number */ -#define SDF_MAJOR_VERSION ${SDF_MAJOR_VERSION} -#define SDF_MINOR_VERSION ${SDF_MINOR_VERSION} -#define SDF_PATCH_VERSION ${SDF_PATCH_VERSION} +#define SDF_MAJOR_VERSION ${PROJECT_VERSION_MAJOR} +#define SDF_MINOR_VERSION ${PROJECT_VERSION_MINOR} +#define SDF_PATCH_VERSION ${PROJECT_VERSION_PATCH} -#define SDF_MAJOR_VERSION_STR "${SDF_MAJOR_VERSION}" -#define SDF_MINOR_VERSION_STR "${SDF_MINOR_VERSION}" -#define SDF_PATCH_VERSION_STR "${SDF_PATCH_VERSION}" +#define SDF_MAJOR_VERSION_STR "${PROJECT_VERSION_MAJOR}" +#define SDF_MINOR_VERSION_STR "${PROJECT_VERSION_MINOR}" +#define SDF_PATCH_VERSION_STR "${PROJECT_VERSION_PATCH}" -#define SDF_PKG_VERSION "${SDF_VERSION}" -#define SDF_VERSION_FULL "${SDF_VERSION_FULL}" -#define SDF_VERSION_NAME ${SDF_VERSION_NAME} -#define SDF_VERSION_NAMESPACE v${SDF_MAJOR_VERSION} +#define SDF_PKG_VERSION "${PROJECT_VERSION}" +#define SDF_VERSION_FULL "${PROJECT_VERSION_FULL}" +#define SDF_VERSION_NAME ${PROJECT_VERSION_NAME} +#define SDF_VERSION_NAMESPACE v${PROJECT_VERSION_MAJOR} #define SDF_VERSION_HEADER "Simulation Description Format (SDF), version ${SDF_PROTOCOL_VERSION}\nCopyright (C) 2014 Open Source Robotics Foundation.\nReleased under the Apache 2 License.\nhttp://gazebosim.org/sdf\n\n" @@ -35,3 +38,5 @@ #define SDF_SHARE_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/" #define SDF_VERSION_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/${SDF_PKG_VERSION}" + +#endif // #ifndef SDF_CONFIG_HH_ diff --git a/include/sdf/sdf.hh b/include/sdf/sdf.hh new file mode 100644 index 000000000..900a12a04 --- /dev/null +++ b/include/sdf/sdf.hh @@ -0,0 +1,25 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef SDF_SDF_HH_ +#define SDF_SDF_HH_ + +// This file is kept for backwards compatibility. +// Use sdformat.hh directly instead. +#include + +#endif diff --git a/include/sdf/sdf_config.h b/include/sdf/sdf_config.h new file mode 100644 index 000000000..656f17b85 --- /dev/null +++ b/include/sdf/sdf_config.h @@ -0,0 +1,25 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef SDF_SDF_CONFIG_H_ +#define SDF_SDF_CONFIG_H_ + +// This file is kept for backwards compatibility. +// Use sdf/config.hh directly instead. +#include + +#endif diff --git a/include/sdf/system_util.hh b/include/sdf/system_util.hh index a94b9f46e..8d244f38c 100644 --- a/include/sdf/system_util.hh +++ b/include/sdf/system_util.hh @@ -17,38 +17,17 @@ #ifndef SDF_VISIBLE_HH_ #define SDF_VISIBLE_HH_ +#include + /** \def SDFORMAT_VISIBLE * Use to represent "symbol visible" if supported */ +#define SDFORMAT_VISIBLE IGNITION_SDFORMAT_VISIBLE /** \def SDFORMAT_HIDDEN * Use to represent "symbol hidden" if supported */ - -#if defined _WIN32 || defined __CYGWIN__ - #ifdef BUILDING_DLL - #ifdef __GNUC__ - #define SDFORMAT_VISIBLE __attribute__ ((dllexport)) - #else - #define SDFORMAT_VISIBLE __declspec(dllexport) - #endif - #else - #ifdef __GNUC__ - #define SDFORMAT_VISIBLE __attribute__ ((dllimport)) - #else - #define SDFORMAT_VISIBLE __declspec(dllimport) - #endif - #endif - #define SDFORMAT_HIDDEN -#else - #if __GNUC__ >= 4 && !defined SDFORMAT_STATIC_DEFINE - #define SDFORMAT_VISIBLE __attribute__ ((visibility ("default"))) - #define SDFORMAT_HIDDEN __attribute__ ((visibility ("hidden"))) - #else - #define SDFORMAT_VISIBLE - #define SDFORMAT_HIDDEN - #endif -#endif +#define SDFORMAT_HIDDEN IGNITION_SDFORMAT_HIDDEN // SDF_VISIBLE_HH_ #endif diff --git a/sdf/1.0/CMakeLists.txt b/sdf/1.0/CMakeLists.txt index 1695588b1..dd62ae21c 100644 --- a/sdf/1.0/CMakeLists.txt +++ b/sdf/1.0/CMakeLists.txt @@ -27,4 +27,4 @@ set (sdfs world.sdf ) -install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.0/) +install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.0/) diff --git a/sdf/1.2/CMakeLists.txt b/sdf/1.2/CMakeLists.txt index a37e84191..051e49e55 100644 --- a/sdf/1.2/CMakeLists.txt +++ b/sdf/1.2/CMakeLists.txt @@ -28,4 +28,4 @@ set (sdfs world.sdf ) -install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.2) +install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.2) diff --git a/sdf/1.3/CMakeLists.txt b/sdf/1.3/CMakeLists.txt index b737f0e50..9325a7e19 100644 --- a/sdf/1.3/CMakeLists.txt +++ b/sdf/1.3/CMakeLists.txt @@ -29,4 +29,4 @@ set (sdfs world.sdf ) -install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.3) +install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.3) diff --git a/sdf/1.4/CMakeLists.txt b/sdf/1.4/CMakeLists.txt index a59f4ea68..657bd085e 100644 --- a/sdf/1.4/CMakeLists.txt +++ b/sdf/1.4/CMakeLists.txt @@ -44,4 +44,4 @@ set (sdfs world.sdf ) -install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.4) +install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.4) diff --git a/sdf/1.5/CMakeLists.txt b/sdf/1.5/CMakeLists.txt index 60fd6a15a..89e721573 100644 --- a/sdf/1.5/CMakeLists.txt +++ b/sdf/1.5/CMakeLists.txt @@ -76,5 +76,5 @@ add_custom_target(schema1_5 ALL DEPENDS ${SDF_SCHEMA}) set_source_files_properties(${SDF_SCHEMA} PROPERTIES GENERATED TRUE) -install(FILES 1_4.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.5) -install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.5) +install(FILES 1_4.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.5) +install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.5) diff --git a/sdf/1.6/CMakeLists.txt b/sdf/1.6/CMakeLists.txt index c77c738ec..efedf3c3d 100644 --- a/sdf/1.6/CMakeLists.txt +++ b/sdf/1.6/CMakeLists.txt @@ -77,5 +77,5 @@ add_custom_target(schema1_6 ALL DEPENDS ${SDF_SCHEMA}) set_source_files_properties(${SDF_SCHEMA} PROPERTIES GENERATED TRUE) -install(FILES 1_5.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.6) -install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.6) +install(FILES 1_5.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.6) +install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.6) diff --git a/sdf/1.7/CMakeLists.txt b/sdf/1.7/CMakeLists.txt index c170977c9..b59e58f0f 100644 --- a/sdf/1.7/CMakeLists.txt +++ b/sdf/1.7/CMakeLists.txt @@ -77,5 +77,5 @@ add_custom_target(schema1_7 ALL DEPENDS ${SDF_SCHEMA}) set_source_files_properties(${SDF_SCHEMA} PROPERTIES GENERATED TRUE) -install(FILES 1_6.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.7) -install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${SDF_MAJOR_VERSION}/1.7) +install(FILES 1_6.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.7) +install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat${PROJECT_VERSION_MAJOR}/1.7) diff --git a/sdf/CMakeLists.txt b/sdf/CMakeLists.txt index 6de59a3a4..728d66aed 100644 --- a/sdf/CMakeLists.txt +++ b/sdf/CMakeLists.txt @@ -20,7 +20,7 @@ execute_process( # Generate aggregated SDF description files for use by the sdformat.org # website. If the description files change, the generated full*.sdf files need # to be removed before running this target. -if (IGNITION-TOOLS_BINARY_DIRS) +if (IGN_PROGRAM) # Update this list as new sdformat spec versions are added. set(sdf_desc_versions 1.4 1.5 1.6 1.7) @@ -33,10 +33,10 @@ if (IGNITION-TOOLS_BINARY_DIRS) OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/full_${desc_ver_dash}.sdf COMMAND ${CMAKE_COMMAND} -E env IGN_CONFIG_PATH=${CMAKE_BINARY_DIR}/test/conf - ${IGNITION-TOOLS_BINARY_DIRS}/ign + ${IGN_PROGRAM} ARGS sdf -d ${desc_ver} > ${CMAKE_CURRENT_BINARY_DIR}/full_${desc_ver_dash}.sdf COMMENT "Generating full description for spec ${desc_ver}" VERBATIM) endforeach() - add_custom_target(sdf_descriptions DEPENDS ${description_targets} ${sdf_target}) + add_custom_target(sdf_descriptions DEPENDS ${description_targets} ${PROJECT_LIBRARY_TARGET_NAME}) endif() diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 75ae5c054..e2e02bbdf 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -1,75 +1,11 @@ -include (${sdf_cmake_dir}/SDFUtils.cmake) +# Collect source files into the "sources" variable and unit test files into the +# "gtest_sources" variable +ign_get_libsources_and_unittests(sources gtest_sources) -link_directories( - ${PROJECT_BINARY_DIR}/test -) - -if (NOT USE_INTERNAL_URDF) - link_directories(${URDF_LIBRARY_DIRS}) -endif() - -set (sources - Actor.cc - AirPressure.cc - Altimeter.cc - Atmosphere.cc - Box.cc - Camera.cc - Collision.cc - Console.cc - Converter.cc - Cylinder.cc - Element.cc - EmbeddedSdf.cc - Error.cc - Exception.cc - Frame.cc - FrameSemantics.cc - Filesystem.cc - ForceTorque.cc - Geometry.cc - Gui.cc - Heightmap.cc - ign.cc - Imu.cc - Joint.cc - JointAxis.cc - Lidar.cc - Light.cc - Link.cc - Magnetometer.cc - Material.cc - Mesh.cc - Model.cc - NavSat.cc - Noise.cc - parser.cc - parser_urdf.cc - Param.cc - ParamPassing.cc - ParticleEmitter.cc - Pbr.cc - Physics.cc - Plane.cc - Root.cc - Scene.cc - SDF.cc - SDFExtension.cc - SemanticPose.cc - Sensor.cc - Sky.cc - Sphere.cc - Surface.cc - Types.cc - Utils.cc - Visual.cc - World.cc - XmlUtils.cc -) -include_directories(${CMAKE_CURRENT_SOURCE_DIR}) +# Add the source file auto-generated into the build folder from sdf/CMakeLists.txt +list(APPEND sources EmbeddedSdf.cc) if (USE_INTERNAL_URDF) - include_directories(${CMAKE_CURRENT_SOURCE_DIR}/urdf) set(sources ${sources} urdf/urdf_parser/model.cpp urdf/urdf_parser/link.cpp @@ -79,164 +15,129 @@ if (USE_INTERNAL_URDF) urdf/urdf_parser/urdf_model_state.cpp urdf/urdf_parser/urdf_sensor.cpp urdf/urdf_parser/world.cpp) -else() - include_directories(${URDF_INCLUDE_DIRS}) endif() -if (BUILD_SDF_TEST) - set (gtest_sources - Actor_TEST.cc - AirPressure_TEST.cc - Altimeter_TEST.cc - Atmosphere_TEST.cc - Box_TEST.cc - Camera_TEST.cc - Collision_TEST.cc - Console_TEST.cc - Cylinder_TEST.cc - Element_TEST.cc - Error_TEST.cc - Exception_TEST.cc - Frame_TEST.cc - Filesystem_TEST.cc - ForceTorque_TEST.cc - Geometry_TEST.cc - Gui_TEST.cc - Heightmap_TEST.cc - Imu_TEST.cc - Joint_TEST.cc - JointAxis_TEST.cc - Lidar_TEST.cc - Light_TEST.cc - Link_TEST.cc - Magnetometer_TEST.cc - Material_TEST.cc - Mesh_TEST.cc - Model_TEST.cc - NavSat_TEST.cc - Noise_TEST.cc - Param_TEST.cc - parser_TEST.cc - ParticleEmitter_TEST.cc - Pbr_TEST.cc - Physics_TEST.cc - Plane_TEST.cc - Root_TEST.cc - Scene_TEST.cc - SemanticPose_TEST.cc - SDF_TEST.cc - Sensor_TEST.cc - Sky_TEST.cc - Sphere_TEST.cc - Surface_TEST.cc - Types_TEST.cc - Visual_TEST.cc - World_TEST.cc - ) - +if (BUILD_TESTING) # Build this test file only if Ignition Tools is installed. - if (IGNITION-TOOLS_BINARY_DIRS) - set (gtest_sources ${gtest_sources} - ign_TEST.cc - ) + if (NOT IGN_PROGRAM) + list(REMOVE_ITEM gtest_sources ign_TEST.cc) endif() - include_directories(${PROJECT_SOURCE_DIR}/test) - sdf_build_tests(${gtest_sources}) + # Skip tests that don't work on Windows + if (WIN32) + list(REMOVE_ITEM gtest_sources Converter_TEST.cc) + list(REMOVE_ITEM gtest_sources FrameSemantics_TEST.cc) + list(REMOVE_ITEM gtest_sources ParamPassing_TEST.cc) + list(REMOVE_ITEM gtest_sources Utils_TEST.cc) + list(REMOVE_ITEM gtest_sources XmlUtils_TEST.cc) + list(REMOVE_ITEM gtest_sources parser_urdf_TEST.cc) + endif() + + ign_build_tests( + TYPE UNIT + SOURCES ${gtest_sources} + INCLUDE_DIRS + ${CMAKE_CURRENT_SOURCE_DIR} + ${PROJECT_SOURCE_DIR}/test + ) if (TARGET UNIT_ign_TEST) # Link the libraries that we always need. target_link_libraries("UNIT_ign_TEST" - PUBLIC - ignition-cmake${IGN_CMAKE_VER}::utilities + ignition-cmake${IGN_CMAKE_VER}::utilities ) endif() - if (NOT WIN32) - set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS Utils.cc) - sdf_build_tests(Utils_TEST.cc) + if (TARGET UNIT_Converter_TEST) + target_link_libraries(UNIT_Converter_TEST + TINYXML2::TINYXML2) + target_sources(UNIT_Converter_TEST PRIVATE + Converter.cc + EmbeddedSdf.cc + XmlUtils.cc) endif() - if (NOT WIN32) - set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS XmlUtils.cc) - sdf_build_tests(XmlUtils_TEST.cc) - target_link_libraries(UNIT_XmlUtils_TEST PRIVATE - ${TinyXML2_LIBRARIES}) + if (TARGET UNIT_FrameSemantics_TEST) + target_sources(UNIT_FrameSemantics_TEST PRIVATE FrameSemantics.cc) endif() - if (NOT WIN32) - set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS FrameSemantics.cc) - sdf_build_tests(FrameSemantics_TEST.cc) + if (TARGET UNIT_ParamPassing_TEST) + if (NOT USE_INTERNAL_URDF) + target_link_libraries(UNIT_ParamPassing_TEST + IgnURDFDOM::IgnURDFDOM) + endif() + target_link_libraries(UNIT_ParamPassing_TEST + TINYXML2::TINYXML2) + target_sources(UNIT_ParamPassing_TEST PRIVATE + Converter.cc + EmbeddedSdf.cc + FrameSemantics.cc + ParamPassing.cc + SDFExtension.cc + XmlUtils.cc + parser.cc + parser_urdf.cc) endif() - if (NOT WIN32) - set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS Converter.cc EmbeddedSdf.cc XmlUtils.cc) - sdf_build_tests(Converter_TEST.cc) - target_link_libraries(UNIT_Converter_TEST PRIVATE - ${TinyXML2_LIBRARIES}) + if (TARGET UNIT_Utils_TEST) + target_sources(UNIT_Utils_TEST PRIVATE Utils.cc) endif() - if (NOT WIN32) - set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS SDFExtension.cc parser_urdf.cc XmlUtils.cc) - sdf_build_tests(parser_urdf_TEST.cc) - if (NOT USE_INTERNAL_URDF) - target_compile_options(UNIT_parser_urdf_TEST PRIVATE ${URDF_CFLAGS}) - if (${CMAKE_VERSION} VERSION_GREATER 3.13) - target_link_options(UNIT_parser_urdf_TEST PRIVATE ${URDF_LDFLAGS}) - endif() - target_link_libraries(UNIT_parser_urdf_TEST PRIVATE ${URDF_LIBRARIES}) - endif() - target_link_libraries(UNIT_parser_urdf_TEST PRIVATE - ${TinyXML2_LIBRARIES}) + if (TARGET UNIT_XmlUtils_TEST) + target_link_libraries(UNIT_XmlUtils_TEST + TINYXML2::TINYXML2) + target_sources(UNIT_XmlUtils_TEST PRIVATE XmlUtils.cc) endif() - if (NOT WIN32) - set(SDF_BUILD_TESTS_EXTRA_EXE_SRCS ParamPassing.cc XmlUtils.cc parser.cc - parser_urdf.cc FrameSemantics.cc Converter.cc EmbeddedSdf.cc SDFExtension.cc) - sdf_build_tests(ParamPassing_TEST.cc) + if (TARGET UNIT_parser_urdf_TEST) if (NOT USE_INTERNAL_URDF) - target_compile_options(UNIT_ParamPassing_TEST PRIVATE ${URDF_CFLAGS}) - if (${CMAKE_VERSION} VERSION_GREATER 3.13) - target_link_options(UNIT_ParamPassing_TEST PRIVATE ${URDF_LDFLAGS}) - endif() - target_link_libraries(UNIT_ParamPassing_TEST PRIVATE ${URDF_LIBRARIES}) + target_link_libraries(UNIT_parser_urdf_TEST + IgnURDFDOM::IgnURDFDOM) endif() - target_link_libraries(UNIT_ParamPassing_TEST PRIVATE - ${TinyXML2_LIBRARIES}) + target_link_libraries(UNIT_parser_urdf_TEST + TINYXML2::TINYXML2) + target_sources(UNIT_parser_urdf_TEST PRIVATE + SDFExtension.cc + XmlUtils.cc + parser_urdf.cc) endif() endif() -sdf_add_library(${sdf_target} ${sources}) -target_compile_features(${sdf_target} PUBLIC cxx_std_17) -target_link_libraries(${sdf_target} +ign_create_core_library(SOURCES ${sources} + CXX_STANDARD 17 + LEGACY_PROJECT_PREFIX SDFormat + ) + +target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} PUBLIC ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER} PRIVATE - ${TinyXML2_LIBRARIES}) + TINYXML2::TINYXML2) if (WIN32) - target_compile_definitions(${sdf_target} PRIVATE URDFDOM_STATIC) + target_compile_definitions(${PROJECT_LIBRARY_TARGET_NAME} PRIVATE URDFDOM_STATIC) endif() -target_include_directories(${sdf_target} +target_include_directories(${PROJECT_LIBRARY_TARGET_NAME} PUBLIC $ $ + PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR} ) -message (STATUS "URDF_LIBRARY_DIRS=${URDF_LIBRARY_DIRS}") -message (STATUS "URDF_LIBRARIES=${URDF_LIBRARIES}") - -if (NOT USE_INTERNAL_URDF) - target_compile_options(${sdf_target} PRIVATE ${URDF_CFLAGS}) - if (${CMAKE_VERSION} VERSION_GREATER 3.13) - target_link_options(${sdf_target} PRIVATE ${URDF_LDFLAGS}) +if (USE_INTERNAL_URDF) + target_include_directories(${PROJECT_LIBRARY_TARGET_NAME} + PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/urdf + ) + if (WIN32) + target_compile_definitions(${PROJECT_LIBRARY_TARGET_NAME} PRIVATE -D_USE_MATH_DEFINES) endif() - target_link_libraries(${sdf_target} PRIVATE ${URDF_LIBRARIES}) +else() + target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} PRIVATE IgnURDFDOM::IgnURDFDOM) endif() -sdf_install_library(${sdf_target}) - if(NOT WIN32) add_subdirectory(cmd) endif() diff --git a/src/Filesystem.cc b/src/Filesystem.cc index 5096a6427..287f818fe 100644 --- a/src/Filesystem.cc +++ b/src/Filesystem.cc @@ -50,6 +50,7 @@ #include #else #include +#include #include #endif diff --git a/src/cmd/CMakeLists.txt b/src/cmd/CMakeLists.txt index 89534f7aa..e831d413a 100644 --- a/src/cmd/CMakeLists.txt +++ b/src/cmd/CMakeLists.txt @@ -2,12 +2,12 @@ # Generate the ruby script for internal testing. # Note that the major version of the library is included in the name. # Ex: cmdsdformat0.rb -set(cmd_script_generated_test "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmd${sdf_target}.rb") +set(cmd_script_generated_test "${CMAKE_BINARY_DIR}/test/lib/ruby/ignition/cmd${PROJECT_NAME}.rb") set(cmd_script_configured_test "${cmd_script_generated_test}.configured") # Set the library_location variable to the full path of the library file within # the build directory. -set(library_location "$") +set(library_location "$") configure_file( "cmd${PROJECT_NAME_NO_VERSION_LOWER}.rb.in" @@ -24,12 +24,12 @@ file(GENERATE # Generate the ruby script that gets installed. # Note that the major version of the library is included in the name. # Ex: cmdsdformat0.rb -set(cmd_script_generated "${CMAKE_CURRENT_BINARY_DIR}/cmd${sdf_target}.rb") +set(cmd_script_generated "${CMAKE_CURRENT_BINARY_DIR}/cmd${PROJECT_NAME}.rb") set(cmd_script_configured "${cmd_script_generated}.configured") # Set the library_location variable to the relative path to the library file # within the install directory structure. -set(library_location "../../../${CMAKE_INSTALL_LIBDIR}/$") +set(library_location "../../../${CMAKE_INSTALL_LIBDIR}/$") configure_file( "cmd${PROJECT_NAME_NO_VERSION_LOWER}.rb.in" diff --git a/src/cmd/cmdsdformat.rb.in b/src/cmd/cmdsdformat.rb.in index 4d354c3b9..ea564f415 100644 --- a/src/cmd/cmdsdformat.rb.in +++ b/src/cmd/cmdsdformat.rb.in @@ -29,7 +29,7 @@ require 'optparse' # Constants. LIBRARY_NAME = '@library_location@' -LIBRARY_VERSION = '@SDF_VERSION_FULL@' +LIBRARY_VERSION = '@PROJECT_VERSION_FULL@' COMMON_OPTIONS = " -h [ --help ] Print this help message.\n"\ " --force-version Use a specific library version.\n"\ diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 22926fd5a..466d6f637 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,33 +1,18 @@ -include_directories ( - ${PROJECT_SOURCE_DIR}/include - ${PROJECT_BINARY_DIR}/include - ${PROJECT_SOURCE_DIR}/test/gtest/include - ${PROJECT_SOURCE_DIR}/test/gtest - ${PROJECT_SOURCE_DIR}/test - ${IGNITION-MATH_INCLUDE_DIRS} -) - -link_directories( - ${IGNITION-MATH_LIBRARY_DIRS} -) - -if (USE_EXTERNAL_TINYXML) - include_directories(${tinyxml_INCLUDE_DIRS}) - link_directories(${tinyxml_LIBRARY_DIRS}) -endif() - -configure_file(test_config.h.in ${PROJECT_BINARY_DIR}/test_config.h) +get_filename_component(IGN_PATH ${IGN_PROGRAM} DIRECTORY) +configure_file(test_config.h.in ${PROJECT_BINARY_DIR}/include/test_config.h) # Build gtest add_library(gtest STATIC gtest/src/gtest-all.cc) +target_include_directories(gtest + PUBLIC + ${PROJECT_SOURCE_DIR}/test/gtest/include + ${PROJECT_SOURCE_DIR}/test/gtest +) add_library(gtest_main STATIC gtest/src/gtest_main.cc) target_link_libraries(gtest_main gtest) -set(GTEST_LIBRARY "${PROJECT_BINARY_DIR}/test/libgtest.a") -set(GTEST_MAIN_LIBRARY "${PROJECT_BINARY_DIR}/test/libgtest_main.a") execute_process(COMMAND cmake -E remove_directory ${CMAKE_BINARY_DIR}/test_results) execute_process(COMMAND cmake -E make_directory ${CMAKE_BINARY_DIR}/test_results) -include_directories(${GTEST_INCLUDE_DIRS}) add_subdirectory(integration) add_subdirectory(performance) diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index 22635b46b..eed5cea69 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -56,12 +56,10 @@ find_program(XMLLINT_EXE xmllint) if (EXISTS ${XMLLINT_EXE}) set (tests ${tests} schema_test.cc) else() - BUILD_WARNING("xmllint not found. schema_test won't be run") + ign_build_warning("xmllint not found. schema_test won't be run") endif() -link_directories(${PROJECT_BINARY_DIR}/test) - -sdf_build_tests(${tests}) +ign_build_tests(TYPE ${TEST_TYPE} SOURCES ${tests} INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/test) if (EXISTS ${XMLLINT_EXE}) # Need to run schema target (build .xsd files) before running schema_test @@ -72,5 +70,5 @@ endif() if (UNIX AND NOT APPLE) configure_file(all_symbols_have_version.bash.in ${CMAKE_CURRENT_BINARY_DIR}/all_symbols_have_version.bash @ONLY) add_test(NAME INTEGRATION_versioned_symbols - COMMAND bash ${CMAKE_CURRENT_BINARY_DIR}/all_symbols_have_version.bash ${CMAKE_BINARY_DIR}/src/libsdformat${SDF_MAJOR_VERSION}.so) + COMMAND bash ${CMAKE_CURRENT_BINARY_DIR}/all_symbols_have_version.bash $) endif() diff --git a/test/integration/all_symbols_have_version.bash.in b/test/integration/all_symbols_have_version.bash.in index cdb5055d1..d69a58442 100644 --- a/test/integration/all_symbols_have_version.bash.in +++ b/test/integration/all_symbols_have_version.bash.in @@ -1,7 +1,7 @@ # Returns non-zero exit code if there are symbols which don't contain the project major version LIBPATH=$1 -VERSIONED_NS=v@SDF_MAJOR_VERSION@ +VERSIONED_NS=v@PROJECT_VERSION_MAJOR@ # Sanity check - there should be at least one symbol NUM_SYMBOLS=$(nm $LIBPATH | grep -e "sdf" | wc -l) diff --git a/test/performance/CMakeLists.txt b/test/performance/CMakeLists.txt index 8df89ac74..807cb38e6 100644 --- a/test/performance/CMakeLists.txt +++ b/test/performance/CMakeLists.txt @@ -4,6 +4,4 @@ set(tests parser_urdf.cc ) -link_directories(${PROJECT_BINARY_DIR}/test) - -sdf_build_tests(${tests}) +ign_build_tests(TYPE ${TEST_TYPE} SOURCES ${tests} INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/test) diff --git a/test/test_config.h.in b/test/test_config.h.in index 0342e73a9..cf63247bd 100644 --- a/test/test_config.h.in +++ b/test/test_config.h.in @@ -19,7 +19,7 @@ #define SDF_TEST_CONFIG_HH_ #define IGN_CONFIG_PATH "@CMAKE_BINARY_DIR@/test/conf" -#define IGN_PATH "@IGNITION-TOOLS_BINARY_DIRS@" +#define IGN_PATH "@IGN_PATH@" #define IGN_TEST_LIBRARY_PATH "${PROJECT_BINARY_DIR}/src:"\ "@IGNITION-MSGS_LIBRARY_DIRS@:" #define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}" diff --git a/tools/check_test_ran.py b/tools/check_test_ran.py deleted file mode 100755 index 304eb7cab..000000000 --- a/tools/check_test_ran.py +++ /dev/null @@ -1,79 +0,0 @@ -#!/usr/bin/env python -# Software License Agreement (BSD License) -# -# Copyright (c) 2008, Willow Garage, Inc. -# All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following -# disclaimer in the documentation and/or other materials provided -# with the distribution. -# * Neither the name of Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived -# from this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -# Revision $Id: check_test_ran.py 16671 2012-04-27 16:15:28Z dthomas $ - -""" -Writes a test failure out to test file if it doesn't exist. -""" - -# Adapted from rosunit/check_test_ran.py - -from __future__ import print_function -NAME="check_test_ran.py" - -import os -import sys - -def usage(): - print("""Usage: -\t%s test-file.xml -"""%(NAME), file=sys.stderr) - print(sys.argv) - sys.exit(getattr(os, 'EX_USAGE', 1)) - -def check_main(): - if len(sys.argv) < 2: - usage() - test_file = sys.argv[1] - - print("Checking for test results in %s"%test_file) - - if not os.path.exists(test_file): - if not os.path.exists(os.path.dirname(test_file)): - os.makedirs(os.path.dirname(test_file)) - - print("Cannot find results, writing failure results to", test_file) - - with open(test_file, 'w') as f: - test_name = os.path.basename(test_file) - d = {'test': test_name, 'test_file': test_file } - f.write(""" - - - - -"""%d) - -if __name__ == '__main__': - check_main() diff --git a/tools/code_check.sh b/tools/code_check.sh deleted file mode 100755 index bd24da512..000000000 --- a/tools/code_check.sh +++ /dev/null @@ -1,67 +0,0 @@ -#!/bin/sh - -# Jenkins will pass -xml, in which case we want to generate XML output -xmlout=0 -if test "$1" = "-xmldir" -a -n "$2"; then - xmlout=1 - xmldir=$2 - mkdir -p $xmldir - rm -rf $xmldir/*.xml - # Assuming that Jenkins called, the `build` directory is a sibling to the src dir - builddir=../build -else - # This is a heuristic guess; not every developer puts the `build` dir in the src dir - builddir=./build -fi - -# Use a suppression file for spurious errors -SUPPRESS=/tmp/sdf_cpp_check.suppress -echo "" > $SUPPRESS - -# Use another suppression file for unused function checking -SUPPRESS2=/tmp/sdf_cpp_check2.suppress -echo "*:src/parser_urdf.cc" > $SUPPRESS2 - -CHECK_FILE_DIRS="./src ./include ./examples ./test/performance ./test/integration" - -#cppcheck -CPPCHECK_BASE="cppcheck -q --suppressions-list=$SUPPRESS --inline-suppr" -CPPCHECK_BASE2="cppcheck -q --suppressions-list=$SUPPRESS2 --inline-suppr" -CPPCHECK_FILES=`find $CHECK_FILE_DIRS -name "*.cc"` -CPPCHECK_INCLUDES="-I include -I test -I . -I $builddir -I $builddir/include" -CPPCHECK_COMMAND1="-j 4 --enable=style,performance,portability,information $CPPCHECK_FILES" -# Unused function checking must happen in one job -CPPCHECK_COMMAND2="--enable=unusedFunction $CPPCHECK_FILES" -# -j 4 was used previously in CPPCHECK_COMMAND3 but it will generate a false -# warning as described in bug: -# http://sourceforge.net/apps/trac/cppcheck/ticket/4946 -CPPCHECK_COMMAND3="-j 1 --enable=missingInclude --suppress=missingIncludeSystem $CPPCHECK_FILES $CPPCHECK_INCLUDES --check-config" -if [ $xmlout -eq 1 ]; then - # Performance, style, portability, and information - ($CPPCHECK_BASE --xml --xml-version=2 $CPPCHECK_COMMAND1) 2> $xmldir/cppcheck.xml - - # Unused function checking - ($CPPCHECK_BASE2 --xml --xml-version=2 $CPPCHECK_COMMAND2) 2> $xmldir/cppcheck-unused-functions.xml - - # Check the configuration - ($CPPCHECK_BASE --xml --xml-version=2 $CPPCHECK_COMMAND3) 2> $xmldir/cppcheck-configuration.xml -else - # Performance, style, portability, and information - $CPPCHECK_BASE $CPPCHECK_COMMAND1 2>&1 - - # Unused function checking - $CPPCHECK_BASE2 $CPPCHECK_COMMAND2 2>&1 - - # Check the configuration - $CPPCHECK_BASE $CPPCHECK_COMMAND3 2>&1 -fi - -# cpplint -# exclude urdf files for now, since they generate lots of errors -CPPLINT_FILES=`find $CHECK_FILE_DIRS -name "*.cc" -o -name "*.hh" | grep -iv "/urdf"` -if [ $xmlout -eq 1 ]; then - (echo $CPPLINT_FILES | xargs python tools/cpplint.py 2>&1) \ - | python tools/cpplint_to_cppcheckxml.py 2> $xmldir/cpplint.xml -else - echo $CPPLINT_FILES | xargs python tools/cpplint.py 2>&1 -fi diff --git a/tools/cpplint.py b/tools/cpplint.py deleted file mode 100644 index 1632bed19..000000000 --- a/tools/cpplint.py +++ /dev/null @@ -1,6923 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2009 Google Inc. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are -# met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above -# copyright notice, this list of conditions and the following disclaimer -# in the documentation and/or other materials provided with the -# distribution. -# * Neither the name of Google Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR -# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT -# OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT -# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, -# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY -# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT -# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - -# Imported from https://github.com/cpplint/cpplint: -# https://github.com/cpplint/cpplint/blob/0f2319741f3407d8638cdc7c41e4fc9bad217f68/cpplint.py - -"""Does google-lint on c++ files. - -The goal of this script is to identify places in the code that *may* -be in non-compliance with google style. It does not attempt to fix -up these problems -- the point is to educate. It does also not -attempt to find all problems, or to ensure that everything it does -find is legitimately a problem. - -In particular, we can get very confused by /* and // inside strings! -We do a small hack, which is to ignore //'s with "'s after them on the -same line, but it is far from perfect (in either direction). -""" - -import codecs -import copy -import getopt -import glob -import itertools -import math # for log -import os -import re -import sre_compile -import string -import sys -import sysconfig -import unicodedata -import xml.etree.ElementTree - -# if empty, use defaults -_valid_extensions = set([]) - -__VERSION__ = '1.5.4' - -try: - xrange # Python 2 -except NameError: - # -- pylint: disable=redefined-builtin - xrange = range # Python 3 - - -_USAGE = """ -Syntax: cpplint.py [--verbose=#] [--output=emacs|eclipse|vs7|junit|sed|gsed] - [--filter=-x,+y,...] - [--counting=total|toplevel|detailed] [--root=subdir] - [--repository=path] - [--linelength=digits] [--headers=x,y,...] - [--recursive] - [--exclude=path] - [--extensions=hpp,cpp,...] - [--includeorder=default|standardcfirst] - [--quiet] - [--version] - [file] ... - - Style checker for C/C++ source files. - This is a fork of the Google style checker with minor extensions. - - The style guidelines this tries to follow are those in - https://google.github.io/styleguide/cppguide.html - - Every problem is given a confidence score from 1-5, with 5 meaning we are - certain of the problem, and 1 meaning it could be a legitimate construct. - This will miss some errors, and is not a substitute for a code review. - - To suppress false-positive errors of a certain category, add a - 'NOLINT(category)' comment to the line. NOLINT or NOLINT(*) - suppresses errors of all categories on that line. - - The files passed in will be linted; at least one file must be provided. - Default linted extensions are %s. - Other file types will be ignored. - Change the extensions with the --extensions flag. - - Flags: - - output=emacs|eclipse|vs7|junit|sed|gsed - By default, the output is formatted to ease emacs parsing. Visual Studio - compatible output (vs7) may also be used. Further support exists for - eclipse (eclipse), and JUnit (junit). XML parsers such as those used - in Jenkins and Bamboo may also be used. - The sed format outputs sed commands that should fix some of the errors. - Note that this requires gnu sed. If that is installed as gsed on your - system (common e.g. on macOS with homebrew) you can use the gsed output - format. Sed commands are written to stdout, not stderr, so you should be - able to pipe output straight to a shell to run the fixes. - - verbose=# - Specify a number 0-5 to restrict errors to certain verbosity levels. - Errors with lower verbosity levels have lower confidence and are more - likely to be false positives. - - quiet - Don't print anything if no errors are found. - - filter=-x,+y,... - Specify a comma-separated list of category-filters to apply: only - error messages whose category names pass the filters will be printed. - (Category names are printed with the message and look like - "[whitespace/indent]".) Filters are evaluated left to right. - "-FOO" and "FOO" means "do not print categories that start with FOO". - "+FOO" means "do print categories that start with FOO". - - Examples: --filter=-whitespace,+whitespace/braces - --filter=whitespace,runtime/printf,+runtime/printf_format - --filter=-,+build/include_what_you_use - - To see a list of all the categories used in cpplint, pass no arg: - --filter= - - counting=total|toplevel|detailed - The total number of errors found is always printed. If - 'toplevel' is provided, then the count of errors in each of - the top-level categories like 'build' and 'whitespace' will - also be printed. If 'detailed' is provided, then a count - is provided for each category like 'build/class'. - - repository=path - The top level directory of the repository, used to derive the header - guard CPP variable. By default, this is determined by searching for a - path that contains .git, .hg, or .svn. When this flag is specified, the - given path is used instead. This option allows the header guard CPP - variable to remain consistent even if members of a team have different - repository root directories (such as when checking out a subdirectory - with SVN). In addition, users of non-mainstream version control systems - can use this flag to ensure readable header guard CPP variables. - - Examples: - Assuming that Alice checks out ProjectName and Bob checks out - ProjectName/trunk and trunk contains src/chrome/ui/browser.h, then - with no --repository flag, the header guard CPP variable will be: - - Alice => TRUNK_SRC_CHROME_BROWSER_UI_BROWSER_H_ - Bob => SRC_CHROME_BROWSER_UI_BROWSER_H_ - - If Alice uses the --repository=trunk flag and Bob omits the flag or - uses --repository=. then the header guard CPP variable will be: - - Alice => SRC_CHROME_BROWSER_UI_BROWSER_H_ - Bob => SRC_CHROME_BROWSER_UI_BROWSER_H_ - - root=subdir - The root directory used for deriving header guard CPP variable. - This directory is relative to the top level directory of the repository - which by default is determined by searching for a directory that contains - .git, .hg, or .svn but can also be controlled with the --repository flag. - If the specified directory does not exist, this flag is ignored. - - Examples: - Assuming that src is the top level directory of the repository (and - cwd=top/src), the header guard CPP variables for - src/chrome/browser/ui/browser.h are: - - No flag => CHROME_BROWSER_UI_BROWSER_H_ - --root=chrome => BROWSER_UI_BROWSER_H_ - --root=chrome/browser => UI_BROWSER_H_ - --root=.. => SRC_CHROME_BROWSER_UI_BROWSER_H_ - - linelength=digits - This is the allowed line length for the project. The default value is - 80 characters. - - Examples: - --linelength=120 - - recursive - Search for files to lint recursively. Each directory given in the list - of files to be linted is replaced by all files that descend from that - directory. Files with extensions not in the valid extensions list are - excluded. - - exclude=path - Exclude the given path from the list of files to be linted. Relative - paths are evaluated relative to the current directory and shell globbing - is performed. This flag can be provided multiple times to exclude - multiple files. - - Examples: - --exclude=one.cc - --exclude=src/*.cc - --exclude=src/*.cc --exclude=test/*.cc - - extensions=extension,extension,... - The allowed file extensions that cpplint will check - - Examples: - --extensions=%s - - includeorder=default|standardcfirst - For the build/include_order rule, the default is to blindly assume angle - bracket includes with file extension are c-system-headers (default), - even knowing this will have false classifications. - The default is established at google. - standardcfirst means to instead use an allow-list of known c headers and - treat all others as separate group of "other system headers". The C headers - included are those of the C-standard lib and closely related ones. - - headers=x,y,... - The header extensions that cpplint will treat as .h in checks. Values are - automatically added to --extensions list. - (by default, only files with extensions %s will be assumed to be headers) - - Examples: - --headers=%s - --headers=hpp,hxx - --headers=hpp - - cpplint.py supports per-directory configurations specified in CPPLINT.cfg - files. CPPLINT.cfg file can contain a number of key=value pairs. - Currently the following options are supported: - - set noparent - filter=+filter1,-filter2,... - exclude_files=regex - linelength=80 - root=subdir - headers=x,y,... - - "set noparent" option prevents cpplint from traversing directory tree - upwards looking for more .cfg files in parent directories. This option - is usually placed in the top-level project directory. - - The "filter" option is similar in function to --filter flag. It specifies - message filters in addition to the |_DEFAULT_FILTERS| and those specified - through --filter command-line flag. - - "exclude_files" allows to specify a regular expression to be matched against - a file name. If the expression matches, the file is skipped and not run - through the linter. - - "linelength" allows to specify the allowed line length for the project. - - The "root" option is similar in function to the --root flag (see example - above). Paths are relative to the directory of the CPPLINT.cfg. - - The "headers" option is similar in function to the --headers flag - (see example above). - - CPPLINT.cfg has an effect on files in the same directory and all - sub-directories, unless overridden by a nested configuration file. - - Example file: - filter=-build/include_order,+build/include_alpha - exclude_files=.*\\.cc - - The above example disables build/include_order warning and enables - build/include_alpha as well as excludes all .cc from being - processed by linter, in the current directory (where the .cfg - file is located) and all sub-directories. -""" - -# We categorize each error message we print. Here are the categories. -# We want an explicit list so we can list them all in cpplint --filter=. -# If you add a new error message with a new category, add it to the list -# here! cpplint_unittest.py should tell you if you forget to do this. -_ERROR_CATEGORIES = [ - 'build/class', - 'build/c++11', - 'build/c++14', - 'build/c++tr1', - 'build/deprecated', - 'build/endif_comment', - 'build/explicit_make_pair', - 'build/forward_decl', - 'build/header_guard', - 'build/include', - 'build/include_subdir', - 'build/include_alpha', - 'build/include_order', - 'build/include_what_you_use', - 'build/namespaces_headers', - 'build/namespaces_literals', - 'build/namespaces', - 'build/printf_format', - 'build/storage_class', - 'legal/copyright', - 'readability/alt_tokens', - 'readability/braces', - 'readability/casting', - 'readability/check', - 'readability/constructors', - 'readability/fn_size', - 'readability/inheritance', - 'readability/multiline_comment', - 'readability/multiline_string', - 'readability/namespace', - 'readability/nolint', - 'readability/nul', - 'readability/strings', - 'readability/todo', - 'readability/utf8', - 'runtime/arrays', - 'runtime/casting', - 'runtime/explicit', - 'runtime/int', - 'runtime/init', - 'runtime/invalid_increment', - 'runtime/member_string_references', - 'runtime/memset', - 'runtime/indentation_namespace', - 'runtime/operator', - 'runtime/printf', - 'runtime/printf_format', - 'runtime/references', - 'runtime/string', - 'runtime/threadsafe_fn', - 'runtime/vlog', - 'whitespace/blank_line', - 'whitespace/braces', - 'whitespace/comma', - 'whitespace/comments', - 'whitespace/empty_conditional_body', - 'whitespace/empty_if_body', - 'whitespace/empty_loop_body', - 'whitespace/end_of_line', - 'whitespace/ending_newline', - 'whitespace/forcolon', - 'whitespace/indent', - 'whitespace/line_length', - 'whitespace/newline', - 'whitespace/operators', - 'whitespace/parens', - 'whitespace/semicolon', - 'whitespace/tab', - 'whitespace/todo', - ] - -# keywords to use with --outputs which generate stdout for machine processing -_MACHINE_OUTPUTS = [ - 'junit', - 'sed', - 'gsed' -] - -# These error categories are no longer enforced by cpplint, but for backwards- -# compatibility they may still appear in NOLINT comments. -_LEGACY_ERROR_CATEGORIES = [ - 'readability/streams', - 'readability/function', - ] - -# The default state of the category filter. This is overridden by the --filter= -# flag. By default all errors are on, so only add here categories that should be -# off by default (i.e., categories that must be enabled by the --filter= flags). -# All entries here should start with a '-' or '+', as in the --filter= flag. -_DEFAULT_FILTERS = [ - '-build/c++11', - '-build/header_guard', - '-build/include_alpha', - '-build/include_order', - '-build/include_subdir', - '-build/namespaces', - '-readability/namespace', - '-runtime/indentation_namespace', - '-runtime/references', - '-whitespace/blank_line', - '-whitespace/braces', - '-whitespace/indent', - '-whitespace/newline', - '-whitespace/parens', - ] - -# The default list of categories suppressed for C (not C++) files. -_DEFAULT_C_SUPPRESSED_CATEGORIES = [ - 'readability/casting', - ] - -# The default list of categories suppressed for Linux Kernel files. -_DEFAULT_KERNEL_SUPPRESSED_CATEGORIES = [ - 'whitespace/tab', - ] - -# We used to check for high-bit characters, but after much discussion we -# decided those were OK, as long as they were in UTF-8 and didn't represent -# hard-coded international strings, which belong in a separate i18n file. - -# C++ headers -_CPP_HEADERS = frozenset([ - # Legacy - 'algobase.h', - 'algo.h', - 'alloc.h', - 'builtinbuf.h', - 'bvector.h', - 'complex.h', - 'defalloc.h', - 'deque.h', - 'editbuf.h', - 'fstream.h', - 'function.h', - 'hash_map', - 'hash_map.h', - 'hash_set', - 'hash_set.h', - 'hashtable.h', - 'heap.h', - 'indstream.h', - 'iomanip.h', - 'iostream.h', - 'istream.h', - 'iterator.h', - 'list.h', - 'map.h', - 'multimap.h', - 'multiset.h', - 'ostream.h', - 'pair.h', - 'parsestream.h', - 'pfstream.h', - 'procbuf.h', - 'pthread_alloc', - 'pthread_alloc.h', - 'rope', - 'rope.h', - 'ropeimpl.h', - 'set.h', - 'slist', - 'slist.h', - 'stack.h', - 'stdiostream.h', - 'stl_alloc.h', - 'stl_relops.h', - 'streambuf.h', - 'stream.h', - 'strfile.h', - 'strstream.h', - 'tempbuf.h', - 'tree.h', - 'type_traits.h', - 'vector.h', - # 17.6.1.2 C++ library headers - 'algorithm', - 'array', - 'atomic', - 'bitset', - 'chrono', - 'codecvt', - 'complex', - 'condition_variable', - 'deque', - 'exception', - 'forward_list', - 'fstream', - 'functional', - 'future', - 'initializer_list', - 'iomanip', - 'ios', - 'iosfwd', - 'iostream', - 'istream', - 'iterator', - 'limits', - 'list', - 'locale', - 'map', - 'memory', - 'mutex', - 'new', - 'numeric', - 'ostream', - 'queue', - 'random', - 'ratio', - 'regex', - 'scoped_allocator', - 'set', - 'sstream', - 'stack', - 'stdexcept', - 'streambuf', - 'string', - 'strstream', - 'system_error', - 'thread', - 'tuple', - 'typeindex', - 'typeinfo', - 'type_traits', - 'unordered_map', - 'unordered_set', - 'utility', - 'valarray', - 'vector', - # 17.6.1.2 C++14 headers - 'shared_mutex', - # 17.6.1.2 C++17 headers - 'any', - 'charconv', - 'codecvt', - 'execution', - 'filesystem', - 'memory_resource', - 'optional', - 'string_view', - 'variant', - # 17.6.1.2 C++ headers for C library facilities - 'cassert', - 'ccomplex', - 'cctype', - 'cerrno', - 'cfenv', - 'cfloat', - 'cinttypes', - 'ciso646', - 'climits', - 'clocale', - 'cmath', - 'csetjmp', - 'csignal', - 'cstdalign', - 'cstdarg', - 'cstdbool', - 'cstddef', - 'cstdint', - 'cstdio', - 'cstdlib', - 'cstring', - 'ctgmath', - 'ctime', - 'cuchar', - 'cwchar', - 'cwctype', - ]) - -# C headers -_C_HEADERS = frozenset([ - # System C headers - 'assert.h', - 'complex.h', - 'ctype.h', - 'errno.h', - 'fenv.h', - 'float.h', - 'inttypes.h', - 'iso646.h', - 'limits.h', - 'locale.h', - 'math.h', - 'setjmp.h', - 'signal.h', - 'stdalign.h', - 'stdarg.h', - 'stdatomic.h', - 'stdbool.h', - 'stddef.h', - 'stdint.h', - 'stdio.h', - 'stdlib.h', - 'stdnoreturn.h', - 'string.h', - 'tgmath.h', - 'threads.h', - 'time.h', - 'uchar.h', - 'wchar.h', - 'wctype.h', - # additional POSIX C headers - 'aio.h', - 'arpa/inet.h', - 'cpio.h', - 'dirent.h', - 'dlfcn.h', - 'fcntl.h', - 'fmtmsg.h', - 'fnmatch.h', - 'ftw.h', - 'glob.h', - 'grp.h', - 'iconv.h', - 'langinfo.h', - 'libgen.h', - 'monetary.h', - 'mqueue.h', - 'ndbm.h', - 'net/if.h', - 'netdb.h', - 'netinet/in.h', - 'netinet/tcp.h', - 'nl_types.h', - 'poll.h', - 'pthread.h', - 'pwd.h', - 'regex.h', - 'sched.h', - 'search.h', - 'semaphore.h', - 'setjmp.h', - 'signal.h', - 'spawn.h', - 'strings.h', - 'stropts.h', - 'syslog.h', - 'tar.h', - 'termios.h', - 'trace.h', - 'ulimit.h', - 'unistd.h', - 'utime.h', - 'utmpx.h', - 'wordexp.h', - # additional GNUlib headers - 'a.out.h', - 'aliases.h', - 'alloca.h', - 'ar.h', - 'argp.h', - 'argz.h', - 'byteswap.h', - 'crypt.h', - 'endian.h', - 'envz.h', - 'err.h', - 'error.h', - 'execinfo.h', - 'fpu_control.h', - 'fstab.h', - 'fts.h', - 'getopt.h', - 'gshadow.h', - 'ieee754.h', - 'ifaddrs.h', - 'libintl.h', - 'mcheck.h', - 'mntent.h', - 'obstack.h', - 'paths.h', - 'printf.h', - 'pty.h', - 'resolv.h', - 'shadow.h', - 'sysexits.h', - 'ttyent.h', - # Additional linux glibc headers - 'dlfcn.h', - 'elf.h', - 'features.h', - 'gconv.h', - 'gnu-versions.h', - 'lastlog.h', - 'libio.h', - 'link.h', - 'malloc.h', - 'memory.h', - 'netash/ash.h', - 'netatalk/at.h', - 'netax25/ax25.h', - 'neteconet/ec.h', - 'netipx/ipx.h', - 'netiucv/iucv.h', - 'netpacket/packet.h', - 'netrom/netrom.h', - 'netrose/rose.h', - 'nfs/nfs.h', - 'nl_types.h', - 'nss.h', - 're_comp.h', - 'regexp.h', - 'sched.h', - 'sgtty.h', - 'stab.h', - 'stdc-predef.h', - 'stdio_ext.h', - 'syscall.h', - 'termio.h', - 'thread_db.h', - 'ucontext.h', - 'ustat.h', - 'utmp.h', - 'values.h', - 'wait.h', - 'xlocale.h', - # Hardware specific headers - 'arm_neon.h', - 'emmintrin.h', - 'xmmintin.h', - ]) - -# Folders of C libraries so commonly used in C++, -# that they have parity with standard C libraries. -C_STANDARD_HEADER_FOLDERS = frozenset([ - # standard C library - "sys", - # glibc for linux - "arpa", - "asm-generic", - "bits", - "gnu", - "net", - "netinet", - "protocols", - "rpc", - "rpcsvc", - "scsi", - # linux kernel header - "drm", - "linux", - "misc", - "mtd", - "rdma", - "sound", - "video", - "xen", - ]) - -# Type names -_TYPES = re.compile( - r'^(?:' - # [dcl.type.simple] - r'(char(16_t|32_t)?)|wchar_t|' - r'bool|short|int|long|signed|unsigned|float|double|' - # [support.types] - r'(ptrdiff_t|size_t|max_align_t|nullptr_t)|' - # [cstdint.syn] - r'(u?int(_fast|_least)?(8|16|32|64)_t)|' - r'(u?int(max|ptr)_t)|' - r')$') - - -# These headers are excluded from [build/include] and [build/include_order] -# checks: -# - Anything not following google file name conventions (containing an -# uppercase character, such as Python.h or nsStringAPI.h, for example). -# - Lua headers. -_THIRD_PARTY_HEADERS_PATTERN = re.compile( - r'^(?:[^/]*[A-Z][^/]*\.h|lua\.h|lauxlib\.h|lualib\.h)$') - -# Pattern for matching FileInfo.BaseName() against test file name -_test_suffixes = ['_test', '_regtest', '_unittest'] -_TEST_FILE_SUFFIX = '(' + '|'.join(_test_suffixes) + r')$' - -# Pattern that matches only complete whitespace, possibly across multiple lines. -_EMPTY_CONDITIONAL_BODY_PATTERN = re.compile(r'^\s*$', re.DOTALL) - -# Assertion macros. These are defined in base/logging.h and -# testing/base/public/gunit.h. -_CHECK_MACROS = [ - 'DCHECK', 'CHECK', - 'EXPECT_TRUE', 'ASSERT_TRUE', - 'EXPECT_FALSE', 'ASSERT_FALSE', - ] - -# Replacement macros for CHECK/DCHECK/EXPECT_TRUE/EXPECT_FALSE -_CHECK_REPLACEMENT = dict([(macro_var, {}) for macro_var in _CHECK_MACROS]) - -for op, replacement in [('==', 'EQ'), ('!=', 'NE'), - ('>=', 'GE'), ('>', 'GT'), - ('<=', 'LE'), ('<', 'LT')]: - _CHECK_REPLACEMENT['DCHECK'][op] = 'DCHECK_%s' % replacement - _CHECK_REPLACEMENT['CHECK'][op] = 'CHECK_%s' % replacement - _CHECK_REPLACEMENT['EXPECT_TRUE'][op] = 'EXPECT_%s' % replacement - _CHECK_REPLACEMENT['ASSERT_TRUE'][op] = 'ASSERT_%s' % replacement - -for op, inv_replacement in [('==', 'NE'), ('!=', 'EQ'), - ('>=', 'LT'), ('>', 'LE'), - ('<=', 'GT'), ('<', 'GE')]: - _CHECK_REPLACEMENT['EXPECT_FALSE'][op] = 'EXPECT_%s' % inv_replacement - _CHECK_REPLACEMENT['ASSERT_FALSE'][op] = 'ASSERT_%s' % inv_replacement - -# Alternative tokens and their replacements. For full list, see section 2.5 -# Alternative tokens [lex.digraph] in the C++ standard. -# -# Digraphs (such as '%:') are not included here since it's a mess to -# match those on a word boundary. -_ALT_TOKEN_REPLACEMENT = { - 'and': '&&', - 'bitor': '|', - 'or': '||', - 'xor': '^', - 'compl': '~', - 'bitand': '&', - 'and_eq': '&=', - 'or_eq': '|=', - 'xor_eq': '^=', - 'not': '!', - 'not_eq': '!=' - } - -# Compile regular expression that matches all the above keywords. The "[ =()]" -# bit is meant to avoid matching these keywords outside of boolean expressions. -# -# False positives include C-style multi-line comments and multi-line strings -# but those have always been troublesome for cpplint. -_ALT_TOKEN_REPLACEMENT_PATTERN = re.compile( - r'[ =()](' + ('|'.join(_ALT_TOKEN_REPLACEMENT.keys())) + r')(?=[ (]|$)') - - -# These constants define types of headers for use with -# _IncludeState.CheckNextIncludeOrder(). -_C_SYS_HEADER = 1 -_CPP_SYS_HEADER = 2 -_OTHER_SYS_HEADER = 3 -_LIKELY_MY_HEADER = 4 -_POSSIBLE_MY_HEADER = 5 -_OTHER_HEADER = 6 - -# These constants define the current inline assembly state -_NO_ASM = 0 # Outside of inline assembly block -_INSIDE_ASM = 1 # Inside inline assembly block -_END_ASM = 2 # Last line of inline assembly block -_BLOCK_ASM = 3 # The whole block is an inline assembly block - -# Match start of assembly blocks -_MATCH_ASM = re.compile(r'^\s*(?:asm|_asm|__asm|__asm__)' - r'(?:\s+(volatile|__volatile__))?' - r'\s*[{(]') - -# Match strings that indicate we're working on a C (not C++) file. -_SEARCH_C_FILE = re.compile(r'\b(?:LINT_C_FILE|' - r'vim?:\s*.*(\s*|:)filetype=c(\s*|:|$))') - -# Match string that indicates we're working on a Linux Kernel file. -_SEARCH_KERNEL_FILE = re.compile(r'\b(?:LINT_KERNEL_FILE)') - -# Commands for sed to fix the problem -_SED_FIXUPS = { - 'Remove spaces around =': r's/ = /=/', - 'Remove spaces around !=': r's/ != /!=/', - 'Remove space before ( in if (': r's/if (/if(/', - 'Remove space before ( in for (': r's/for (/for(/', - 'Remove space before ( in while (': r's/while (/while(/', - 'Remove space before ( in switch (': r's/switch (/switch(/', - 'Should have a space between // and comment': r's/\/\//\/\/ /', - 'Missing space before {': r's/\([^ ]\){/\1 {/', - 'Tab found, replace by spaces': r's/\t/ /g', - 'Line ends in whitespace. Consider deleting these extra spaces.': r's/\s*$//', - 'You don\'t need a ; after a }': r's/};/}/', - 'Missing space after ,': r's/,\([^ ]\)/, \1/g', -} - -_regexp_compile_cache = {} - -# {str, set(int)}: a map from error categories to sets of linenumbers -# on which those errors are expected and should be suppressed. -_error_suppressions = {} - -# The root directory used for deriving header guard CPP variable. -# This is set by --root flag. -_root = None -_root_debug = False - -# The top level repository directory. If set, _root is calculated relative to -# this directory instead of the directory containing version control artifacts. -# This is set by the --repository flag. -_repository = None - -# Files to exclude from linting. This is set by the --exclude flag. -_excludes = None - -# Whether to supress all PrintInfo messages, UNRELATED to --quiet flag -_quiet = False - -# The allowed line length of files. -# This is set by --linelength flag. -_line_length = 80 - -# This allows to use different include order rule than default -_include_order = "default" - -try: - unicode -except NameError: - # -- pylint: disable=redefined-builtin - basestring = unicode = str - -try: - long -except NameError: - # -- pylint: disable=redefined-builtin - long = int - -if sys.version_info < (3,): - # -- pylint: disable=no-member - # BINARY_TYPE = str - itervalues = dict.itervalues - iteritems = dict.iteritems -else: - # BINARY_TYPE = bytes - itervalues = dict.values - iteritems = dict.items - -def unicode_escape_decode(x): - if sys.version_info < (3,): - return codecs.unicode_escape_decode(x)[0] - else: - return x - -# Treat all headers starting with 'h' equally: .h, .hpp, .hxx etc. -# This is set by --headers flag. -_hpp_headers = set([]) - -# {str, bool}: a map from error categories to booleans which indicate if the -# category should be suppressed for every line. -_global_error_suppressions = {} - -def ProcessHppHeadersOption(val): - global _hpp_headers - try: - _hpp_headers = {ext.strip() for ext in val.split(',')} - except ValueError: - PrintUsage('Header extensions must be comma separated list.') - -def ProcessIncludeOrderOption(val): - if val is None or val == "default": - pass - elif val == "standardcfirst": - global _include_order - _include_order = val - else: - PrintUsage('Invalid includeorder value %s. Expected default|standardcfirst') - -def IsHeaderExtension(file_extension): - return file_extension in GetHeaderExtensions() - -def GetHeaderExtensions(): - if _hpp_headers: - return _hpp_headers - if _valid_extensions: - return {h for h in _valid_extensions if 'h' in h} - return set(['h', 'hh', 'hpp', 'hxx', 'h++', 'cuh']) - -# The allowed extensions for file names -# This is set by --extensions flag -def GetAllExtensions(): - return GetHeaderExtensions().union(_valid_extensions or set( - ['c', 'cc', 'cpp', 'cxx', 'c++', 'cu'])) - -def ProcessExtensionsOption(val): - global _valid_extensions - try: - extensions = [ext.strip() for ext in val.split(',')] - _valid_extensions = set(extensions) - except ValueError: - PrintUsage('Extensions should be a comma-separated list of values;' - 'for example: extensions=hpp,cpp\n' - 'This could not be parsed: "%s"' % (val,)) - -def GetNonHeaderExtensions(): - return GetAllExtensions().difference(GetHeaderExtensions()) - -def ParseNolintSuppressions(filename, raw_line, linenum, error): - """Updates the global list of line error-suppressions. - - Parses any NOLINT comments on the current line, updating the global - error_suppressions store. Reports an error if the NOLINT comment - was malformed. - - Args: - filename: str, the name of the input file. - raw_line: str, the line of input text, with comments. - linenum: int, the number of the current line. - error: function, an error handler. - """ - matched = Search(r'\bNOLINT(NEXTLINE)?\b(\([^)]+\))?', raw_line) - if matched: - if matched.group(1): - suppressed_line = linenum + 1 - else: - suppressed_line = linenum - category = matched.group(2) - if category in (None, '(*)'): # => "suppress all" - _error_suppressions.setdefault(None, set()).add(suppressed_line) - else: - if category.startswith('(') and category.endswith(')'): - category = category[1:-1] - if category in _ERROR_CATEGORIES: - _error_suppressions.setdefault(category, set()).add(suppressed_line) - elif category not in _LEGACY_ERROR_CATEGORIES: - error(filename, linenum, 'readability/nolint', 5, - 'Unknown NOLINT error category: %s' % category) - - -def ProcessGlobalSuppresions(lines): - """Updates the list of global error suppressions. - - Parses any lint directives in the file that have global effect. - - Args: - lines: An array of strings, each representing a line of the file, with the - last element being empty if the file is terminated with a newline. - """ - for line in lines: - if _SEARCH_C_FILE.search(line): - for category in _DEFAULT_C_SUPPRESSED_CATEGORIES: - _global_error_suppressions[category] = True - if _SEARCH_KERNEL_FILE.search(line): - for category in _DEFAULT_KERNEL_SUPPRESSED_CATEGORIES: - _global_error_suppressions[category] = True - - -def ResetNolintSuppressions(): - """Resets the set of NOLINT suppressions to empty.""" - _error_suppressions.clear() - _global_error_suppressions.clear() - - -def IsErrorSuppressedByNolint(category, linenum): - """Returns true if the specified error category is suppressed on this line. - - Consults the global error_suppressions map populated by - ParseNolintSuppressions/ProcessGlobalSuppresions/ResetNolintSuppressions. - - Args: - category: str, the category of the error. - linenum: int, the current line number. - Returns: - bool, True iff the error should be suppressed due to a NOLINT comment or - global suppression. - """ - return (_global_error_suppressions.get(category, False) or - linenum in _error_suppressions.get(category, set()) or - linenum in _error_suppressions.get(None, set())) - - -def Match(pattern, s): - """Matches the string with the pattern, caching the compiled regexp.""" - # The regexp compilation caching is inlined in both Match and Search for - # performance reasons; factoring it out into a separate function turns out - # to be noticeably expensive. - if pattern not in _regexp_compile_cache: - _regexp_compile_cache[pattern] = sre_compile.compile(pattern) - return _regexp_compile_cache[pattern].match(s) - - -def ReplaceAll(pattern, rep, s): - """Replaces instances of pattern in a string with a replacement. - - The compiled regex is kept in a cache shared by Match and Search. - - Args: - pattern: regex pattern - rep: replacement text - s: search string - - Returns: - string with replacements made (or original string if no replacements) - """ - if pattern not in _regexp_compile_cache: - _regexp_compile_cache[pattern] = sre_compile.compile(pattern) - return _regexp_compile_cache[pattern].sub(rep, s) - - -def Search(pattern, s): - """Searches the string for the pattern, caching the compiled regexp.""" - if pattern not in _regexp_compile_cache: - _regexp_compile_cache[pattern] = sre_compile.compile(pattern) - return _regexp_compile_cache[pattern].search(s) - - -def _IsSourceExtension(s): - """File extension (excluding dot) matches a source file extension.""" - return s in GetNonHeaderExtensions() - - -class _IncludeState(object): - """Tracks line numbers for includes, and the order in which includes appear. - - include_list contains list of lists of (header, line number) pairs. - It's a lists of lists rather than just one flat list to make it - easier to update across preprocessor boundaries. - - Call CheckNextIncludeOrder() once for each header in the file, passing - in the type constants defined above. Calls in an illegal order will - raise an _IncludeError with an appropriate error message. - - """ - # self._section will move monotonically through this set. If it ever - # needs to move backwards, CheckNextIncludeOrder will raise an error. - _INITIAL_SECTION = 0 - _MY_H_SECTION = 1 - _C_SECTION = 2 - _CPP_SECTION = 3 - _OTHER_SYS_SECTION = 4 - _OTHER_H_SECTION = 5 - - _TYPE_NAMES = { - _C_SYS_HEADER: 'C system header', - _CPP_SYS_HEADER: 'C++ system header', - _OTHER_SYS_HEADER: 'other system header', - _LIKELY_MY_HEADER: 'header this file implements', - _POSSIBLE_MY_HEADER: 'header this file may implement', - _OTHER_HEADER: 'other header', - } - _SECTION_NAMES = { - _INITIAL_SECTION: "... nothing. (This can't be an error.)", - _MY_H_SECTION: 'a header this file implements', - _C_SECTION: 'C system header', - _CPP_SECTION: 'C++ system header', - _OTHER_SYS_SECTION: 'other system header', - _OTHER_H_SECTION: 'other header', - } - - def __init__(self): - self.include_list = [[]] - self._section = None - self._last_header = None - self.ResetSection('') - - def FindHeader(self, header): - """Check if a header has already been included. - - Args: - header: header to check. - Returns: - Line number of previous occurrence, or -1 if the header has not - been seen before. - """ - for section_list in self.include_list: - for f in section_list: - if f[0] == header: - return f[1] - return -1 - - def ResetSection(self, directive): - """Reset section checking for preprocessor directive. - - Args: - directive: preprocessor directive (e.g. "if", "else"). - """ - # The name of the current section. - self._section = self._INITIAL_SECTION - # The path of last found header. - self._last_header = '' - - # Update list of includes. Note that we never pop from the - # include list. - if directive in ('if', 'ifdef', 'ifndef'): - self.include_list.append([]) - elif directive in ('else', 'elif'): - self.include_list[-1] = [] - - def SetLastHeader(self, header_path): - self._last_header = header_path - - def CanonicalizeAlphabeticalOrder(self, header_path): - """Returns a path canonicalized for alphabetical comparison. - - - replaces "-" with "_" so they both cmp the same. - - removes '-inl' since we don't require them to be after the main header. - - lowercase everything, just in case. - - Args: - header_path: Path to be canonicalized. - - Returns: - Canonicalized path. - """ - return header_path.replace('-inl.h', '.h').replace('-', '_').lower() - - def IsInAlphabeticalOrder(self, clean_lines, linenum, header_path): - """Check if a header is in alphabetical order with the previous header. - - Args: - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - header_path: Canonicalized header to be checked. - - Returns: - Returns true if the header is in alphabetical order. - """ - # If previous section is different from current section, _last_header will - # be reset to empty string, so it's always less than current header. - # - # If previous line was a blank line, assume that the headers are - # intentionally sorted the way they are. - if (self._last_header > header_path and - Match(r'^\s*#\s*include\b', clean_lines.elided[linenum - 1])): - return False - return True - - def CheckNextIncludeOrder(self, header_type): - """Returns a non-empty error message if the next header is out of order. - - This function also updates the internal state to be ready to check - the next include. - - Args: - header_type: One of the _XXX_HEADER constants defined above. - - Returns: - The empty string if the header is in the right order, or an - error message describing what's wrong. - - """ - error_message = ('Found %s after %s' % - (self._TYPE_NAMES[header_type], - self._SECTION_NAMES[self._section])) - - last_section = self._section - - if header_type == _C_SYS_HEADER: - if self._section <= self._C_SECTION: - self._section = self._C_SECTION - else: - self._last_header = '' - return error_message - elif header_type == _CPP_SYS_HEADER: - if self._section <= self._CPP_SECTION: - self._section = self._CPP_SECTION - else: - self._last_header = '' - return error_message - elif header_type == _OTHER_SYS_HEADER: - if self._section <= self._OTHER_SYS_SECTION: - self._section = self._OTHER_SYS_SECTION - else: - self._last_header = '' - return error_message - elif header_type == _LIKELY_MY_HEADER: - if self._section <= self._MY_H_SECTION: - self._section = self._MY_H_SECTION - else: - self._section = self._OTHER_H_SECTION - elif header_type == _POSSIBLE_MY_HEADER: - if self._section <= self._MY_H_SECTION: - self._section = self._MY_H_SECTION - else: - # This will always be the fallback because we're not sure - # enough that the header is associated with this file. - self._section = self._OTHER_H_SECTION - else: - assert header_type == _OTHER_HEADER - self._section = self._OTHER_H_SECTION - - if last_section != self._section: - self._last_header = '' - - return '' - - -class _CppLintState(object): - """Maintains module-wide state..""" - - def __init__(self): - self.verbose_level = 1 # global setting. - self.error_count = 0 # global count of reported errors - # filters to apply when emitting error messages - self.filters = _DEFAULT_FILTERS[:] - # backup of filter list. Used to restore the state after each file. - self._filters_backup = self.filters[:] - self.counting = 'total' # In what way are we counting errors? - self.errors_by_category = {} # string to int dict storing error counts - self.quiet = False # Suppress non-error messagess? - - # output format: - # "emacs" - format that emacs can parse (default) - # "eclipse" - format that eclipse can parse - # "vs7" - format that Microsoft Visual Studio 7 can parse - # "junit" - format that Jenkins, Bamboo, etc can parse - # "sed" - returns a gnu sed command to fix the problem - # "gsed" - like sed, but names the command gsed, e.g. for macOS homebrew users - self.output_format = 'emacs' - - # For JUnit output, save errors and failures until the end so that they - # can be written into the XML - self._junit_errors = [] - self._junit_failures = [] - - def SetOutputFormat(self, output_format): - """Sets the output format for errors.""" - self.output_format = output_format - - def SetQuiet(self, quiet): - """Sets the module's quiet settings, and returns the previous setting.""" - last_quiet = self.quiet - self.quiet = quiet - return last_quiet - - def SetVerboseLevel(self, level): - """Sets the module's verbosity, and returns the previous setting.""" - last_verbose_level = self.verbose_level - self.verbose_level = level - return last_verbose_level - - def SetCountingStyle(self, counting_style): - """Sets the module's counting options.""" - self.counting = counting_style - - def SetFilters(self, filters): - """Sets the error-message filters. - - These filters are applied when deciding whether to emit a given - error message. - - Args: - filters: A string of comma-separated filters (eg "+whitespace/indent"). - Each filter should start with + or -; else we die. - - Raises: - ValueError: The comma-separated filters did not all start with '+' or '-'. - E.g. "-,+whitespace,-whitespace/indent,whitespace/badfilter" - """ - # Default filters always have less priority than the flag ones. - self.filters = _DEFAULT_FILTERS[:] - self.AddFilters(filters) - - def AddFilters(self, filters): - """ Adds more filters to the existing list of error-message filters. """ - for filt in filters.split(','): - clean_filt = filt.strip() - if clean_filt: - self.filters.append(clean_filt) - for filt in self.filters: - if not (filt.startswith('+') or filt.startswith('-')): - raise ValueError('Every filter in --filters must start with + or -' - ' (%s does not)' % filt) - - def BackupFilters(self): - """ Saves the current filter list to backup storage.""" - self._filters_backup = self.filters[:] - - def RestoreFilters(self): - """ Restores filters previously backed up.""" - self.filters = self._filters_backup[:] - - def ResetErrorCounts(self): - """Sets the module's error statistic back to zero.""" - self.error_count = 0 - self.errors_by_category = {} - - def IncrementErrorCount(self, category): - """Bumps the module's error statistic.""" - self.error_count += 1 - if self.counting in ('toplevel', 'detailed'): - if self.counting != 'detailed': - category = category.split('/')[0] - if category not in self.errors_by_category: - self.errors_by_category[category] = 0 - self.errors_by_category[category] += 1 - - def PrintErrorCounts(self): - """Print a summary of errors by category, and the total.""" - for category, count in sorted(iteritems(self.errors_by_category)): - self.PrintInfo('Category \'%s\' errors found: %d\n' % - (category, count)) - if self.error_count > 0: - self.PrintInfo('Total errors found: %d\n' % self.error_count) - - def PrintInfo(self, message): - # _quiet does not represent --quiet flag. - # Hide infos from stdout to keep stdout pure for machine consumption - if not _quiet and self.output_format not in _MACHINE_OUTPUTS: - sys.stdout.write(message) - - def PrintError(self, message): - if self.output_format == 'junit': - self._junit_errors.append(message) - else: - sys.stderr.write(message) - - def AddJUnitFailure(self, filename, linenum, message, category, confidence): - self._junit_failures.append((filename, linenum, message, category, - confidence)) - - def FormatJUnitXML(self): - num_errors = len(self._junit_errors) - num_failures = len(self._junit_failures) - - testsuite = xml.etree.ElementTree.Element('testsuite') - testsuite.attrib['errors'] = str(num_errors) - testsuite.attrib['failures'] = str(num_failures) - testsuite.attrib['name'] = 'cpplint' - - if num_errors == 0 and num_failures == 0: - testsuite.attrib['tests'] = str(1) - xml.etree.ElementTree.SubElement(testsuite, 'testcase', name='passed') - - else: - testsuite.attrib['tests'] = str(num_errors + num_failures) - if num_errors > 0: - testcase = xml.etree.ElementTree.SubElement(testsuite, 'testcase') - testcase.attrib['name'] = 'errors' - error = xml.etree.ElementTree.SubElement(testcase, 'error') - error.text = '\n'.join(self._junit_errors) - if num_failures > 0: - # Group failures by file - failed_file_order = [] - failures_by_file = {} - for failure in self._junit_failures: - failed_file = failure[0] - if failed_file not in failed_file_order: - failed_file_order.append(failed_file) - failures_by_file[failed_file] = [] - failures_by_file[failed_file].append(failure) - # Create a testcase for each file - for failed_file in failed_file_order: - failures = failures_by_file[failed_file] - testcase = xml.etree.ElementTree.SubElement(testsuite, 'testcase') - testcase.attrib['name'] = failed_file - failure = xml.etree.ElementTree.SubElement(testcase, 'failure') - template = '{0}: {1} [{2}] [{3}]' - texts = [template.format(f[1], f[2], f[3], f[4]) for f in failures] - failure.text = '\n'.join(texts) - - xml_decl = '\n' - return xml_decl + xml.etree.ElementTree.tostring(testsuite, 'utf-8').decode('utf-8') - - -_cpplint_state = _CppLintState() - - -def _OutputFormat(): - """Gets the module's output format.""" - return _cpplint_state.output_format - - -def _SetOutputFormat(output_format): - """Sets the module's output format.""" - _cpplint_state.SetOutputFormat(output_format) - -def _Quiet(): - """Return's the module's quiet setting.""" - return _cpplint_state.quiet - -def _SetQuiet(quiet): - """Set the module's quiet status, and return previous setting.""" - return _cpplint_state.SetQuiet(quiet) - - -def _VerboseLevel(): - """Returns the module's verbosity setting.""" - return _cpplint_state.verbose_level - - -def _SetVerboseLevel(level): - """Sets the module's verbosity, and returns the previous setting.""" - return _cpplint_state.SetVerboseLevel(level) - - -def _SetCountingStyle(level): - """Sets the module's counting options.""" - _cpplint_state.SetCountingStyle(level) - - -def _Filters(): - """Returns the module's list of output filters, as a list.""" - return _cpplint_state.filters - - -def _SetFilters(filters): - """Sets the module's error-message filters. - - These filters are applied when deciding whether to emit a given - error message. - - Args: - filters: A string of comma-separated filters (eg "whitespace/indent"). - Each filter should start with + or -; else we die. - """ - _cpplint_state.SetFilters(filters) - -def _AddFilters(filters): - """Adds more filter overrides. - - Unlike _SetFilters, this function does not reset the current list of filters - available. - - Args: - filters: A string of comma-separated filters (eg "whitespace/indent"). - Each filter should start with + or -; else we die. - """ - _cpplint_state.AddFilters(filters) - -def _BackupFilters(): - """ Saves the current filter list to backup storage.""" - _cpplint_state.BackupFilters() - -def _RestoreFilters(): - """ Restores filters previously backed up.""" - _cpplint_state.RestoreFilters() - -class _FunctionState(object): - """Tracks current function name and the number of lines in its body.""" - - _NORMAL_TRIGGER = 250 # for --v=0, 500 for --v=1, etc. - _TEST_TRIGGER = 400 # about 50% more than _NORMAL_TRIGGER. - - def __init__(self): - self.in_a_function = False - self.lines_in_function = 0 - self.current_function = '' - - def Begin(self, function_name): - """Start analyzing function body. - - Args: - function_name: The name of the function being tracked. - """ - self.in_a_function = True - self.lines_in_function = 0 - self.current_function = function_name - - def Count(self): - """Count line in current function body.""" - if self.in_a_function: - self.lines_in_function += 1 - - def Check(self, error, filename, linenum): - """Report if too many lines in function body. - - Args: - error: The function to call with any errors found. - filename: The name of the current file. - linenum: The number of the line to check. - """ - if not self.in_a_function: - return - - if Match(r'T(EST|est)', self.current_function): - base_trigger = self._TEST_TRIGGER - else: - base_trigger = self._NORMAL_TRIGGER - trigger = base_trigger * 2**_VerboseLevel() - - if self.lines_in_function > trigger: - error_level = int(math.log(self.lines_in_function / base_trigger, 2)) - # 50 => 0, 100 => 1, 200 => 2, 400 => 3, 800 => 4, 1600 => 5, ... - if error_level > 5: - error_level = 5 - error(filename, linenum, 'readability/fn_size', error_level, - 'Small and focused functions are preferred:' - ' %s has %d non-comment lines' - ' (error triggered by exceeding %d lines).' % ( - self.current_function, self.lines_in_function, trigger)) - - def End(self): - """Stop analyzing function body.""" - self.in_a_function = False - - -class _IncludeError(Exception): - """Indicates a problem with the include order in a file.""" - pass - - -class FileInfo(object): - """Provides utility functions for filenames. - - FileInfo provides easy access to the components of a file's path - relative to the project root. - """ - - def __init__(self, filename): - self._filename = filename - - def FullName(self): - """Make Windows paths like Unix.""" - return os.path.abspath(self._filename).replace('\\', '/') - - def RepositoryName(self): - r"""FullName after removing the local path to the repository. - - If we have a real absolute path name here we can try to do something smart: - detecting the root of the checkout and truncating /path/to/checkout from - the name so that we get header guards that don't include things like - "C:\\Documents and Settings\\..." or "/home/username/..." in them and thus - people on different computers who have checked the source out to different - locations won't see bogus errors. - """ - fullname = self.FullName() - - if os.path.exists(fullname): - project_dir = os.path.dirname(fullname) - - # If the user specified a repository path, it exists, and the file is - # contained in it, use the specified repository path - if _repository: - repo = FileInfo(_repository).FullName() - root_dir = project_dir - while os.path.exists(root_dir): - # allow case insensitive compare on Windows - if os.path.normcase(root_dir) == os.path.normcase(repo): - return os.path.relpath(fullname, root_dir).replace('\\', '/') - one_up_dir = os.path.dirname(root_dir) - if one_up_dir == root_dir: - break - root_dir = one_up_dir - - if os.path.exists(os.path.join(project_dir, ".svn")): - # If there's a .svn file in the current directory, we recursively look - # up the directory tree for the top of the SVN checkout - root_dir = project_dir - one_up_dir = os.path.dirname(root_dir) - while os.path.exists(os.path.join(one_up_dir, ".svn")): - root_dir = os.path.dirname(root_dir) - one_up_dir = os.path.dirname(one_up_dir) - - prefix = os.path.commonprefix([root_dir, project_dir]) - return fullname[len(prefix) + 1:] - - # Not SVN <= 1.6? Try to find a git, hg, or svn top level directory by - # searching up from the current path. - root_dir = current_dir = os.path.dirname(fullname) - while current_dir != os.path.dirname(current_dir): - if (os.path.exists(os.path.join(current_dir, ".git")) or - os.path.exists(os.path.join(current_dir, ".hg")) or - os.path.exists(os.path.join(current_dir, ".svn"))): - root_dir = current_dir - current_dir = os.path.dirname(current_dir) - - if (os.path.exists(os.path.join(root_dir, ".git")) or - os.path.exists(os.path.join(root_dir, ".hg")) or - os.path.exists(os.path.join(root_dir, ".svn"))): - prefix = os.path.commonprefix([root_dir, project_dir]) - return fullname[len(prefix) + 1:] - - # Don't know what to do; header guard warnings may be wrong... - return fullname - - def Split(self): - """Splits the file into the directory, basename, and extension. - - For 'chrome/browser/browser.cc', Split() would - return ('chrome/browser', 'browser', '.cc') - - Returns: - A tuple of (directory, basename, extension). - """ - - googlename = self.RepositoryName() - project, rest = os.path.split(googlename) - return (project,) + os.path.splitext(rest) - - def BaseName(self): - """File base name - text after the final slash, before the final period.""" - return self.Split()[1] - - def Extension(self): - """File extension - text following the final period, includes that period.""" - return self.Split()[2] - - def NoExtension(self): - """File has no source file extension.""" - return '/'.join(self.Split()[0:2]) - - def IsSource(self): - """File has a source file extension.""" - return _IsSourceExtension(self.Extension()[1:]) - - -def _ShouldPrintError(category, confidence, linenum): - """If confidence >= verbose, category passes filter and is not suppressed.""" - - # There are three ways we might decide not to print an error message: - # a "NOLINT(category)" comment appears in the source, - # the verbosity level isn't high enough, or the filters filter it out. - if IsErrorSuppressedByNolint(category, linenum): - return False - - if confidence < _cpplint_state.verbose_level: - return False - - is_filtered = False - for one_filter in _Filters(): - if one_filter.startswith('-'): - if category.startswith(one_filter[1:]): - is_filtered = True - elif one_filter.startswith('+'): - if category.startswith(one_filter[1:]): - is_filtered = False - else: - assert False # should have been checked for in SetFilter. - if is_filtered: - return False - - return True - - -def Error(filename, linenum, category, confidence, message): - """Logs the fact we've found a lint error. - - We log where the error was found, and also our confidence in the error, - that is, how certain we are this is a legitimate style regression, and - not a misidentification or a use that's sometimes justified. - - False positives can be suppressed by the use of - "cpplint(category)" comments on the offending line. These are - parsed into _error_suppressions. - - Args: - filename: The name of the file containing the error. - linenum: The number of the line containing the error. - category: A string used to describe the "category" this bug - falls under: "whitespace", say, or "runtime". Categories - may have a hierarchy separated by slashes: "whitespace/indent". - confidence: A number from 1-5 representing a confidence score for - the error, with 5 meaning that we are certain of the problem, - and 1 meaning that it could be a legitimate construct. - message: The error message. - """ - if _ShouldPrintError(category, confidence, linenum): - _cpplint_state.IncrementErrorCount(category) - if _cpplint_state.output_format == 'vs7': - _cpplint_state.PrintError('%s(%s): error cpplint: [%s] %s [%d]\n' % ( - filename, linenum, category, message, confidence)) - elif _cpplint_state.output_format == 'eclipse': - sys.stderr.write('%s:%s: warning: %s [%s] [%d]\n' % ( - filename, linenum, message, category, confidence)) - elif _cpplint_state.output_format == 'junit': - _cpplint_state.AddJUnitFailure(filename, linenum, message, category, - confidence) - elif _cpplint_state.output_format in ['sed', 'gsed']: - if message in _SED_FIXUPS: - sys.stdout.write(_cpplint_state.output_format + " -i '%s%s' %s # %s [%s] [%d]\n" % ( - linenum, _SED_FIXUPS[message], filename, message, category, confidence)) - else: - sys.stderr.write('# %s:%s: "%s" [%s] [%d]\n' % ( - filename, linenum, message, category, confidence)) - else: - final_message = '%s:%s: %s [%s] [%d]\n' % ( - filename, linenum, message, category, confidence) - sys.stderr.write(final_message) - -# Matches standard C++ escape sequences per 2.13.2.3 of the C++ standard. -_RE_PATTERN_CLEANSE_LINE_ESCAPES = re.compile( - r'\\([abfnrtv?"\\\']|\d+|x[0-9a-fA-F]+)') -# Match a single C style comment on the same line. -_RE_PATTERN_C_COMMENTS = r'/\*(?:[^*]|\*(?!/))*\*/' -# Matches multi-line C style comments. -# This RE is a little bit more complicated than one might expect, because we -# have to take care of space removals tools so we can handle comments inside -# statements better. -# The current rule is: We only clear spaces from both sides when we're at the -# end of the line. Otherwise, we try to remove spaces from the right side, -# if this doesn't work we try on left side but only if there's a non-character -# on the right. -_RE_PATTERN_CLEANSE_LINE_C_COMMENTS = re.compile( - r'(\s*' + _RE_PATTERN_C_COMMENTS + r'\s*$|' + - _RE_PATTERN_C_COMMENTS + r'\s+|' + - r'\s+' + _RE_PATTERN_C_COMMENTS + r'(?=\W)|' + - _RE_PATTERN_C_COMMENTS + r')') - - -def IsCppString(line): - """Does line terminate so, that the next symbol is in string constant. - - This function does not consider single-line nor multi-line comments. - - Args: - line: is a partial line of code starting from the 0..n. - - Returns: - True, if next character appended to 'line' is inside a - string constant. - """ - - line = line.replace(r'\\', 'XX') # after this, \\" does not match to \" - return ((line.count('"') - line.count(r'\"') - line.count("'\"'")) & 1) == 1 - - -def CleanseRawStrings(raw_lines): - """Removes C++11 raw strings from lines. - - Before: - static const char kData[] = R"( - multi-line string - )"; - - After: - static const char kData[] = "" - (replaced by blank line) - ""; - - Args: - raw_lines: list of raw lines. - - Returns: - list of lines with C++11 raw strings replaced by empty strings. - """ - - delimiter = None - lines_without_raw_strings = [] - for line in raw_lines: - if delimiter: - # Inside a raw string, look for the end - end = line.find(delimiter) - if end >= 0: - # Found the end of the string, match leading space for this - # line and resume copying the original lines, and also insert - # a "" on the last line. - leading_space = Match(r'^(\s*)\S', line) - line = leading_space.group(1) + '""' + line[end + len(delimiter):] - delimiter = None - else: - # Haven't found the end yet, append a blank line. - line = '""' - - # Look for beginning of a raw string, and replace them with - # empty strings. This is done in a loop to handle multiple raw - # strings on the same line. - while delimiter is None: - # Look for beginning of a raw string. - # See 2.14.15 [lex.string] for syntax. - # - # Once we have matched a raw string, we check the prefix of the - # line to make sure that the line is not part of a single line - # comment. It's done this way because we remove raw strings - # before removing comments as opposed to removing comments - # before removing raw strings. This is because there are some - # cpplint checks that requires the comments to be preserved, but - # we don't want to check comments that are inside raw strings. - matched = Match(r'^(.*?)\b(?:R|u8R|uR|UR|LR)"([^\s\\()]*)\((.*)$', line) - if (matched and - not Match(r'^([^\'"]|\'(\\.|[^\'])*\'|"(\\.|[^"])*")*//', - matched.group(1))): - delimiter = ')' + matched.group(2) + '"' - - end = matched.group(3).find(delimiter) - if end >= 0: - # Raw string ended on same line - line = (matched.group(1) + '""' + - matched.group(3)[end + len(delimiter):]) - delimiter = None - else: - # Start of a multi-line raw string - line = matched.group(1) + '""' - else: - break - - lines_without_raw_strings.append(line) - - # TODO(unknown): if delimiter is not None here, we might want to - # emit a warning for unterminated string. - return lines_without_raw_strings - - -def FindNextMultiLineCommentStart(lines, lineix): - """Find the beginning marker for a multiline comment.""" - while lineix < len(lines): - if lines[lineix].strip().startswith('/*'): - # Only return this marker if the comment goes beyond this line - if lines[lineix].strip().find('*/', 2) < 0: - return lineix - lineix += 1 - return len(lines) - - -def FindNextMultiLineCommentEnd(lines, lineix): - """We are inside a comment, find the end marker.""" - while lineix < len(lines): - if lines[lineix].strip().endswith('*/'): - return lineix - lineix += 1 - return len(lines) - - -def RemoveMultiLineCommentsFromRange(lines, begin, end): - """Clears a range of lines for multi-line comments.""" - # Having // comments makes the lines non-empty, so we will not get - # unnecessary blank line warnings later in the code. - for i in range(begin, end): - lines[i] = '/**/' - - -def RemoveMultiLineComments(filename, lines, error): - """Removes multiline (c-style) comments from lines.""" - lineix = 0 - while lineix < len(lines): - lineix_begin = FindNextMultiLineCommentStart(lines, lineix) - if lineix_begin >= len(lines): - return - lineix_end = FindNextMultiLineCommentEnd(lines, lineix_begin) - if lineix_end >= len(lines): - error(filename, lineix_begin + 1, 'readability/multiline_comment', 5, - 'Could not find end of multi-line comment') - return - RemoveMultiLineCommentsFromRange(lines, lineix_begin, lineix_end + 1) - lineix = lineix_end + 1 - - -def CleanseComments(line): - """Removes //-comments and single-line C-style /* */ comments. - - Args: - line: A line of C++ source. - - Returns: - The line with single-line comments removed. - """ - commentpos = line.find('//') - if commentpos != -1 and not IsCppString(line[:commentpos]): - line = line[:commentpos].rstrip() - # get rid of /* ... */ - return _RE_PATTERN_CLEANSE_LINE_C_COMMENTS.sub('', line) - - -class CleansedLines(object): - """Holds 4 copies of all lines with different preprocessing applied to them. - - 1) elided member contains lines without strings and comments. - 2) lines member contains lines without comments. - 3) raw_lines member contains all the lines without processing. - 4) lines_without_raw_strings member is same as raw_lines, but with C++11 raw - strings removed. - All these members are of , and of the same length. - """ - - def __init__(self, lines): - self.elided = [] - self.lines = [] - self.raw_lines = lines - self.num_lines = len(lines) - self.lines_without_raw_strings = CleanseRawStrings(lines) - for linenum in range(len(self.lines_without_raw_strings)): - self.lines.append(CleanseComments( - self.lines_without_raw_strings[linenum])) - elided = self._CollapseStrings(self.lines_without_raw_strings[linenum]) - self.elided.append(CleanseComments(elided)) - - def NumLines(self): - """Returns the number of lines represented.""" - return self.num_lines - - @staticmethod - def _CollapseStrings(elided): - """Collapses strings and chars on a line to simple "" or '' blocks. - - We nix strings first so we're not fooled by text like '"http://"' - - Args: - elided: The line being processed. - - Returns: - The line with collapsed strings. - """ - if _RE_PATTERN_INCLUDE.match(elided): - return elided - - # Remove escaped characters first to make quote/single quote collapsing - # basic. Things that look like escaped characters shouldn't occur - # outside of strings and chars. - elided = _RE_PATTERN_CLEANSE_LINE_ESCAPES.sub('', elided) - - # Replace quoted strings and digit separators. Both single quotes - # and double quotes are processed in the same loop, otherwise - # nested quotes wouldn't work. - collapsed = '' - while True: - # Find the first quote character - match = Match(r'^([^\'"]*)([\'"])(.*)$', elided) - if not match: - collapsed += elided - break - head, quote, tail = match.groups() - - if quote == '"': - # Collapse double quoted strings - second_quote = tail.find('"') - if second_quote >= 0: - collapsed += head + '""' - elided = tail[second_quote + 1:] - else: - # Unmatched double quote, don't bother processing the rest - # of the line since this is probably a multiline string. - collapsed += elided - break - else: - # Found single quote, check nearby text to eliminate digit separators. - # - # There is no special handling for floating point here, because - # the integer/fractional/exponent parts would all be parsed - # correctly as long as there are digits on both sides of the - # separator. So we are fine as long as we don't see something - # like "0.'3" (gcc 4.9.0 will not allow this literal). - if Search(r'\b(?:0[bBxX]?|[1-9])[0-9a-fA-F]*$', head): - match_literal = Match(r'^((?:\'?[0-9a-zA-Z_])*)(.*)$', "'" + tail) - collapsed += head + match_literal.group(1).replace("'", '') - elided = match_literal.group(2) - else: - second_quote = tail.find('\'') - if second_quote >= 0: - collapsed += head + "''" - elided = tail[second_quote + 1:] - else: - # Unmatched single quote - collapsed += elided - break - - return collapsed - - -def FindEndOfExpressionInLine(line, startpos, stack): - """Find the position just after the end of current parenthesized expression. - - Args: - line: a CleansedLines line. - startpos: start searching at this position. - stack: nesting stack at startpos. - - Returns: - On finding matching end: (index just after matching end, None) - On finding an unclosed expression: (-1, None) - Otherwise: (-1, new stack at end of this line) - """ - for i in xrange(startpos, len(line)): - char = line[i] - if char in '([{': - # Found start of parenthesized expression, push to expression stack - stack.append(char) - elif char == '<': - # Found potential start of template argument list - if i > 0 and line[i - 1] == '<': - # Left shift operator - if stack and stack[-1] == '<': - stack.pop() - if not stack: - return (-1, None) - elif i > 0 and Search(r'\boperator\s*$', line[0:i]): - # operator<, don't add to stack - continue - else: - # Tentative start of template argument list - stack.append('<') - elif char in ')]}': - # Found end of parenthesized expression. - # - # If we are currently expecting a matching '>', the pending '<' - # must have been an operator. Remove them from expression stack. - while stack and stack[-1] == '<': - stack.pop() - if not stack: - return (-1, None) - if ((stack[-1] == '(' and char == ')') or - (stack[-1] == '[' and char == ']') or - (stack[-1] == '{' and char == '}')): - stack.pop() - if not stack: - return (i + 1, None) - else: - # Mismatched parentheses - return (-1, None) - elif char == '>': - # Found potential end of template argument list. - - # Ignore "->" and operator functions - if (i > 0 and - (line[i - 1] == '-' or Search(r'\boperator\s*$', line[0:i - 1]))): - continue - - # Pop the stack if there is a matching '<'. Otherwise, ignore - # this '>' since it must be an operator. - if stack: - if stack[-1] == '<': - stack.pop() - if not stack: - return (i + 1, None) - elif char == ';': - # Found something that look like end of statements. If we are currently - # expecting a '>', the matching '<' must have been an operator, since - # template argument list should not contain statements. - while stack and stack[-1] == '<': - stack.pop() - if not stack: - return (-1, None) - - # Did not find end of expression or unbalanced parentheses on this line - return (-1, stack) - - -def CloseExpression(clean_lines, linenum, pos): - """If input points to ( or { or [ or <, finds the position that closes it. - - If lines[linenum][pos] points to a '(' or '{' or '[' or '<', finds the - linenum/pos that correspond to the closing of the expression. - - TODO(unknown): cpplint spends a fair bit of time matching parentheses. - Ideally we would want to index all opening and closing parentheses once - and have CloseExpression be just a simple lookup, but due to preprocessor - tricks, this is not so easy. - - Args: - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - pos: A position on the line. - - Returns: - A tuple (line, linenum, pos) pointer *past* the closing brace, or - (line, len(lines), -1) if we never find a close. Note we ignore - strings and comments when matching; and the line we return is the - 'cleansed' line at linenum. - """ - - line = clean_lines.elided[linenum] - if (line[pos] not in '({[<') or Match(r'<[<=]', line[pos:]): - return (line, clean_lines.NumLines(), -1) - - # Check first line - (end_pos, stack) = FindEndOfExpressionInLine(line, pos, []) - if end_pos > -1: - return (line, linenum, end_pos) - - # Continue scanning forward - while stack and linenum < clean_lines.NumLines() - 1: - linenum += 1 - line = clean_lines.elided[linenum] - (end_pos, stack) = FindEndOfExpressionInLine(line, 0, stack) - if end_pos > -1: - return (line, linenum, end_pos) - - # Did not find end of expression before end of file, give up - return (line, clean_lines.NumLines(), -1) - - -def FindStartOfExpressionInLine(line, endpos, stack): - """Find position at the matching start of current expression. - - This is almost the reverse of FindEndOfExpressionInLine, but note - that the input position and returned position differs by 1. - - Args: - line: a CleansedLines line. - endpos: start searching at this position. - stack: nesting stack at endpos. - - Returns: - On finding matching start: (index at matching start, None) - On finding an unclosed expression: (-1, None) - Otherwise: (-1, new stack at beginning of this line) - """ - i = endpos - while i >= 0: - char = line[i] - if char in ')]}': - # Found end of expression, push to expression stack - stack.append(char) - elif char == '>': - # Found potential end of template argument list. - # - # Ignore it if it's a "->" or ">=" or "operator>" - if (i > 0 and - (line[i - 1] == '-' or - Match(r'\s>=\s', line[i - 1:]) or - Search(r'\boperator\s*$', line[0:i]))): - i -= 1 - else: - stack.append('>') - elif char == '<': - # Found potential start of template argument list - if i > 0 and line[i - 1] == '<': - # Left shift operator - i -= 1 - else: - # If there is a matching '>', we can pop the expression stack. - # Otherwise, ignore this '<' since it must be an operator. - if stack and stack[-1] == '>': - stack.pop() - if not stack: - return (i, None) - elif char in '([{': - # Found start of expression. - # - # If there are any unmatched '>' on the stack, they must be - # operators. Remove those. - while stack and stack[-1] == '>': - stack.pop() - if not stack: - return (-1, None) - if ((char == '(' and stack[-1] == ')') or - (char == '[' and stack[-1] == ']') or - (char == '{' and stack[-1] == '}')): - stack.pop() - if not stack: - return (i, None) - else: - # Mismatched parentheses - return (-1, None) - elif char == ';': - # Found something that look like end of statements. If we are currently - # expecting a '<', the matching '>' must have been an operator, since - # template argument list should not contain statements. - while stack and stack[-1] == '>': - stack.pop() - if not stack: - return (-1, None) - - i -= 1 - - return (-1, stack) - - -def ReverseCloseExpression(clean_lines, linenum, pos): - """If input points to ) or } or ] or >, finds the position that opens it. - - If lines[linenum][pos] points to a ')' or '}' or ']' or '>', finds the - linenum/pos that correspond to the opening of the expression. - - Args: - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - pos: A position on the line. - - Returns: - A tuple (line, linenum, pos) pointer *at* the opening brace, or - (line, 0, -1) if we never find the matching opening brace. Note - we ignore strings and comments when matching; and the line we - return is the 'cleansed' line at linenum. - """ - line = clean_lines.elided[linenum] - if line[pos] not in ')}]>': - return (line, 0, -1) - - # Check last line - (start_pos, stack) = FindStartOfExpressionInLine(line, pos, []) - if start_pos > -1: - return (line, linenum, start_pos) - - # Continue scanning backward - while stack and linenum > 0: - linenum -= 1 - line = clean_lines.elided[linenum] - (start_pos, stack) = FindStartOfExpressionInLine(line, len(line) - 1, stack) - if start_pos > -1: - return (line, linenum, start_pos) - - # Did not find start of expression before beginning of file, give up - return (line, 0, -1) - - -def CheckForCopyright(filename, lines, error): - """Logs an error if no Copyright message appears at the top of the file.""" - - # We'll say it should occur by line 10. Don't forget there's a - # placeholder line at the front. - for line in xrange(1, min(len(lines), 11)): - if re.search(r'Copyright', lines[line], re.I): break - else: # means no copyright line was found - error(filename, 0, 'legal/copyright', 5, - 'No copyright message found. ' - 'You should have a line: "Copyright [year] "') - - -def GetIndentLevel(line): - """Return the number of leading spaces in line. - - Args: - line: A string to check. - - Returns: - An integer count of leading spaces, possibly zero. - """ - indent = Match(r'^( *)\S', line) - if indent: - return len(indent.group(1)) - else: - return 0 - -def PathSplitToList(path): - """Returns the path split into a list by the separator. - - Args: - path: An absolute or relative path (e.g. '/a/b/c/' or '../a') - - Returns: - A list of path components (e.g. ['a', 'b', 'c]). - """ - lst = [] - while True: - (head, tail) = os.path.split(path) - if head == path: # absolute paths end - lst.append(head) - break - if tail == path: # relative paths end - lst.append(tail) - break - - path = head - lst.append(tail) - - lst.reverse() - return lst - -def GetHeaderGuardCPPVariable(filename): - """Returns the CPP variable that should be used as a header guard. - - Args: - filename: The name of a C++ header file. - - Returns: - The CPP variable that should be used as a header guard in the - named file. - - """ - - # Restores original filename in case that cpplint is invoked from Emacs's - # flymake. - filename = re.sub(r'_flymake\.h$', '.h', filename) - filename = re.sub(r'/\.flymake/([^/]*)$', r'/\1', filename) - # Replace 'c++' with 'cpp'. - filename = filename.replace('C++', 'cpp').replace('c++', 'cpp') - - fileinfo = FileInfo(filename) - file_path_from_root = fileinfo.RepositoryName() - - def FixupPathFromRoot(): - if _root_debug: - sys.stderr.write("\n_root fixup, _root = '%s', repository name = '%s'\n" - % (_root, fileinfo.RepositoryName())) - - # Process the file path with the --root flag if it was set. - if not _root: - if _root_debug: - sys.stderr.write("_root unspecified\n") - return file_path_from_root - - def StripListPrefix(lst, prefix): - # f(['x', 'y'], ['w, z']) -> None (not a valid prefix) - if lst[:len(prefix)] != prefix: - return None - # f(['a, 'b', 'c', 'd'], ['a', 'b']) -> ['c', 'd'] - return lst[(len(prefix)):] - - # root behavior: - # --root=subdir , lstrips subdir from the header guard - maybe_path = StripListPrefix(PathSplitToList(file_path_from_root), - PathSplitToList(_root)) - - if _root_debug: - sys.stderr.write(("_root lstrip (maybe_path=%s, file_path_from_root=%s," + - " _root=%s)\n") % (maybe_path, file_path_from_root, _root)) - - if maybe_path: - return os.path.join(*maybe_path) - - # --root=.. , will prepend the outer directory to the header guard - full_path = fileinfo.FullName() - # adapt slashes for windows - root_abspath = os.path.abspath(_root).replace('\\', '/') - - maybe_path = StripListPrefix(PathSplitToList(full_path), - PathSplitToList(root_abspath)) - - if _root_debug: - sys.stderr.write(("_root prepend (maybe_path=%s, full_path=%s, " + - "root_abspath=%s)\n") % (maybe_path, full_path, root_abspath)) - - if maybe_path: - return os.path.join(*maybe_path) - - if _root_debug: - sys.stderr.write("_root ignore, returning %s\n" % (file_path_from_root)) - - # --root=FAKE_DIR is ignored - return file_path_from_root - - file_path_from_root = FixupPathFromRoot() - return re.sub(r'[^a-zA-Z0-9]', '_', file_path_from_root).upper() + '_' - - -def CheckForHeaderGuard(filename, clean_lines, error): - """Checks that the file contains a header guard. - - Logs an error if no #ifndef header guard is present. For other - headers, checks that the full pathname is used. - - Args: - filename: The name of the C++ header file. - clean_lines: A CleansedLines instance containing the file. - error: The function to call with any errors found. - """ - - # Don't check for header guards if there are error suppression - # comments somewhere in this file. - # - # Because this is silencing a warning for a nonexistent line, we - # only support the very specific NOLINT(build/header_guard) syntax, - # and not the general NOLINT or NOLINT(*) syntax. - raw_lines = clean_lines.lines_without_raw_strings - for i in raw_lines: - if Search(r'//\s*NOLINT\(build/header_guard\)', i): - return - - # Allow pragma once instead of header guards - for i in raw_lines: - if Search(r'^\s*#pragma\s+once', i): - return - - cppvar = GetHeaderGuardCPPVariable(filename) - - ifndef = '' - ifndef_linenum = 0 - define = '' - endif = '' - endif_linenum = 0 - for linenum, line in enumerate(raw_lines): - linesplit = line.split() - if len(linesplit) >= 2: - # find the first occurrence of #ifndef and #define, save arg - if not ifndef and linesplit[0] == '#ifndef': - # set ifndef to the header guard presented on the #ifndef line. - ifndef = linesplit[1] - ifndef_linenum = linenum - if not define and linesplit[0] == '#define': - define = linesplit[1] - # find the last occurrence of #endif, save entire line - if line.startswith('#endif'): - endif = line - endif_linenum = linenum - - if not ifndef or not define or ifndef != define: - error(filename, 0, 'build/header_guard', 5, - 'No #ifndef header guard found, suggested CPP variable is: %s' % - cppvar) - return - - # The guard should be PATH_FILE_H_, but we also allow PATH_FILE_H__ - # for backward compatibility. - if ifndef != cppvar: - error_level = 0 - if ifndef != cppvar + '_': - error_level = 5 - - ParseNolintSuppressions(filename, raw_lines[ifndef_linenum], ifndef_linenum, - error) - error(filename, ifndef_linenum, 'build/header_guard', error_level, - '#ifndef header guard has wrong style, please use: %s' % cppvar) - - # Check for "//" comments on endif line. - ParseNolintSuppressions(filename, raw_lines[endif_linenum], endif_linenum, - error) - match = Match(r'#endif\s*//\s*' + cppvar + r'(_)?\b', endif) - if match: - if match.group(1) == '_': - # Issue low severity warning for deprecated double trailing underscore - error(filename, endif_linenum, 'build/header_guard', 0, - '#endif line should be "#endif // %s"' % cppvar) - return - - # Didn't find the corresponding "//" comment. If this file does not - # contain any "//" comments at all, it could be that the compiler - # only wants "/**/" comments, look for those instead. - no_single_line_comments = True - for i in xrange(1, len(raw_lines) - 1): - line = raw_lines[i] - if Match(r'^(?:(?:\'(?:\.|[^\'])*\')|(?:"(?:\.|[^"])*")|[^\'"])*//', line): - no_single_line_comments = False - break - - if no_single_line_comments: - match = Match(r'#endif\s*/\*\s*' + cppvar + r'(_)?\s*\*/', endif) - if match: - if match.group(1) == '_': - # Low severity warning for double trailing underscore - error(filename, endif_linenum, 'build/header_guard', 0, - '#endif line should be "#endif /* %s */"' % cppvar) - return - - # Didn't find anything - error(filename, endif_linenum, 'build/header_guard', 5, - '#endif line should be "#endif // %s"' % cppvar) - - -def CheckHeaderFileIncluded(filename, include_state, error): - """Logs an error if a source file does not include its header.""" - - # Do not check test files - fileinfo = FileInfo(filename) - if Search(_TEST_FILE_SUFFIX, fileinfo.BaseName()): - return - - for ext in GetHeaderExtensions(): - basefilename = filename[0:len(filename) - len(fileinfo.Extension())] - headerfile = basefilename + '.' + ext - if not os.path.exists(headerfile): - continue - headername = FileInfo(headerfile).RepositoryName() - first_include = None - include_uses_unix_dir_aliases = False - for section_list in include_state.include_list: - for f in section_list: - include_text = f[0] - if "./" in include_text: - include_uses_unix_dir_aliases = True - if headername in include_text or include_text in headername: - return - if not first_include: - first_include = f[1] - - message = '%s should include its header file %s' % (fileinfo.RepositoryName(), headername) - if include_uses_unix_dir_aliases: - message += ". Relative paths like . and .. are not allowed." - - error(filename, first_include, 'build/include', 5, message) - - -def CheckForBadCharacters(filename, lines, error): - """Logs an error for each line containing bad characters. - - Two kinds of bad characters: - - 1. Unicode replacement characters: These indicate that either the file - contained invalid UTF-8 (likely) or Unicode replacement characters (which - it shouldn't). Note that it's possible for this to throw off line - numbering if the invalid UTF-8 occurred adjacent to a newline. - - 2. NUL bytes. These are problematic for some tools. - - Args: - filename: The name of the current file. - lines: An array of strings, each representing a line of the file. - error: The function to call with any errors found. - """ - for linenum, line in enumerate(lines): - if unicode_escape_decode('\ufffd') in line: - error(filename, linenum, 'readability/utf8', 5, - 'Line contains invalid UTF-8 (or Unicode replacement character).') - if '\0' in line: - error(filename, linenum, 'readability/nul', 5, 'Line contains NUL byte.') - - -def CheckForNewlineAtEOF(filename, lines, error): - """Logs an error if there is no newline char at the end of the file. - - Args: - filename: The name of the current file. - lines: An array of strings, each representing a line of the file. - error: The function to call with any errors found. - """ - - # The array lines() was created by adding two newlines to the - # original file (go figure), then splitting on \n. - # To verify that the file ends in \n, we just have to make sure the - # last-but-two element of lines() exists and is empty. - if len(lines) < 3 or lines[-2]: - error(filename, len(lines) - 2, 'whitespace/ending_newline', 5, - 'Could not find a newline character at the end of the file.') - - -def CheckForMultilineCommentsAndStrings(filename, clean_lines, linenum, error): - """Logs an error if we see /* ... */ or "..." that extend past one line. - - /* ... */ comments are legit inside macros, for one line. - Otherwise, we prefer // comments, so it's ok to warn about the - other. Likewise, it's ok for strings to extend across multiple - lines, as long as a line continuation character (backslash) - terminates each line. Although not currently prohibited by the C++ - style guide, it's ugly and unnecessary. We don't do well with either - in this lint program, so we warn about both. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # Remove all \\ (escaped backslashes) from the line. They are OK, and the - # second (escaped) slash may trigger later \" detection erroneously. - line = line.replace('\\\\', '') - - if line.count('/*') > line.count('*/'): - error(filename, linenum, 'readability/multiline_comment', 5, - 'Complex multi-line /*...*/-style comment found. ' - 'Lint may give bogus warnings. ' - 'Consider replacing these with //-style comments, ' - 'with #if 0...#endif, ' - 'or with more clearly structured multi-line comments.') - - if (line.count('"') - line.count('\\"')) % 2: - error(filename, linenum, 'readability/multiline_string', 5, - 'Multi-line string ("...") found. This lint script doesn\'t ' - 'do well with such strings, and may give bogus warnings. ' - 'Use C++11 raw strings or concatenation instead.') - - -# (non-threadsafe name, thread-safe alternative, validation pattern) -# -# The validation pattern is used to eliminate false positives such as: -# _rand(); // false positive due to substring match. -# ->rand(); // some member function rand(). -# ACMRandom rand(seed); // some variable named rand. -# ISAACRandom rand(); // another variable named rand. -# -# Basically we require the return value of these functions to be used -# in some expression context on the same line by matching on some -# operator before the function name. This eliminates constructors and -# member function calls. -_UNSAFE_FUNC_PREFIX = r'(?:[-+*/=%^&|(<]\s*|>\s+)' -_THREADING_LIST = ( - ('asctime(', 'asctime_r(', _UNSAFE_FUNC_PREFIX + r'asctime\([^)]+\)'), - ('ctime(', 'ctime_r(', _UNSAFE_FUNC_PREFIX + r'ctime\([^)]+\)'), - ('getgrgid(', 'getgrgid_r(', _UNSAFE_FUNC_PREFIX + r'getgrgid\([^)]+\)'), - ('getgrnam(', 'getgrnam_r(', _UNSAFE_FUNC_PREFIX + r'getgrnam\([^)]+\)'), - ('getlogin(', 'getlogin_r(', _UNSAFE_FUNC_PREFIX + r'getlogin\(\)'), - ('getpwnam(', 'getpwnam_r(', _UNSAFE_FUNC_PREFIX + r'getpwnam\([^)]+\)'), - ('getpwuid(', 'getpwuid_r(', _UNSAFE_FUNC_PREFIX + r'getpwuid\([^)]+\)'), - ('gmtime(', 'gmtime_r(', _UNSAFE_FUNC_PREFIX + r'gmtime\([^)]+\)'), - ('localtime(', 'localtime_r(', _UNSAFE_FUNC_PREFIX + r'localtime\([^)]+\)'), - ('rand(', 'rand_r(', _UNSAFE_FUNC_PREFIX + r'rand\(\)'), - ('strtok(', 'strtok_r(', - _UNSAFE_FUNC_PREFIX + r'strtok\([^)]+\)'), - ('ttyname(', 'ttyname_r(', _UNSAFE_FUNC_PREFIX + r'ttyname\([^)]+\)'), - ) - - -def CheckPosixThreading(filename, clean_lines, linenum, error): - """Checks for calls to thread-unsafe functions. - - Much code has been originally written without consideration of - multi-threading. Also, engineers are relying on their old experience; - they have learned posix before threading extensions were added. These - tests guide the engineers to use thread-safe functions (when using - posix directly). - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - for single_thread_func, multithread_safe_func, pattern in _THREADING_LIST: - # Additional pattern matching check to confirm that this is the - # function we are looking for - if Search(pattern, line): - error(filename, linenum, 'runtime/threadsafe_fn', 2, - 'Consider using ' + multithread_safe_func + - '...) instead of ' + single_thread_func + - '...) for improved thread safety.') - - -def CheckVlogArguments(filename, clean_lines, linenum, error): - """Checks that VLOG() is only used for defining a logging level. - - For example, VLOG(2) is correct. VLOG(INFO), VLOG(WARNING), VLOG(ERROR), and - VLOG(FATAL) are not. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - if Search(r'\bVLOG\((INFO|ERROR|WARNING|DFATAL|FATAL)\)', line): - error(filename, linenum, 'runtime/vlog', 5, - 'VLOG() should be used with numeric verbosity level. ' - 'Use LOG() if you want symbolic severity levels.') - -# Matches invalid increment: *count++, which moves pointer instead of -# incrementing a value. -_RE_PATTERN_INVALID_INCREMENT = re.compile( - r'^\s*\*\w+(\+\+|--);') - - -def CheckInvalidIncrement(filename, clean_lines, linenum, error): - """Checks for invalid increment *count++. - - For example following function: - void increment_counter(int* count) { - *count++; - } - is invalid, because it effectively does count++, moving pointer, and should - be replaced with ++*count, (*count)++ or *count += 1. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - if _RE_PATTERN_INVALID_INCREMENT.match(line): - error(filename, linenum, 'runtime/invalid_increment', 5, - 'Changing pointer instead of value (or unused value of operator*).') - - -def IsMacroDefinition(clean_lines, linenum): - if Search(r'^#define', clean_lines[linenum]): - return True - - if linenum > 0 and Search(r'\\$', clean_lines[linenum - 1]): - return True - - return False - - -def IsForwardClassDeclaration(clean_lines, linenum): - return Match(r'^\s*(\btemplate\b)*.*class\s+\w+;\s*$', clean_lines[linenum]) - - -class _BlockInfo(object): - """Stores information about a generic block of code.""" - - def __init__(self, linenum, seen_open_brace): - self.starting_linenum = linenum - self.seen_open_brace = seen_open_brace - self.open_parentheses = 0 - self.inline_asm = _NO_ASM - self.check_namespace_indentation = False - - def CheckBegin(self, filename, clean_lines, linenum, error): - """Run checks that applies to text up to the opening brace. - - This is mostly for checking the text after the class identifier - and the "{", usually where the base class is specified. For other - blocks, there isn't much to check, so we always pass. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - pass - - def CheckEnd(self, filename, clean_lines, linenum, error): - """Run checks that applies to text after the closing brace. - - This is mostly used for checking end of namespace comments. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - pass - - def IsBlockInfo(self): - """Returns true if this block is a _BlockInfo. - - This is convenient for verifying that an object is an instance of - a _BlockInfo, but not an instance of any of the derived classes. - - Returns: - True for this class, False for derived classes. - """ - return self.__class__ == _BlockInfo - - -class _ExternCInfo(_BlockInfo): - """Stores information about an 'extern "C"' block.""" - - def __init__(self, linenum): - _BlockInfo.__init__(self, linenum, True) - - -class _ClassInfo(_BlockInfo): - """Stores information about a class.""" - - def __init__(self, name, class_or_struct, clean_lines, linenum): - _BlockInfo.__init__(self, linenum, False) - self.name = name - self.is_derived = False - self.check_namespace_indentation = True - if class_or_struct == 'struct': - self.access = 'public' - self.is_struct = True - else: - self.access = 'private' - self.is_struct = False - - # Remember initial indentation level for this class. Using raw_lines here - # instead of elided to account for leading comments. - self.class_indent = GetIndentLevel(clean_lines.raw_lines[linenum]) - - # Try to find the end of the class. This will be confused by things like: - # class A { - # } *x = { ... - # - # But it's still good enough for CheckSectionSpacing. - self.last_line = 0 - depth = 0 - for i in range(linenum, clean_lines.NumLines()): - line = clean_lines.elided[i] - depth += line.count('{') - line.count('}') - if not depth: - self.last_line = i - break - - def CheckBegin(self, filename, clean_lines, linenum, error): - # Look for a bare ':' - if Search('(^|[^:]):($|[^:])', clean_lines.elided[linenum]): - self.is_derived = True - - def CheckEnd(self, filename, clean_lines, linenum, error): - # If there is a DISALLOW macro, it should appear near the end of - # the class. - seen_last_thing_in_class = False - for i in xrange(linenum - 1, self.starting_linenum, -1): - match = Search( - r'\b(DISALLOW_COPY_AND_ASSIGN|DISALLOW_IMPLICIT_CONSTRUCTORS)\(' + - self.name + r'\)', - clean_lines.elided[i]) - if match: - if seen_last_thing_in_class: - error(filename, i, 'readability/constructors', 3, - match.group(1) + ' should be the last thing in the class') - break - - if not Match(r'^\s*$', clean_lines.elided[i]): - seen_last_thing_in_class = True - - # Check that closing brace is aligned with beginning of the class. - # Only do this if the closing brace is indented by only whitespaces. - # This means we will not check single-line class definitions. - indent = Match(r'^( *)\}', clean_lines.elided[linenum]) - if indent and len(indent.group(1)) != self.class_indent: - if self.is_struct: - parent = 'struct ' + self.name - else: - parent = 'class ' + self.name - error(filename, linenum, 'whitespace/indent', 3, - 'Closing brace should be aligned with beginning of %s' % parent) - - -class _NamespaceInfo(_BlockInfo): - """Stores information about a namespace.""" - - def __init__(self, name, linenum): - _BlockInfo.__init__(self, linenum, False) - self.name = name or '' - self.check_namespace_indentation = True - - def CheckEnd(self, filename, clean_lines, linenum, error): - """Check end of namespace comments.""" - line = clean_lines.raw_lines[linenum] - - # Check how many lines is enclosed in this namespace. Don't issue - # warning for missing namespace comments if there aren't enough - # lines. However, do apply checks if there is already an end of - # namespace comment and it's incorrect. - # - # TODO(unknown): We always want to check end of namespace comments - # if a namespace is large, but sometimes we also want to apply the - # check if a short namespace contained nontrivial things (something - # other than forward declarations). There is currently no logic on - # deciding what these nontrivial things are, so this check is - # triggered by namespace size only, which works most of the time. - if (linenum - self.starting_linenum < 10 - and not Match(r'^\s*};*\s*(//|/\*).*\bnamespace\b', line)): - return - - # Look for matching comment at end of namespace. - # - # Note that we accept C style "/* */" comments for terminating - # namespaces, so that code that terminate namespaces inside - # preprocessor macros can be cpplint clean. - # - # We also accept stuff like "// end of namespace ." with the - # period at the end. - # - # Besides these, we don't accept anything else, otherwise we might - # get false negatives when existing comment is a substring of the - # expected namespace. - if self.name: - # Named namespace - if not Match((r'^\s*};*\s*(//|/\*).*\bnamespace\s+' + - re.escape(self.name) + r'[\*/\.\\\s]*$'), - line): - error(filename, linenum, 'readability/namespace', 5, - 'Namespace should be terminated with "// namespace %s"' % - self.name) - else: - # Anonymous namespace - if not Match(r'^\s*};*\s*(//|/\*).*\bnamespace[\*/\.\\\s]*$', line): - # If "// namespace anonymous" or "// anonymous namespace (more text)", - # mention "// anonymous namespace" as an acceptable form - if Match(r'^\s*}.*\b(namespace anonymous|anonymous namespace)\b', line): - error(filename, linenum, 'readability/namespace', 5, - 'Anonymous namespace should be terminated with "// namespace"' - ' or "// anonymous namespace"') - else: - error(filename, linenum, 'readability/namespace', 5, - 'Anonymous namespace should be terminated with "// namespace"') - - -class _PreprocessorInfo(object): - """Stores checkpoints of nesting stacks when #if/#else is seen.""" - - def __init__(self, stack_before_if): - # The entire nesting stack before #if - self.stack_before_if = stack_before_if - - # The entire nesting stack up to #else - self.stack_before_else = [] - - # Whether we have already seen #else or #elif - self.seen_else = False - - -class NestingState(object): - """Holds states related to parsing braces.""" - - def __init__(self): - # Stack for tracking all braces. An object is pushed whenever we - # see a "{", and popped when we see a "}". Only 3 types of - # objects are possible: - # - _ClassInfo: a class or struct. - # - _NamespaceInfo: a namespace. - # - _BlockInfo: some other type of block. - self.stack = [] - - # Top of the previous stack before each Update(). - # - # Because the nesting_stack is updated at the end of each line, we - # had to do some convoluted checks to find out what is the current - # scope at the beginning of the line. This check is simplified by - # saving the previous top of nesting stack. - # - # We could save the full stack, but we only need the top. Copying - # the full nesting stack would slow down cpplint by ~10%. - self.previous_stack_top = [] - - # Stack of _PreprocessorInfo objects. - self.pp_stack = [] - - def SeenOpenBrace(self): - """Check if we have seen the opening brace for the innermost block. - - Returns: - True if we have seen the opening brace, False if the innermost - block is still expecting an opening brace. - """ - return (not self.stack) or self.stack[-1].seen_open_brace - - def InNamespaceBody(self): - """Check if we are currently one level inside a namespace body. - - Returns: - True if top of the stack is a namespace block, False otherwise. - """ - return self.stack and isinstance(self.stack[-1], _NamespaceInfo) - - def InExternC(self): - """Check if we are currently one level inside an 'extern "C"' block. - - Returns: - True if top of the stack is an extern block, False otherwise. - """ - return self.stack and isinstance(self.stack[-1], _ExternCInfo) - - def InClassDeclaration(self): - """Check if we are currently one level inside a class or struct declaration. - - Returns: - True if top of the stack is a class/struct, False otherwise. - """ - return self.stack and isinstance(self.stack[-1], _ClassInfo) - - def InAsmBlock(self): - """Check if we are currently one level inside an inline ASM block. - - Returns: - True if the top of the stack is a block containing inline ASM. - """ - return self.stack and self.stack[-1].inline_asm != _NO_ASM - - def InTemplateArgumentList(self, clean_lines, linenum, pos): - """Check if current position is inside template argument list. - - Args: - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - pos: position just after the suspected template argument. - Returns: - True if (linenum, pos) is inside template arguments. - """ - while linenum < clean_lines.NumLines(): - # Find the earliest character that might indicate a template argument - line = clean_lines.elided[linenum] - match = Match(r'^[^{};=\[\]\.<>]*(.)', line[pos:]) - if not match: - linenum += 1 - pos = 0 - continue - token = match.group(1) - pos += len(match.group(0)) - - # These things do not look like template argument list: - # class Suspect { - # class Suspect x; } - if token in ('{', '}', ';'): return False - - # These things look like template argument list: - # template - # template - # template - # template - if token in ('>', '=', '[', ']', '.'): return True - - # Check if token is an unmatched '<'. - # If not, move on to the next character. - if token != '<': - pos += 1 - if pos >= len(line): - linenum += 1 - pos = 0 - continue - - # We can't be sure if we just find a single '<', and need to - # find the matching '>'. - (_, end_line, end_pos) = CloseExpression(clean_lines, linenum, pos - 1) - if end_pos < 0: - # Not sure if template argument list or syntax error in file - return False - linenum = end_line - pos = end_pos - return False - - def UpdatePreprocessor(self, line): - """Update preprocessor stack. - - We need to handle preprocessors due to classes like this: - #ifdef SWIG - struct ResultDetailsPageElementExtensionPoint { - #else - struct ResultDetailsPageElementExtensionPoint : public Extension { - #endif - - We make the following assumptions (good enough for most files): - - Preprocessor condition evaluates to true from #if up to first - #else/#elif/#endif. - - - Preprocessor condition evaluates to false from #else/#elif up - to #endif. We still perform lint checks on these lines, but - these do not affect nesting stack. - - Args: - line: current line to check. - """ - if Match(r'^\s*#\s*(if|ifdef|ifndef)\b', line): - # Beginning of #if block, save the nesting stack here. The saved - # stack will allow us to restore the parsing state in the #else case. - self.pp_stack.append(_PreprocessorInfo(copy.deepcopy(self.stack))) - elif Match(r'^\s*#\s*(else|elif)\b', line): - # Beginning of #else block - if self.pp_stack: - if not self.pp_stack[-1].seen_else: - # This is the first #else or #elif block. Remember the - # whole nesting stack up to this point. This is what we - # keep after the #endif. - self.pp_stack[-1].seen_else = True - self.pp_stack[-1].stack_before_else = copy.deepcopy(self.stack) - - # Restore the stack to how it was before the #if - self.stack = copy.deepcopy(self.pp_stack[-1].stack_before_if) - else: - # TODO(unknown): unexpected #else, issue warning? - pass - elif Match(r'^\s*#\s*endif\b', line): - # End of #if or #else blocks. - if self.pp_stack: - # If we saw an #else, we will need to restore the nesting - # stack to its former state before the #else, otherwise we - # will just continue from where we left off. - if self.pp_stack[-1].seen_else: - # Here we can just use a shallow copy since we are the last - # reference to it. - self.stack = self.pp_stack[-1].stack_before_else - # Drop the corresponding #if - self.pp_stack.pop() - else: - # TODO(unknown): unexpected #endif, issue warning? - pass - - # TODO(unknown): Update() is too long, but we will refactor later. - def Update(self, filename, clean_lines, linenum, error): - """Update nesting state with current line. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # Remember top of the previous nesting stack. - # - # The stack is always pushed/popped and not modified in place, so - # we can just do a shallow copy instead of copy.deepcopy. Using - # deepcopy would slow down cpplint by ~28%. - if self.stack: - self.previous_stack_top = self.stack[-1] - else: - self.previous_stack_top = None - - # Update pp_stack - self.UpdatePreprocessor(line) - - # Count parentheses. This is to avoid adding struct arguments to - # the nesting stack. - if self.stack: - inner_block = self.stack[-1] - depth_change = line.count('(') - line.count(')') - inner_block.open_parentheses += depth_change - - # Also check if we are starting or ending an inline assembly block. - if inner_block.inline_asm in (_NO_ASM, _END_ASM): - if (depth_change != 0 and - inner_block.open_parentheses == 1 and - _MATCH_ASM.match(line)): - # Enter assembly block - inner_block.inline_asm = _INSIDE_ASM - else: - # Not entering assembly block. If previous line was _END_ASM, - # we will now shift to _NO_ASM state. - inner_block.inline_asm = _NO_ASM - elif (inner_block.inline_asm == _INSIDE_ASM and - inner_block.open_parentheses == 0): - # Exit assembly block - inner_block.inline_asm = _END_ASM - - # Consume namespace declaration at the beginning of the line. Do - # this in a loop so that we catch same line declarations like this: - # namespace proto2 { namespace bridge { class MessageSet; } } - while True: - # Match start of namespace. The "\b\s*" below catches namespace - # declarations even if it weren't followed by a whitespace, this - # is so that we don't confuse our namespace checker. The - # missing spaces will be flagged by CheckSpacing. - namespace_decl_match = Match(r'^\s*namespace\b\s*([:\w]+)?(.*)$', line) - if not namespace_decl_match: - break - - new_namespace = _NamespaceInfo(namespace_decl_match.group(1), linenum) - self.stack.append(new_namespace) - - line = namespace_decl_match.group(2) - if line.find('{') != -1: - new_namespace.seen_open_brace = True - line = line[line.find('{') + 1:] - - # Look for a class declaration in whatever is left of the line - # after parsing namespaces. The regexp accounts for decorated classes - # such as in: - # class LOCKABLE API Object { - # }; - class_decl_match = Match( - r'^(\s*(?:template\s*<[\w\s<>,:=]*>\s*)?' - r'(class|struct)\s+(?:[a-zA-Z0-9_]+\s+)*(\w+(?:::\w+)*))' - r'(.*)$', line) - if (class_decl_match and - (not self.stack or self.stack[-1].open_parentheses == 0)): - # We do not want to accept classes that are actually template arguments: - # template , - # template class Ignore3> - # void Function() {}; - # - # To avoid template argument cases, we scan forward and look for - # an unmatched '>'. If we see one, assume we are inside a - # template argument list. - end_declaration = len(class_decl_match.group(1)) - if not self.InTemplateArgumentList(clean_lines, linenum, end_declaration): - self.stack.append(_ClassInfo( - class_decl_match.group(3), class_decl_match.group(2), - clean_lines, linenum)) - line = class_decl_match.group(4) - - # If we have not yet seen the opening brace for the innermost block, - # run checks here. - if not self.SeenOpenBrace(): - self.stack[-1].CheckBegin(filename, clean_lines, linenum, error) - - # Update access control if we are inside a class/struct - if self.stack and isinstance(self.stack[-1], _ClassInfo): - classinfo = self.stack[-1] - access_match = Match( - r'^(.*)\b(public|private|protected|signals)(\s+(?:slots\s*)?)?' - r':(?:[^:]|$)', - line) - if access_match: - classinfo.access = access_match.group(2) - - # Check that access keywords are indented +1 space. Skip this - # check if the keywords are not preceded by whitespaces. - indent = access_match.group(1) - if (len(indent) != classinfo.class_indent + 1 and - Match(r'^\s*$', indent)): - if classinfo.is_struct: - parent = 'struct ' + classinfo.name - else: - parent = 'class ' + classinfo.name - slots = '' - if access_match.group(3): - slots = access_match.group(3) - error(filename, linenum, 'whitespace/indent', 3, - '%s%s: should be indented +1 space inside %s' % ( - access_match.group(2), slots, parent)) - - # Consume braces or semicolons from what's left of the line - while True: - # Match first brace, semicolon, or closed parenthesis. - matched = Match(r'^[^{;)}]*([{;)}])(.*)$', line) - if not matched: - break - - token = matched.group(1) - if token == '{': - # If namespace or class hasn't seen a opening brace yet, mark - # namespace/class head as complete. Push a new block onto the - # stack otherwise. - if not self.SeenOpenBrace(): - self.stack[-1].seen_open_brace = True - elif Match(r'^extern\s*"[^"]*"\s*\{', line): - self.stack.append(_ExternCInfo(linenum)) - else: - self.stack.append(_BlockInfo(linenum, True)) - if _MATCH_ASM.match(line): - self.stack[-1].inline_asm = _BLOCK_ASM - - elif token == ';' or token == ')': - # If we haven't seen an opening brace yet, but we already saw - # a semicolon, this is probably a forward declaration. Pop - # the stack for these. - # - # Similarly, if we haven't seen an opening brace yet, but we - # already saw a closing parenthesis, then these are probably - # function arguments with extra "class" or "struct" keywords. - # Also pop these stack for these. - if not self.SeenOpenBrace(): - self.stack.pop() - else: # token == '}' - # Perform end of block checks and pop the stack. - if self.stack: - self.stack[-1].CheckEnd(filename, clean_lines, linenum, error) - self.stack.pop() - line = matched.group(2) - - def InnermostClass(self): - """Get class info on the top of the stack. - - Returns: - A _ClassInfo object if we are inside a class, or None otherwise. - """ - for i in range(len(self.stack), 0, -1): - classinfo = self.stack[i - 1] - if isinstance(classinfo, _ClassInfo): - return classinfo - return None - - def CheckCompletedBlocks(self, filename, error): - """Checks that all classes and namespaces have been completely parsed. - - Call this when all lines in a file have been processed. - Args: - filename: The name of the current file. - error: The function to call with any errors found. - """ - # Note: This test can result in false positives if #ifdef constructs - # get in the way of brace matching. See the testBuildClass test in - # cpplint_unittest.py for an example of this. - for obj in self.stack: - if isinstance(obj, _ClassInfo): - error(filename, obj.starting_linenum, 'build/class', 5, - 'Failed to find complete declaration of class %s' % - obj.name) - elif isinstance(obj, _NamespaceInfo): - error(filename, obj.starting_linenum, 'build/namespaces', 5, - 'Failed to find complete declaration of namespace %s' % - obj.name) - - -def CheckForNonStandardConstructs(filename, clean_lines, linenum, - nesting_state, error): - r"""Logs an error if we see certain non-ANSI constructs ignored by gcc-2. - - Complain about several constructs which gcc-2 accepts, but which are - not standard C++. Warning about these in lint is one way to ease the - transition to new compilers. - - put storage class first (e.g. "static const" instead of "const static"). - - "%lld" instead of %qd" in printf-type functions. - - "%1$d" is non-standard in printf-type functions. - - "\%" is an undefined character escape sequence. - - text after #endif is not allowed. - - invalid inner-style forward declaration. - - >? and ?= and )\?=?\s*(\w+|[+-]?\d+)(\.\d*)?', - line): - error(filename, linenum, 'build/deprecated', 3, - '>? and ))?' - # r'\s*const\s*' + type_name + '\s*&\s*\w+\s*;' - error(filename, linenum, 'runtime/member_string_references', 2, - 'const string& members are dangerous. It is much better to use ' - 'alternatives, such as pointers or simple constants.') - - # Everything else in this function operates on class declarations. - # Return early if the top of the nesting stack is not a class, or if - # the class head is not completed yet. - classinfo = nesting_state.InnermostClass() - if not classinfo or not classinfo.seen_open_brace: - return - - # The class may have been declared with namespace or classname qualifiers. - # The constructor and destructor will not have those qualifiers. - base_classname = classinfo.name.split('::')[-1] - - # Look for single-argument constructors that aren't marked explicit. - # Technically a valid construct, but against style. - explicit_constructor_match = Match( - r'\s+(?:(?:inline|constexpr)\s+)*(explicit\s+)?' - r'(?:(?:inline|constexpr)\s+)*%s\s*' - r'\(((?:[^()]|\([^()]*\))*)\)' - % re.escape(base_classname), - line) - - if explicit_constructor_match: - is_marked_explicit = explicit_constructor_match.group(1) - - if not explicit_constructor_match.group(2): - constructor_args = [] - else: - constructor_args = explicit_constructor_match.group(2).split(',') - - # collapse arguments so that commas in template parameter lists and function - # argument parameter lists don't split arguments in two - i = 0 - while i < len(constructor_args): - constructor_arg = constructor_args[i] - while (constructor_arg.count('<') > constructor_arg.count('>') or - constructor_arg.count('(') > constructor_arg.count(')')): - constructor_arg += ',' + constructor_args[i + 1] - del constructor_args[i + 1] - constructor_args[i] = constructor_arg - i += 1 - - variadic_args = [arg for arg in constructor_args if '&&...' in arg] - defaulted_args = [arg for arg in constructor_args if '=' in arg] - noarg_constructor = (not constructor_args or # empty arg list - # 'void' arg specifier - (len(constructor_args) == 1 and - constructor_args[0].strip() == 'void')) - onearg_constructor = ((len(constructor_args) == 1 and # exactly one arg - not noarg_constructor) or - # all but at most one arg defaulted - (len(constructor_args) >= 1 and - not noarg_constructor and - len(defaulted_args) >= len(constructor_args) - 1) or - # variadic arguments with zero or one argument - (len(constructor_args) <= 2 and - len(variadic_args) >= 1)) - initializer_list_constructor = bool( - onearg_constructor and - Search(r'\bstd\s*::\s*initializer_list\b', constructor_args[0])) - copy_constructor = bool( - onearg_constructor and - Match(r'((const\s+(volatile\s+)?)?|(volatile\s+(const\s+)?))?' - r'%s(\s*<[^>]*>)?(\s+const)?\s*(?:<\w+>\s*)?&' - % re.escape(base_classname), constructor_args[0].strip())) - - if (not is_marked_explicit and - onearg_constructor and - not initializer_list_constructor and - not copy_constructor): - if defaulted_args or variadic_args: - error(filename, linenum, 'runtime/explicit', 5, - 'Constructors callable with one argument ' - 'should be marked explicit.') - else: - error(filename, linenum, 'runtime/explicit', 5, - 'Single-parameter constructors should be marked explicit.') - elif is_marked_explicit and not onearg_constructor: - if noarg_constructor: - error(filename, linenum, 'runtime/explicit', 5, - 'Zero-parameter constructors should not be marked explicit.') - - -def CheckSpacingForFunctionCall(filename, clean_lines, linenum, error): - """Checks for the correctness of various spacing around function calls. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # Since function calls often occur inside if/for/while/switch - # expressions - which have their own, more liberal conventions - we - # first see if we should be looking inside such an expression for a - # function call, to which we can apply more strict standards. - fncall = line # if there's no control flow construct, look at whole line - for pattern in (r'\bif\s*\((.*)\)\s*{', - r'\bfor\s*\((.*)\)\s*{', - r'\bwhile\s*\((.*)\)\s*[{;]', - r'\bswitch\s*\((.*)\)\s*{'): - match = Search(pattern, line) - if match: - fncall = match.group(1) # look inside the parens for function calls - break - - # Except in if/for/while/switch, there should never be space - # immediately inside parens (eg "f( 3, 4 )"). We make an exception - # for nested parens ( (a+b) + c ). Likewise, there should never be - # a space before a ( when it's a function argument. I assume it's a - # function argument when the char before the whitespace is legal in - # a function name (alnum + _) and we're not starting a macro. Also ignore - # pointers and references to arrays and functions coz they're too tricky: - # we use a very simple way to recognize these: - # " (something)(maybe-something)" or - # " (something)(maybe-something," or - # " (something)[something]" - # Note that we assume the contents of [] to be short enough that - # they'll never need to wrap. - if ( # Ignore control structures. - not Search(r'\b(if|for|while|switch|return|new|delete|catch|sizeof)\b', - fncall) and - # Ignore pointers/references to functions. - not Search(r' \([^)]+\)\([^)]*(\)|,$)', fncall) and - # Ignore pointers/references to arrays. - not Search(r' \([^)]+\)\[[^\]]+\]', fncall)): - if Search(r'\w\s*\(\s(?!\s*\\$)', fncall): # a ( used for a fn call - error(filename, linenum, 'whitespace/parens', 4, - 'Extra space after ( in function call') - elif Search(r'\(\s+(?!(\s*\\)|\()', fncall): - error(filename, linenum, 'whitespace/parens', 2, - 'Extra space after (') - if (Search(r'\w\s+\(', fncall) and - not Search(r'_{0,2}asm_{0,2}\s+_{0,2}volatile_{0,2}\s+\(', fncall) and - not Search(r'#\s*define|typedef|using\s+\w+\s*=', fncall) and - not Search(r'\w\s+\((\w+::)*\*\w+\)\(', fncall) and - not Search(r'\bcase\s+\(', fncall)): - # TODO(unknown): Space after an operator function seem to be a common - # error, silence those for now by restricting them to highest verbosity. - if Search(r'\boperator_*\b', line): - error(filename, linenum, 'whitespace/parens', 0, - 'Extra space before ( in function call') - else: - error(filename, linenum, 'whitespace/parens', 4, - 'Extra space before ( in function call') - # If the ) is followed only by a newline or a { + newline, assume it's - # part of a control statement (if/while/etc), and don't complain - if Search(r'[^)]\s+\)\s*[^{\s]', fncall): - # If the closing parenthesis is preceded by only whitespaces, - # try to give a more descriptive error message. - if Search(r'^\s+\)', fncall): - error(filename, linenum, 'whitespace/parens', 2, - 'Closing ) should be moved to the previous line') - else: - error(filename, linenum, 'whitespace/parens', 2, - 'Extra space before )') - - -def IsBlankLine(line): - """Returns true if the given line is blank. - - We consider a line to be blank if the line is empty or consists of - only white spaces. - - Args: - line: A line of a string. - - Returns: - True, if the given line is blank. - """ - return not line or line.isspace() - - -def CheckForNamespaceIndentation(filename, nesting_state, clean_lines, line, - error): - is_namespace_indent_item = ( - len(nesting_state.stack) > 1 and - nesting_state.stack[-1].check_namespace_indentation and - isinstance(nesting_state.previous_stack_top, _NamespaceInfo) and - nesting_state.previous_stack_top == nesting_state.stack[-2]) - - if ShouldCheckNamespaceIndentation(nesting_state, is_namespace_indent_item, - clean_lines.elided, line): - CheckItemIndentationInNamespace(filename, clean_lines.elided, - line, error) - - -def CheckForFunctionLengths(filename, clean_lines, linenum, - function_state, error): - """Reports for long function bodies. - - For an overview why this is done, see: - https://google-styleguide.googlecode.com/svn/trunk/cppguide.xml#Write_Short_Functions - - Uses a simplistic algorithm assuming other style guidelines - (especially spacing) are followed. - Only checks unindented functions, so class members are unchecked. - Trivial bodies are unchecked, so constructors with huge initializer lists - may be missed. - Blank/comment lines are not counted so as to avoid encouraging the removal - of vertical space and comments just to get through a lint check. - NOLINT *on the last line of a function* disables this check. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - function_state: Current function name and lines in body so far. - error: The function to call with any errors found. - """ - lines = clean_lines.lines - line = lines[linenum] - joined_line = '' - - starting_func = False - regexp = r'(\w(\w|::|\*|\&|\s)*)\(' # decls * & space::name( ... - match_result = Match(regexp, line) - if match_result: - # If the name is all caps and underscores, figure it's a macro and - # ignore it, unless it's TEST or TEST_F. - function_name = match_result.group(1).split()[-1] - if function_name == 'TEST' or function_name == 'TEST_F' or ( - not Match(r'[A-Z_]+$', function_name)): - starting_func = True - - if starting_func: - body_found = False - for start_linenum in xrange(linenum, clean_lines.NumLines()): - start_line = lines[start_linenum] - joined_line += ' ' + start_line.lstrip() - if Search(r'(;|})', start_line): # Declarations and trivial functions - body_found = True - break # ... ignore - if Search(r'{', start_line): - body_found = True - function = Search(r'((\w|:)*)\(', line).group(1) - if Match(r'TEST', function): # Handle TEST... macros - parameter_regexp = Search(r'(\(.*\))', joined_line) - if parameter_regexp: # Ignore bad syntax - function += parameter_regexp.group(1) - else: - function += '()' - function_state.Begin(function) - break - if not body_found: - # No body for the function (or evidence of a non-function) was found. - error(filename, linenum, 'readability/fn_size', 5, - 'Lint failed to find start of function body.') - elif Match(r'^\}\s*$', line): # function end - function_state.Check(error, filename, linenum) - function_state.End() - elif not Match(r'^\s*$', line): - function_state.Count() # Count non-blank/non-comment lines. - - -_RE_PATTERN_TODO = re.compile(r'^//(\s*)TODO(\(.+?\))?:?(\s|$)?') - - -def CheckComment(line, filename, linenum, next_line_start, error): - """Checks for common mistakes in comments. - - Args: - line: The line in question. - filename: The name of the current file. - linenum: The number of the line to check. - next_line_start: The first non-whitespace column of the next line. - error: The function to call with any errors found. - """ - commentpos = line.find('//') - if commentpos != -1: - # Check if the // may be in quotes. If so, ignore it - if re.sub(r'\\.', '', line[0:commentpos]).count('"') % 2 == 0: - # Allow one space for new scopes, two spaces otherwise: - if (not (Match(r'^.*{ *//', line) and next_line_start == commentpos) and - ((commentpos >= 1 and - line[commentpos-1] not in string.whitespace) or - (commentpos >= 2 and - line[commentpos-2] not in string.whitespace))): - error(filename, linenum, 'whitespace/comments', 2, - 'At least two spaces is best between code and comments') - - # Checks for common mistakes in TODO comments. - comment = line[commentpos:] - match = _RE_PATTERN_TODO.match(comment) - if match: - # One whitespace is correct; zero whitespace is handled elsewhere. - leading_whitespace = match.group(1) - if len(leading_whitespace) > 1: - error(filename, linenum, 'whitespace/todo', 2, - 'Too many spaces before TODO') - - username = match.group(2) - if not username: - error(filename, linenum, 'readability/todo', 2, - 'Missing username in TODO; it should look like ' - '"// TODO(my_username): Stuff."') - - middle_whitespace = match.group(3) - # Comparisons made explicit for correctness -- pylint: disable=g-explicit-bool-comparison - if middle_whitespace != ' ' and middle_whitespace != '': - error(filename, linenum, 'whitespace/todo', 2, - 'TODO(my_username) should be followed by a space') - - # If the comment contains an alphanumeric character, there - # should be a space somewhere between it and the // unless - # it's a /// or //! Doxygen comment. - if (Match(r'//[^ ]*\w', comment) and - not Match(r'(///|//\!)(\s+|$)', comment)): - error(filename, linenum, 'whitespace/comments', 4, - 'Should have a space between // and comment') - - -def CheckSpacing(filename, clean_lines, linenum, nesting_state, error): - """Checks for the correctness of various spacing issues in the code. - - Things we check for: spaces around operators, spaces after - if/for/while/switch, no spaces around parens in function calls, two - spaces between code and comment, don't start a block with a blank - line, don't end a function with a blank line, don't add a blank line - after public/protected/private, don't have too many blank lines in a row. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - nesting_state: A NestingState instance which maintains information about - the current stack of nested blocks being parsed. - error: The function to call with any errors found. - """ - - # Don't use "elided" lines here, otherwise we can't check commented lines. - # Don't want to use "raw" either, because we don't want to check inside C++11 - # raw strings, - raw = clean_lines.lines_without_raw_strings - line = raw[linenum] - - # Before nixing comments, check if the line is blank for no good - # reason. This includes the first line after a block is opened, and - # blank lines at the end of a function (ie, right before a line like '}' - # - # Skip all the blank line checks if we are immediately inside a - # namespace body. In other words, don't issue blank line warnings - # for this block: - # namespace { - # - # } - # - # A warning about missing end of namespace comments will be issued instead. - # - # Also skip blank line checks for 'extern "C"' blocks, which are formatted - # like namespaces. - if (IsBlankLine(line) and - not nesting_state.InNamespaceBody() and - not nesting_state.InExternC()): - elided = clean_lines.elided - prev_line = elided[linenum - 1] - prevbrace = prev_line.rfind('{') - # TODO(unknown): Don't complain if line before blank line, and line after, - # both start with alnums and are indented the same amount. - # This ignores whitespace at the start of a namespace block - # because those are not usually indented. - if prevbrace != -1 and prev_line[prevbrace:].find('}') == -1: - # OK, we have a blank line at the start of a code block. Before we - # complain, we check if it is an exception to the rule: The previous - # non-empty line has the parameters of a function header that are indented - # 4 spaces (because they did not fit in a 80 column line when placed on - # the same line as the function name). We also check for the case where - # the previous line is indented 6 spaces, which may happen when the - # initializers of a constructor do not fit into a 80 column line. - exception = False - if Match(r' {6}\w', prev_line): # Initializer list? - # We are looking for the opening column of initializer list, which - # should be indented 4 spaces to cause 6 space indentation afterwards. - search_position = linenum-2 - while (search_position >= 0 - and Match(r' {6}\w', elided[search_position])): - search_position -= 1 - exception = (search_position >= 0 - and elided[search_position][:5] == ' :') - else: - # Search for the function arguments or an initializer list. We use a - # simple heuristic here: If the line is indented 4 spaces; and we have a - # closing paren, without the opening paren, followed by an opening brace - # or colon (for initializer lists) we assume that it is the last line of - # a function header. If we have a colon indented 4 spaces, it is an - # initializer list. - exception = (Match(r' {4}\w[^\(]*\)\s*(const\s*)?(\{\s*$|:)', - prev_line) - or Match(r' {4}:', prev_line)) - - if not exception: - error(filename, linenum, 'whitespace/blank_line', 2, - 'Redundant blank line at the start of a code block ' - 'should be deleted.') - # Ignore blank lines at the end of a block in a long if-else - # chain, like this: - # if (condition1) { - # // Something followed by a blank line - # - # } else if (condition2) { - # // Something else - # } - if linenum + 1 < clean_lines.NumLines(): - next_line = raw[linenum + 1] - if (next_line - and Match(r'\s*}', next_line) - and next_line.find('} else ') == -1): - error(filename, linenum, 'whitespace/blank_line', 3, - 'Redundant blank line at the end of a code block ' - 'should be deleted.') - - matched = Match(r'\s*(public|protected|private):', prev_line) - if matched: - error(filename, linenum, 'whitespace/blank_line', 3, - 'Do not leave a blank line after "%s:"' % matched.group(1)) - - # Next, check comments - next_line_start = 0 - if linenum + 1 < clean_lines.NumLines(): - next_line = raw[linenum + 1] - next_line_start = len(next_line) - len(next_line.lstrip()) - CheckComment(line, filename, linenum, next_line_start, error) - - # get rid of comments and strings - line = clean_lines.elided[linenum] - - # You shouldn't have spaces before your brackets, except for C++11 attributes - # or maybe after 'delete []', 'return []() {};', or 'auto [abc, ...] = ...;'. - if (Search(r'\w\s+\[(?!\[)', line) and - not Search(r'(?:auto&?|delete|return)\s+\[', line)): - error(filename, linenum, 'whitespace/braces', 5, - 'Extra space before [') - - # In range-based for, we wanted spaces before and after the colon, but - # not around "::" tokens that might appear. - if (Search(r'for *\(.*[^:]:[^: ]', line) or - Search(r'for *\(.*[^: ]:[^:]', line)): - error(filename, linenum, 'whitespace/forcolon', 2, - 'Missing space around colon in range-based for loop') - - -def CheckOperatorSpacing(filename, clean_lines, linenum, error): - """Checks for horizontal spacing around operators. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # Don't try to do spacing checks for operator methods. Do this by - # replacing the troublesome characters with something else, - # preserving column position for all other characters. - # - # The replacement is done repeatedly to avoid false positives from - # operators that call operators. - while True: - match = Match(r'^(.*\boperator\b)(\S+)(\s*\(.*)$', line) - if match: - line = match.group(1) + ('_' * len(match.group(2))) + match.group(3) - else: - break - - # We allow no-spaces around = within an if: "if ( (a=Foo()) == 0 )". - # Otherwise not. Note we only check for non-spaces on *both* sides; - # sometimes people put non-spaces on one side when aligning ='s among - # many lines (not that this is behavior that I approve of...) - if ((Search(r'[\w.]=', line) or - Search(r'=[\w.]', line)) - and not Search(r'\b(if|while|for) ', line) - # Operators taken from [lex.operators] in C++11 standard. - and not Search(r'(>=|<=|==|!=|&=|\^=|\|=|\+=|\*=|\/=|\%=)', line) - and not Search(r'operator=', line)): - error(filename, linenum, 'whitespace/operators', 4, - 'Missing spaces around =') - - # It's ok not to have spaces around binary operators like + - * /, but if - # there's too little whitespace, we get concerned. It's hard to tell, - # though, so we punt on this one for now. TODO. - - # You should always have whitespace around binary operators. - # - # Check <= and >= first to avoid false positives with < and >, then - # check non-include lines for spacing around < and >. - # - # If the operator is followed by a comma, assume it's be used in a - # macro context and don't do any checks. This avoids false - # positives. - # - # Note that && is not included here. This is because there are too - # many false positives due to RValue references. - match = Search(r'[^<>=!\s](==|!=|<=|>=|\|\|)[^<>=!\s,;\)]', line) - if match: - error(filename, linenum, 'whitespace/operators', 3, - 'Missing spaces around %s' % match.group(1)) - elif not Match(r'#.*include', line): - # Look for < that is not surrounded by spaces. This is only - # triggered if both sides are missing spaces, even though - # technically should should flag if at least one side is missing a - # space. This is done to avoid some false positives with shifts. - match = Match(r'^(.*[^\s<])<[^\s=<,]', line) - if match: - (_, _, end_pos) = CloseExpression( - clean_lines, linenum, len(match.group(1))) - if end_pos <= -1: - error(filename, linenum, 'whitespace/operators', 3, - 'Missing spaces around <') - - # Look for > that is not surrounded by spaces. Similar to the - # above, we only trigger if both sides are missing spaces to avoid - # false positives with shifts. - match = Match(r'^(.*[^-\s>])>[^\s=>,]', line) - if match: - (_, _, start_pos) = ReverseCloseExpression( - clean_lines, linenum, len(match.group(1))) - if start_pos <= -1: - error(filename, linenum, 'whitespace/operators', 3, - 'Missing spaces around >') - - # We allow no-spaces around << when used like this: 10<<20, but - # not otherwise (particularly, not when used as streams) - # - # We also allow operators following an opening parenthesis, since - # those tend to be macros that deal with operators. - match = Search(r'(operator|[^\s(<])(?:L|UL|LL|ULL|l|ul|ll|ull)?<<([^\s,=<])', line) - if (match and not (match.group(1).isdigit() and match.group(2).isdigit()) and - not (match.group(1) == 'operator' and match.group(2) == ';')): - error(filename, linenum, 'whitespace/operators', 3, - 'Missing spaces around <<') - - # We allow no-spaces around >> for almost anything. This is because - # C++11 allows ">>" to close nested templates, which accounts for - # most cases when ">>" is not followed by a space. - # - # We still warn on ">>" followed by alpha character, because that is - # likely due to ">>" being used for right shifts, e.g.: - # value >> alpha - # - # When ">>" is used to close templates, the alphanumeric letter that - # follows would be part of an identifier, and there should still be - # a space separating the template type and the identifier. - # type> alpha - match = Search(r'>>[a-zA-Z_]', line) - if match: - error(filename, linenum, 'whitespace/operators', 3, - 'Missing spaces around >>') - - # There shouldn't be space around unary operators - match = Search(r'(!\s|~\s|[\s]--[\s;]|[\s]\+\+[\s;])', line) - if match: - error(filename, linenum, 'whitespace/operators', 4, - 'Extra space for operator %s' % match.group(1)) - - -def CheckParenthesisSpacing(filename, clean_lines, linenum, error): - """Checks for horizontal spacing around parentheses. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # No spaces after an if, while, switch, or for - match = Search(r' (if\(|for\(|while\(|switch\()', line) - if match: - error(filename, linenum, 'whitespace/parens', 5, - 'Missing space before ( in %s' % match.group(1)) - - # For if/for/while/switch, the left and right parens should be - # consistent about how many spaces are inside the parens, and - # there should either be zero or one spaces inside the parens. - # We don't want: "if ( foo)" or "if ( foo )". - # Exception: "for ( ; foo; bar)" and "for (foo; bar; )" are allowed. - match = Search(r'\b(if|for|while|switch)\s*' - r'\(([ ]*)(.).*[^ ]+([ ]*)\)\s*{\s*$', - line) - if match: - if len(match.group(2)) != len(match.group(4)): - if not (match.group(3) == ';' and - len(match.group(2)) == 1 + len(match.group(4)) or - not match.group(2) and Search(r'\bfor\s*\(.*; \)', line)): - error(filename, linenum, 'whitespace/parens', 5, - 'Mismatching spaces inside () in %s' % match.group(1)) - if len(match.group(2)) not in [0, 1]: - error(filename, linenum, 'whitespace/parens', 5, - 'Should have zero or one spaces inside ( and ) in %s' % - match.group(1)) - - -def CheckCommaSpacing(filename, clean_lines, linenum, error): - """Checks for horizontal spacing near commas and semicolons. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - raw = clean_lines.lines_without_raw_strings - line = clean_lines.elided[linenum] - - # You should always have a space after a comma (either as fn arg or operator) - # - # This does not apply when the non-space character following the - # comma is another comma, since the only time when that happens is - # for empty macro arguments. - # - # We run this check in two passes: first pass on elided lines to - # verify that lines contain missing whitespaces, second pass on raw - # lines to confirm that those missing whitespaces are not due to - # elided comments. - if (Search(r',[^,\s]', ReplaceAll(r'\boperator\s*,\s*\(', 'F(', line)) and - Search(r',[^,\s]', raw[linenum])): - error(filename, linenum, 'whitespace/comma', 3, - 'Missing space after ,') - - # You should always have a space after a semicolon - # except for few corner cases - # TODO(unknown): clarify if 'if (1) { return 1;}' is requires one more - # space after ; - if Search(r';[^\s};\\)/]', line): - error(filename, linenum, 'whitespace/semicolon', 3, - 'Missing space after ;') - - -def _IsType(clean_lines, nesting_state, expr): - """Check if expression looks like a type name, returns true if so. - - Args: - clean_lines: A CleansedLines instance containing the file. - nesting_state: A NestingState instance which maintains information about - the current stack of nested blocks being parsed. - expr: The expression to check. - Returns: - True, if token looks like a type. - """ - # Keep only the last token in the expression - last_word = Match(r'^.*(\b\S+)$', expr) - if last_word: - token = last_word.group(1) - else: - token = expr - - # Match native types and stdint types - if _TYPES.match(token): - return True - - # Try a bit harder to match templated types. Walk up the nesting - # stack until we find something that resembles a typename - # declaration for what we are looking for. - typename_pattern = (r'\b(?:typename|class|struct)\s+' + re.escape(token) + - r'\b') - block_index = len(nesting_state.stack) - 1 - while block_index >= 0: - if isinstance(nesting_state.stack[block_index], _NamespaceInfo): - return False - - # Found where the opening brace is. We want to scan from this - # line up to the beginning of the function, minus a few lines. - # template - # class C - # : public ... { // start scanning here - last_line = nesting_state.stack[block_index].starting_linenum - - next_block_start = 0 - if block_index > 0: - next_block_start = nesting_state.stack[block_index - 1].starting_linenum - first_line = last_line - while first_line >= next_block_start: - if clean_lines.elided[first_line].find('template') >= 0: - break - first_line -= 1 - if first_line < next_block_start: - # Didn't find any "template" keyword before reaching the next block, - # there are probably no template things to check for this block - block_index -= 1 - continue - - # Look for typename in the specified range - for i in xrange(first_line, last_line + 1, 1): - if Search(typename_pattern, clean_lines.elided[i]): - return True - block_index -= 1 - - return False - - -def CheckBracesSpacing(filename, clean_lines, linenum, nesting_state, error): - """Checks for horizontal spacing near commas. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - nesting_state: A NestingState instance which maintains information about - the current stack of nested blocks being parsed. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # Except after an opening paren, or after another opening brace (in case of - # an initializer list, for instance), you should have spaces before your - # braces when they are delimiting blocks, classes, namespaces etc. - # And since you should never have braces at the beginning of a line, - # this is an easy test. Except that braces used for initialization don't - # follow the same rule; we often don't want spaces before those. - match = Match(r'^(.*[^ ({>]){', line) - - if match: - # Try a bit harder to check for brace initialization. This - # happens in one of the following forms: - # Constructor() : initializer_list_{} { ... } - # Constructor{}.MemberFunction() - # Type variable{}; - # FunctionCall(type{}, ...); - # LastArgument(..., type{}); - # LOG(INFO) << type{} << " ..."; - # map_of_type[{...}] = ...; - # ternary = expr ? new type{} : nullptr; - # OuterTemplate{}> - # - # We check for the character following the closing brace, and - # silence the warning if it's one of those listed above, i.e. - # "{.;,)<>]:". - # - # To account for nested initializer list, we allow any number of - # closing braces up to "{;,)<". We can't simply silence the - # warning on first sight of closing brace, because that would - # cause false negatives for things that are not initializer lists. - # Silence this: But not this: - # Outer{ if (...) { - # Inner{...} if (...){ // Missing space before { - # }; } - # - # There is a false negative with this approach if people inserted - # spurious semicolons, e.g. "if (cond){};", but we will catch the - # spurious semicolon with a separate check. - leading_text = match.group(1) - (endline, endlinenum, endpos) = CloseExpression( - clean_lines, linenum, len(match.group(1))) - trailing_text = '' - if endpos > -1: - trailing_text = endline[endpos:] - for offset in xrange(endlinenum + 1, - min(endlinenum + 3, clean_lines.NumLines() - 1)): - trailing_text += clean_lines.elided[offset] - # We also suppress warnings for `uint64_t{expression}` etc., as the style - # guide recommends brace initialization for integral types to avoid - # overflow/truncation. - if (not Match(r'^[\s}]*[{.;,)<>\]:]', trailing_text) - and not _IsType(clean_lines, nesting_state, leading_text)): - error(filename, linenum, 'whitespace/braces', 5, - 'Missing space before {') - - # Make sure '} else {' has spaces. - if Search(r'}else', line): - error(filename, linenum, 'whitespace/braces', 5, - 'Missing space before else') - - # You shouldn't have a space before a semicolon at the end of the line. - # There's a special case for "for" since the style guide allows space before - # the semicolon there. - if Search(r':\s*;\s*$', line): - error(filename, linenum, 'whitespace/semicolon', 5, - 'Semicolon defining empty statement. Use {} instead.') - elif Search(r'^\s*;\s*$', line): - error(filename, linenum, 'whitespace/semicolon', 5, - 'Line contains only semicolon. If this should be an empty statement, ' - 'use {} instead.') - elif (Search(r'\s+;\s*$', line) and - not Search(r'\bfor\b', line)): - error(filename, linenum, 'whitespace/semicolon', 5, - 'Extra space before last semicolon. If this should be an empty ' - 'statement, use {} instead.') - - -def IsDecltype(clean_lines, linenum, column): - """Check if the token ending on (linenum, column) is decltype(). - - Args: - clean_lines: A CleansedLines instance containing the file. - linenum: the number of the line to check. - column: end column of the token to check. - Returns: - True if this token is decltype() expression, False otherwise. - """ - (text, _, start_col) = ReverseCloseExpression(clean_lines, linenum, column) - if start_col < 0: - return False - if Search(r'\bdecltype\s*$', text[0:start_col]): - return True - return False - -def CheckSectionSpacing(filename, clean_lines, class_info, linenum, error): - """Checks for additional blank line issues related to sections. - - Currently the only thing checked here is blank line before protected/private. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - class_info: A _ClassInfo objects. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - # Skip checks if the class is small, where small means 25 lines or less. - # 25 lines seems like a good cutoff since that's the usual height of - # terminals, and any class that can't fit in one screen can't really - # be considered "small". - # - # Also skip checks if we are on the first line. This accounts for - # classes that look like - # class Foo { public: ... }; - # - # If we didn't find the end of the class, last_line would be zero, - # and the check will be skipped by the first condition. - if (class_info.last_line - class_info.starting_linenum <= 24 or - linenum <= class_info.starting_linenum): - return - - matched = Match(r'\s*(public|protected|private):', clean_lines.lines[linenum]) - if matched: - # Issue warning if the line before public/protected/private was - # not a blank line, but don't do this if the previous line contains - # "class" or "struct". This can happen two ways: - # - We are at the beginning of the class. - # - We are forward-declaring an inner class that is semantically - # private, but needed to be public for implementation reasons. - # Also ignores cases where the previous line ends with a backslash as can be - # common when defining classes in C macros. - prev_line = clean_lines.lines[linenum - 1] - if (not IsBlankLine(prev_line) and - not Search(r'\b(class|struct)\b', prev_line) and - not Search(r'\\$', prev_line)): - # Try a bit harder to find the beginning of the class. This is to - # account for multi-line base-specifier lists, e.g.: - # class Derived - # : public Base { - end_class_head = class_info.starting_linenum - for i in range(class_info.starting_linenum, linenum): - if Search(r'\{\s*$', clean_lines.lines[i]): - end_class_head = i - break - if end_class_head < linenum - 1: - error(filename, linenum, 'whitespace/blank_line', 3, - '"%s:" should be preceded by a blank line' % matched.group(1)) - - -def GetPreviousNonBlankLine(clean_lines, linenum): - """Return the most recent non-blank line and its line number. - - Args: - clean_lines: A CleansedLines instance containing the file contents. - linenum: The number of the line to check. - - Returns: - A tuple with two elements. The first element is the contents of the last - non-blank line before the current line, or the empty string if this is the - first non-blank line. The second is the line number of that line, or -1 - if this is the first non-blank line. - """ - - prevlinenum = linenum - 1 - while prevlinenum >= 0: - prevline = clean_lines.elided[prevlinenum] - if not IsBlankLine(prevline): # if not a blank line... - return (prevline, prevlinenum) - prevlinenum -= 1 - return ('', -1) - - -def CheckBraces(filename, clean_lines, linenum, error): - """Looks for misplaced braces (e.g. at the end of line). - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - - line = clean_lines.elided[linenum] # get rid of comments and strings - - if Match(r'\s*{\s*$', line): - # We allow an open brace to start a line in the case where someone is using - # braces in a block to explicitly create a new scope, which is commonly used - # to control the lifetime of stack-allocated variables. Braces are also - # used for brace initializers inside function calls. We don't detect this - # perfectly: we just don't complain if the last non-whitespace character on - # the previous non-blank line is ',', ';', ':', '(', '{', or '}', or if the - # previous line starts a preprocessor block. We also allow a brace on the - # following line if it is part of an array initialization and would not fit - # within the 80 character limit of the preceding line. - prevline = GetPreviousNonBlankLine(clean_lines, linenum)[0] - if (not Search(r'[,;:}{(]\s*$', prevline) and - not Match(r'\s*#', prevline) and - not (GetLineWidth(prevline) > _line_length - 2 and '[]' in prevline)): - error(filename, linenum, 'whitespace/braces', 4, - '{ should almost always be at the end of the previous line') - - # An else clause should be on the same line as the preceding closing brace. - if Match(r'\s*else\b\s*(?:if\b|\{|$)', line): - prevline = GetPreviousNonBlankLine(clean_lines, linenum)[0] - if Match(r'\s*}\s*$', prevline): - error(filename, linenum, 'whitespace/newline', 4, - 'An else should appear on the same line as the preceding }') - - # If braces come on one side of an else, they should be on both. - # However, we have to worry about "else if" that spans multiple lines! - if Search(r'else if\s*\(', line): # could be multi-line if - brace_on_left = bool(Search(r'}\s*else if\s*\(', line)) - # find the ( after the if - pos = line.find('else if') - pos = line.find('(', pos) - if pos > 0: - (endline, _, endpos) = CloseExpression(clean_lines, linenum, pos) - brace_on_right = endline[endpos:].find('{') != -1 - if brace_on_left != brace_on_right: # must be brace after if - error(filename, linenum, 'readability/braces', 5, - 'If an else has a brace on one side, it should have it on both') - elif Search(r'}\s*else[^{]*$', line) or Match(r'[^}]*else\s*{', line): - error(filename, linenum, 'readability/braces', 5, - 'If an else has a brace on one side, it should have it on both') - - # Likewise, an else should never have the else clause on the same line - if Search(r'\belse [^\s{]', line) and not Search(r'\belse if\b', line): - error(filename, linenum, 'whitespace/newline', 4, - 'Else clause should never be on same line as else (use 2 lines)') - - # In the same way, a do/while should never be on one line - if Match(r'\s*do [^\s{]', line): - error(filename, linenum, 'whitespace/newline', 4, - 'do/while clauses should not be on a single line') - - # Check single-line if/else bodies. The style guide says 'curly braces are not - # required for single-line statements'. We additionally allow multi-line, - # single statements, but we reject anything with more than one semicolon in - # it. This means that the first semicolon after the if should be at the end of - # its line, and the line after that should have an indent level equal to or - # lower than the if. We also check for ambiguous if/else nesting without - # braces. - if_else_match = Search(r'\b(if\s*(|constexpr)\s*\(|else\b)', line) - if if_else_match and not Match(r'\s*#', line): - if_indent = GetIndentLevel(line) - endline, endlinenum, endpos = line, linenum, if_else_match.end() - if_match = Search(r'\bif\s*(|constexpr)\s*\(', line) - if if_match: - # This could be a multiline if condition, so find the end first. - pos = if_match.end() - 1 - (endline, endlinenum, endpos) = CloseExpression(clean_lines, linenum, pos) - # Check for an opening brace, either directly after the if or on the next - # line. If found, this isn't a single-statement conditional. - if (not Match(r'\s*{', endline[endpos:]) - and not (Match(r'\s*$', endline[endpos:]) - and endlinenum < (len(clean_lines.elided) - 1) - and Match(r'\s*{', clean_lines.elided[endlinenum + 1]))): - while (endlinenum < len(clean_lines.elided) - and ';' not in clean_lines.elided[endlinenum][endpos:]): - endlinenum += 1 - endpos = 0 - if endlinenum < len(clean_lines.elided): - endline = clean_lines.elided[endlinenum] - # We allow a mix of whitespace and closing braces (e.g. for one-liner - # methods) and a single \ after the semicolon (for macros) - endpos = endline.find(';') - if not Match(r';[\s}]*(\\?)$', endline[endpos:]): - # Semicolon isn't the last character, there's something trailing. - # Output a warning if the semicolon is not contained inside - # a lambda expression. - if not Match(r'^[^{};]*\[[^\[\]]*\][^{}]*\{[^{}]*\}\s*\)*[;,]\s*$', - endline): - error(filename, linenum, 'readability/braces', 4, - 'If/else bodies with multiple statements require braces') - elif endlinenum < len(clean_lines.elided) - 1: - # Make sure the next line is dedented - next_line = clean_lines.elided[endlinenum + 1] - next_indent = GetIndentLevel(next_line) - # With ambiguous nested if statements, this will error out on the - # if that *doesn't* match the else, regardless of whether it's the - # inner one or outer one. - if (if_match and Match(r'\s*else\b', next_line) - and next_indent != if_indent): - error(filename, linenum, 'readability/braces', 4, - 'Else clause should be indented at the same level as if. ' - 'Ambiguous nested if/else chains require braces.') - elif next_indent > if_indent: - error(filename, linenum, 'readability/braces', 4, - 'If/else bodies with multiple statements require braces') - - -def CheckTrailingSemicolon(filename, clean_lines, linenum, error): - """Looks for redundant trailing semicolon. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - - line = clean_lines.elided[linenum] - - # Block bodies should not be followed by a semicolon. Due to C++11 - # brace initialization, there are more places where semicolons are - # required than not, so we explicitly list the allowed rules rather - # than listing the disallowed ones. These are the places where "};" - # should be replaced by just "}": - # 1. Some flavor of block following closing parenthesis: - # for (;;) {}; - # while (...) {}; - # switch (...) {}; - # Function(...) {}; - # if (...) {}; - # if (...) else if (...) {}; - # - # 2. else block: - # if (...) else {}; - # - # 3. const member function: - # Function(...) const {}; - # - # 4. Block following some statement: - # x = 42; - # {}; - # - # 5. Block at the beginning of a function: - # Function(...) { - # {}; - # } - # - # Note that naively checking for the preceding "{" will also match - # braces inside multi-dimensional arrays, but this is fine since - # that expression will not contain semicolons. - # - # 6. Block following another block: - # while (true) {} - # {}; - # - # 7. End of namespaces: - # namespace {}; - # - # These semicolons seems far more common than other kinds of - # redundant semicolons, possibly due to people converting classes - # to namespaces. For now we do not warn for this case. - # - # Try matching case 1 first. - match = Match(r'^(.*\)\s*)\{', line) - if match: - # Matched closing parenthesis (case 1). Check the token before the - # matching opening parenthesis, and don't warn if it looks like a - # macro. This avoids these false positives: - # - macro that defines a base class - # - multi-line macro that defines a base class - # - macro that defines the whole class-head - # - # But we still issue warnings for macros that we know are safe to - # warn, specifically: - # - TEST, TEST_F, TEST_P, MATCHER, MATCHER_P - # - TYPED_TEST - # - INTERFACE_DEF - # - EXCLUSIVE_LOCKS_REQUIRED, SHARED_LOCKS_REQUIRED, LOCKS_EXCLUDED: - # - # We implement a list of safe macros instead of a list of - # unsafe macros, even though the latter appears less frequently in - # google code and would have been easier to implement. This is because - # the downside for getting the allowed checks wrong means some extra - # semicolons, while the downside for getting disallowed checks wrong - # would result in compile errors. - # - # In addition to macros, we also don't want to warn on - # - Compound literals - # - Lambdas - # - alignas specifier with anonymous structs - # - decltype - closing_brace_pos = match.group(1).rfind(')') - opening_parenthesis = ReverseCloseExpression( - clean_lines, linenum, closing_brace_pos) - if opening_parenthesis[2] > -1: - line_prefix = opening_parenthesis[0][0:opening_parenthesis[2]] - macro = Search(r'\b([A-Z_][A-Z0-9_]*)\s*$', line_prefix) - func = Match(r'^(.*\])\s*$', line_prefix) - if ((macro and - macro.group(1) not in ( - 'TEST', 'TEST_F', 'MATCHER', 'MATCHER_P', 'TYPED_TEST', - 'EXCLUSIVE_LOCKS_REQUIRED', 'SHARED_LOCKS_REQUIRED', - 'LOCKS_EXCLUDED', 'INTERFACE_DEF')) or - (func and not Search(r'\boperator\s*\[\s*\]', func.group(1))) or - Search(r'\b(?:struct|union)\s+alignas\s*$', line_prefix) or - Search(r'\bdecltype$', line_prefix) or - Search(r'\s+=\s*$', line_prefix)): - match = None - if (match and - opening_parenthesis[1] > 1 and - Search(r'\]\s*$', clean_lines.elided[opening_parenthesis[1] - 1])): - # Multi-line lambda-expression - match = None - - else: - # Try matching cases 2-3. - match = Match(r'^(.*(?:else|\)\s*const)\s*)\{', line) - if not match: - # Try matching cases 4-6. These are always matched on separate lines. - # - # Note that we can't simply concatenate the previous line to the - # current line and do a single match, otherwise we may output - # duplicate warnings for the blank line case: - # if (cond) { - # // blank line - # } - prevline = GetPreviousNonBlankLine(clean_lines, linenum)[0] - if prevline and Search(r'[;{}]\s*$', prevline): - match = Match(r'^(\s*)\{', line) - - # Check matching closing brace - if match: - (endline, endlinenum, endpos) = CloseExpression( - clean_lines, linenum, len(match.group(1))) - if endpos > -1 and Match(r'^\s*;', endline[endpos:]): - # Current {} pair is eligible for semicolon check, and we have found - # the redundant semicolon, output warning here. - # - # Note: because we are scanning forward for opening braces, and - # outputting warnings for the matching closing brace, if there are - # nested blocks with trailing semicolons, we will get the error - # messages in reversed order. - - # We need to check the line forward for NOLINT - raw_lines = clean_lines.raw_lines - ParseNolintSuppressions(filename, raw_lines[endlinenum-1], endlinenum-1, - error) - ParseNolintSuppressions(filename, raw_lines[endlinenum], endlinenum, - error) - - error(filename, endlinenum, 'readability/braces', 4, - "You don't need a ; after a }") - - -def CheckEmptyBlockBody(filename, clean_lines, linenum, error): - """Look for empty loop/conditional body with only a single semicolon. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - - # Search for loop keywords at the beginning of the line. Because only - # whitespaces are allowed before the keywords, this will also ignore most - # do-while-loops, since those lines should start with closing brace. - # - # We also check "if" blocks here, since an empty conditional block - # is likely an error. - line = clean_lines.elided[linenum] - matched = Match(r'\s*(for|while|if)\s*\(', line) - if matched: - # Find the end of the conditional expression. - (end_line, end_linenum, end_pos) = CloseExpression( - clean_lines, linenum, line.find('(')) - - # Output warning if what follows the condition expression is a semicolon. - # No warning for all other cases, including whitespace or newline, since we - # have a separate check for semicolons preceded by whitespace. - if end_pos >= 0 and Match(r';', end_line[end_pos:]): - if matched.group(1) == 'if': - error(filename, end_linenum, 'whitespace/empty_conditional_body', 5, - 'Empty conditional bodies should use {}') - else: - error(filename, end_linenum, 'whitespace/empty_loop_body', 5, - 'Empty loop bodies should use {} or continue') - - # Check for if statements that have completely empty bodies (no comments) - # and no else clauses. - if end_pos >= 0 and matched.group(1) == 'if': - # Find the position of the opening { for the if statement. - # Return without logging an error if it has no brackets. - opening_linenum = end_linenum - opening_line_fragment = end_line[end_pos:] - # Loop until EOF or find anything that's not whitespace or opening {. - while not Search(r'^\s*\{', opening_line_fragment): - if Search(r'^(?!\s*$)', opening_line_fragment): - # Conditional has no brackets. - return - opening_linenum += 1 - if opening_linenum == len(clean_lines.elided): - # Couldn't find conditional's opening { or any code before EOF. - return - opening_line_fragment = clean_lines.elided[opening_linenum] - # Set opening_line (opening_line_fragment may not be entire opening line). - opening_line = clean_lines.elided[opening_linenum] - - # Find the position of the closing }. - opening_pos = opening_line_fragment.find('{') - if opening_linenum == end_linenum: - # We need to make opening_pos relative to the start of the entire line. - opening_pos += end_pos - (closing_line, closing_linenum, closing_pos) = CloseExpression( - clean_lines, opening_linenum, opening_pos) - if closing_pos < 0: - return - - # Now construct the body of the conditional. This consists of the portion - # of the opening line after the {, all lines until the closing line, - # and the portion of the closing line before the }. - if (clean_lines.raw_lines[opening_linenum] != - CleanseComments(clean_lines.raw_lines[opening_linenum])): - # Opening line ends with a comment, so conditional isn't empty. - return - if closing_linenum > opening_linenum: - # Opening line after the {. Ignore comments here since we checked above. - bodylist = list(opening_line[opening_pos+1:]) - # All lines until closing line, excluding closing line, with comments. - bodylist.extend(clean_lines.raw_lines[opening_linenum+1:closing_linenum]) - # Closing line before the }. Won't (and can't) have comments. - bodylist.append(clean_lines.elided[closing_linenum][:closing_pos-1]) - body = '\n'.join(bodylist) - else: - # If statement has brackets and fits on a single line. - body = opening_line[opening_pos+1:closing_pos-1] - - # Check if the body is empty - if not _EMPTY_CONDITIONAL_BODY_PATTERN.search(body): - return - # The body is empty. Now make sure there's not an else clause. - current_linenum = closing_linenum - current_line_fragment = closing_line[closing_pos:] - # Loop until EOF or find anything that's not whitespace or else clause. - while Search(r'^\s*$|^(?=\s*else)', current_line_fragment): - if Search(r'^(?=\s*else)', current_line_fragment): - # Found an else clause, so don't log an error. - return - current_linenum += 1 - if current_linenum == len(clean_lines.elided): - break - current_line_fragment = clean_lines.elided[current_linenum] - - # The body is empty and there's no else clause until EOF or other code. - error(filename, end_linenum, 'whitespace/empty_if_body', 4, - ('If statement had no body and no else clause')) - - -def FindCheckMacro(line): - """Find a replaceable CHECK-like macro. - - Args: - line: line to search on. - Returns: - (macro name, start position), or (None, -1) if no replaceable - macro is found. - """ - for macro in _CHECK_MACROS: - i = line.find(macro) - if i >= 0: - # Find opening parenthesis. Do a regular expression match here - # to make sure that we are matching the expected CHECK macro, as - # opposed to some other macro that happens to contain the CHECK - # substring. - matched = Match(r'^(.*\b' + macro + r'\s*)\(', line) - if not matched: - continue - return (macro, len(matched.group(1))) - return (None, -1) - - -def CheckCheck(filename, clean_lines, linenum, error): - """Checks the use of CHECK and EXPECT macros. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - - # Decide the set of replacement macros that should be suggested - lines = clean_lines.elided - (check_macro, start_pos) = FindCheckMacro(lines[linenum]) - if not check_macro: - return - - # Find end of the boolean expression by matching parentheses - (last_line, end_line, end_pos) = CloseExpression( - clean_lines, linenum, start_pos) - if end_pos < 0: - return - - # If the check macro is followed by something other than a - # semicolon, assume users will log their own custom error messages - # and don't suggest any replacements. - if not Match(r'\s*;', last_line[end_pos:]): - return - - if linenum == end_line: - expression = lines[linenum][start_pos + 1:end_pos - 1] - else: - expression = lines[linenum][start_pos + 1:] - for i in xrange(linenum + 1, end_line): - expression += lines[i] - expression += last_line[0:end_pos - 1] - - # Parse expression so that we can take parentheses into account. - # This avoids false positives for inputs like "CHECK((a < 4) == b)", - # which is not replaceable by CHECK_LE. - lhs = '' - rhs = '' - operator = None - while expression: - matched = Match(r'^\s*(<<|<<=|>>|>>=|->\*|->|&&|\|\||' - r'==|!=|>=|>|<=|<|\()(.*)$', expression) - if matched: - token = matched.group(1) - if token == '(': - # Parenthesized operand - expression = matched.group(2) - (end, _) = FindEndOfExpressionInLine(expression, 0, ['(']) - if end < 0: - return # Unmatched parenthesis - lhs += '(' + expression[0:end] - expression = expression[end:] - elif token in ('&&', '||'): - # Logical and/or operators. This means the expression - # contains more than one term, for example: - # CHECK(42 < a && a < b); - # - # These are not replaceable with CHECK_LE, so bail out early. - return - elif token in ('<<', '<<=', '>>', '>>=', '->*', '->'): - # Non-relational operator - lhs += token - expression = matched.group(2) - else: - # Relational operator - operator = token - rhs = matched.group(2) - break - else: - # Unparenthesized operand. Instead of appending to lhs one character - # at a time, we do another regular expression match to consume several - # characters at once if possible. Trivial benchmark shows that this - # is more efficient when the operands are longer than a single - # character, which is generally the case. - matched = Match(r'^([^-=!<>()&|]+)(.*)$', expression) - if not matched: - matched = Match(r'^(\s*\S)(.*)$', expression) - if not matched: - break - lhs += matched.group(1) - expression = matched.group(2) - - # Only apply checks if we got all parts of the boolean expression - if not (lhs and operator and rhs): - return - - # Check that rhs do not contain logical operators. We already know - # that lhs is fine since the loop above parses out && and ||. - if rhs.find('&&') > -1 or rhs.find('||') > -1: - return - - # At least one of the operands must be a constant literal. This is - # to avoid suggesting replacements for unprintable things like - # CHECK(variable != iterator) - # - # The following pattern matches decimal, hex integers, strings, and - # characters (in that order). - lhs = lhs.strip() - rhs = rhs.strip() - match_constant = r'^([-+]?(\d+|0[xX][0-9a-fA-F]+)[lLuU]{0,3}|".*"|\'.*\')$' - if Match(match_constant, lhs) or Match(match_constant, rhs): - # Note: since we know both lhs and rhs, we can provide a more - # descriptive error message like: - # Consider using CHECK_EQ(x, 42) instead of CHECK(x == 42) - # Instead of: - # Consider using CHECK_EQ instead of CHECK(a == b) - # - # We are still keeping the less descriptive message because if lhs - # or rhs gets long, the error message might become unreadable. - error(filename, linenum, 'readability/check', 2, - 'Consider using %s instead of %s(a %s b)' % ( - _CHECK_REPLACEMENT[check_macro][operator], - check_macro, operator)) - - -def CheckAltTokens(filename, clean_lines, linenum, error): - """Check alternative keywords being used in boolean expressions. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # Avoid preprocessor lines - if Match(r'^\s*#', line): - return - - # Last ditch effort to avoid multi-line comments. This will not help - # if the comment started before the current line or ended after the - # current line, but it catches most of the false positives. At least, - # it provides a way to workaround this warning for people who use - # multi-line comments in preprocessor macros. - # - # TODO(unknown): remove this once cpplint has better support for - # multi-line comments. - if line.find('/*') >= 0 or line.find('*/') >= 0: - return - - for match in _ALT_TOKEN_REPLACEMENT_PATTERN.finditer(line): - error(filename, linenum, 'readability/alt_tokens', 2, - 'Use operator %s instead of %s' % ( - _ALT_TOKEN_REPLACEMENT[match.group(1)], match.group(1))) - - -def GetLineWidth(line): - """Determines the width of the line in column positions. - - Args: - line: A string, which may be a Unicode string. - - Returns: - The width of the line in column positions, accounting for Unicode - combining characters and wide characters. - """ - if isinstance(line, unicode): - width = 0 - for uc in unicodedata.normalize('NFC', line): - if unicodedata.east_asian_width(uc) in ('W', 'F'): - width += 2 - elif not unicodedata.combining(uc): - # Issue 337 - # https://mail.python.org/pipermail/python-list/2012-August/628809.html - if (sys.version_info.major, sys.version_info.minor) <= (3, 2): - # https://github.com/python/cpython/blob/2.7/Include/unicodeobject.h#L81 - is_wide_build = sysconfig.get_config_var("Py_UNICODE_SIZE") >= 4 - # https://github.com/python/cpython/blob/2.7/Objects/unicodeobject.c#L564 - is_low_surrogate = 0xDC00 <= ord(uc) <= 0xDFFF - if not is_wide_build and is_low_surrogate: - width -= 1 - - width += 1 - return width - else: - return len(line) - - -def CheckStyle(filename, clean_lines, linenum, file_extension, nesting_state, - error): - """Checks rules from the 'C++ style rules' section of cppguide.html. - - Most of these rules are hard to test (naming, comment style), but we - do what we can. In particular we check for 2-space indents, line lengths, - tab usage, spaces inside code, etc. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - file_extension: The extension (without the dot) of the filename. - nesting_state: A NestingState instance which maintains information about - the current stack of nested blocks being parsed. - error: The function to call with any errors found. - """ - - # Don't use "elided" lines here, otherwise we can't check commented lines. - # Don't want to use "raw" either, because we don't want to check inside C++11 - # raw strings, - raw_lines = clean_lines.lines_without_raw_strings - line = raw_lines[linenum] - prev = raw_lines[linenum - 1] if linenum > 0 else '' - - if line.find('\t') != -1: - error(filename, linenum, 'whitespace/tab', 1, - 'Tab found; better to use spaces') - - # One or three blank spaces at the beginning of the line is weird; it's - # hard to reconcile that with 2-space indents. - # NOTE: here are the conditions rob pike used for his tests. Mine aren't - # as sophisticated, but it may be worth becoming so: RLENGTH==initial_spaces - # if(RLENGTH > 20) complain = 0; - # if(match($0, " +(error|private|public|protected):")) complain = 0; - # if(match(prev, "&& *$")) complain = 0; - # if(match(prev, "\\|\\| *$")) complain = 0; - # if(match(prev, "[\",=><] *$")) complain = 0; - # if(match($0, " <<")) complain = 0; - # if(match(prev, " +for \\(")) complain = 0; - # if(prevodd && match(prevprev, " +for \\(")) complain = 0; - scope_or_label_pattern = r'\s*(?:public|private|protected|signals)(?:\s+(?:slots\s*)?)?:\s*\\?$' - classinfo = nesting_state.InnermostClass() - initial_spaces = 0 - cleansed_line = clean_lines.elided[linenum] - while initial_spaces < len(line) and line[initial_spaces] == ' ': - initial_spaces += 1 - # There are certain situations we allow one space, notably for - # section labels, and also lines containing multi-line raw strings. - # We also don't check for lines that look like continuation lines - # (of lines ending in double quotes, commas, equals, or angle brackets) - # because the rules for how to indent those are non-trivial. - if (not Search(r'[",=><] *$', prev) and - (initial_spaces == 1 or initial_spaces == 3) and - not Match(scope_or_label_pattern, cleansed_line) and - not (clean_lines.raw_lines[linenum] != line and - Match(r'^\s*""', line))): - error(filename, linenum, 'whitespace/indent', 3, - 'Weird number of spaces at line-start. ' - 'Are you using a 2-space indent?') - - if line and line[-1].isspace(): - error(filename, linenum, 'whitespace/end_of_line', 4, - 'Line ends in whitespace. Consider deleting these extra spaces.') - - # Check if the line is a header guard. - is_header_guard = False - if IsHeaderExtension(file_extension): - cppvar = GetHeaderGuardCPPVariable(filename) - if (line.startswith('#ifndef %s' % cppvar) or - line.startswith('#define %s' % cppvar) or - line.startswith('#endif // %s' % cppvar)): - is_header_guard = True - # #include lines and header guards can be long, since there's no clean way to - # split them. - # - # URLs can be long too. It's possible to split these, but it makes them - # harder to cut&paste. - # - # The "$Id:...$" comment may also get very long without it being the - # developers fault. - # - # Doxygen documentation copying can get pretty long when using an overloaded - # function declaration - if (not line.startswith('#include') and not is_header_guard and - not Match(r'^\s*//.*http(s?)://\S*$', line) and - not Match(r'^\s*//\s*[^\s]*$', line) and - not Match(r'^// \$Id:.*#[0-9]+ \$$', line) and - not Match(r'^\s*/// [@\\](copydoc|copydetails|copybrief) .*$', line)): - line_width = GetLineWidth(line) - if line_width > _line_length: - error(filename, linenum, 'whitespace/line_length', 2, - 'Lines should be <= %i characters long' % _line_length) - - if (cleansed_line.count(';') > 1 and - # allow simple single line lambdas - not Match(r'^[^{};]*\[[^\[\]]*\][^{}]*\{[^{}\n\r]*\}', - line) and - # for loops are allowed two ;'s (and may run over two lines). - cleansed_line.find('for') == -1 and - (GetPreviousNonBlankLine(clean_lines, linenum)[0].find('for') == -1 or - GetPreviousNonBlankLine(clean_lines, linenum)[0].find(';') != -1) and - # It's ok to have many commands in a switch case that fits in 1 line - not ((cleansed_line.find('case ') != -1 or - cleansed_line.find('default:') != -1) and - cleansed_line.find('break;') != -1)): - error(filename, linenum, 'whitespace/newline', 0, - 'More than one command on the same line') - - # Some more style checks - CheckBraces(filename, clean_lines, linenum, error) - CheckTrailingSemicolon(filename, clean_lines, linenum, error) - CheckEmptyBlockBody(filename, clean_lines, linenum, error) - CheckSpacing(filename, clean_lines, linenum, nesting_state, error) - CheckOperatorSpacing(filename, clean_lines, linenum, error) - CheckParenthesisSpacing(filename, clean_lines, linenum, error) - CheckCommaSpacing(filename, clean_lines, linenum, error) - CheckBracesSpacing(filename, clean_lines, linenum, nesting_state, error) - CheckSpacingForFunctionCall(filename, clean_lines, linenum, error) - CheckCheck(filename, clean_lines, linenum, error) - CheckAltTokens(filename, clean_lines, linenum, error) - classinfo = nesting_state.InnermostClass() - if classinfo: - CheckSectionSpacing(filename, clean_lines, classinfo, linenum, error) - - -_RE_PATTERN_INCLUDE = re.compile(r'^\s*#\s*include\s*([<"])([^>"]*)[>"].*$') -# Matches the first component of a filename delimited by -s and _s. That is: -# _RE_FIRST_COMPONENT.match('foo').group(0) == 'foo' -# _RE_FIRST_COMPONENT.match('foo.cc').group(0) == 'foo' -# _RE_FIRST_COMPONENT.match('foo-bar_baz.cc').group(0) == 'foo' -# _RE_FIRST_COMPONENT.match('foo_bar-baz.cc').group(0) == 'foo' -_RE_FIRST_COMPONENT = re.compile(r'^[^-_.]+') - - -def _DropCommonSuffixes(filename): - """Drops common suffixes like _test.cc or -inl.h from filename. - - For example: - >>> _DropCommonSuffixes('foo/foo-inl.h') - 'foo/foo' - >>> _DropCommonSuffixes('foo/bar/foo.cc') - 'foo/bar/foo' - >>> _DropCommonSuffixes('foo/foo_internal.h') - 'foo/foo' - >>> _DropCommonSuffixes('foo/foo_unusualinternal.h') - 'foo/foo_unusualinternal' - - Args: - filename: The input filename. - - Returns: - The filename with the common suffix removed. - """ - for suffix in itertools.chain( - ('%s.%s' % (test_suffix.lstrip('_'), ext) - for test_suffix, ext in itertools.product(_test_suffixes, GetNonHeaderExtensions())), - ('%s.%s' % (suffix, ext) - for suffix, ext in itertools.product(['inl', 'imp', 'internal'], GetHeaderExtensions()))): - if (filename.endswith(suffix) and len(filename) > len(suffix) and - filename[-len(suffix) - 1] in ('-', '_')): - return filename[:-len(suffix) - 1] - return os.path.splitext(filename)[0] - - -def _ClassifyInclude(fileinfo, include, used_angle_brackets, include_order="default"): - """Figures out what kind of header 'include' is. - - Args: - fileinfo: The current file cpplint is running over. A FileInfo instance. - include: The path to a #included file. - used_angle_brackets: True if the #include used <> rather than "". - include_order: "default" or other value allowed in program arguments - - Returns: - One of the _XXX_HEADER constants. - - For example: - >>> _ClassifyInclude(FileInfo('foo/foo.cc'), 'stdio.h', True) - _C_SYS_HEADER - >>> _ClassifyInclude(FileInfo('foo/foo.cc'), 'string', True) - _CPP_SYS_HEADER - >>> _ClassifyInclude(FileInfo('foo/foo.cc'), 'foo/foo.h', True, "standardcfirst") - _OTHER_SYS_HEADER - >>> _ClassifyInclude(FileInfo('foo/foo.cc'), 'foo/foo.h', False) - _LIKELY_MY_HEADER - >>> _ClassifyInclude(FileInfo('foo/foo_unknown_extension.cc'), - ... 'bar/foo_other_ext.h', False) - _POSSIBLE_MY_HEADER - >>> _ClassifyInclude(FileInfo('foo/foo.cc'), 'foo/bar.h', False) - _OTHER_HEADER - """ - # This is a list of all standard c++ header files, except - # those already checked for above. - is_cpp_header = include in _CPP_HEADERS - - # Mark include as C header if in list or in a known folder for standard-ish C headers. - is_std_c_header = (include_order == "default") or (include in _C_HEADERS - # additional linux glibc header folders - or Search(r'(?:%s)\/.*\.h' % "|".join(C_STANDARD_HEADER_FOLDERS), include)) - - # Headers with C++ extensions shouldn't be considered C system headers - is_system = used_angle_brackets and not os.path.splitext(include)[1] in ['.hpp', '.hxx', '.h++'] - - if is_system: - if is_cpp_header: - return _CPP_SYS_HEADER - if is_std_c_header: - return _C_SYS_HEADER - else: - return _OTHER_SYS_HEADER - - # If the target file and the include we're checking share a - # basename when we drop common extensions, and the include - # lives in . , then it's likely to be owned by the target file. - target_dir, target_base = ( - os.path.split(_DropCommonSuffixes(fileinfo.RepositoryName()))) - include_dir, include_base = os.path.split(_DropCommonSuffixes(include)) - target_dir_pub = os.path.normpath(target_dir + '/../public') - target_dir_pub = target_dir_pub.replace('\\', '/') - if target_base == include_base and ( - include_dir == target_dir or - include_dir == target_dir_pub): - return _LIKELY_MY_HEADER - - # If the target and include share some initial basename - # component, it's possible the target is implementing the - # include, so it's allowed to be first, but we'll never - # complain if it's not there. - target_first_component = _RE_FIRST_COMPONENT.match(target_base) - include_first_component = _RE_FIRST_COMPONENT.match(include_base) - if (target_first_component and include_first_component and - target_first_component.group(0) == - include_first_component.group(0)): - return _POSSIBLE_MY_HEADER - - return _OTHER_HEADER - - - -def CheckIncludeLine(filename, clean_lines, linenum, include_state, error): - """Check rules that are applicable to #include lines. - - Strings on #include lines are NOT removed from elided line, to make - certain tasks easier. However, to prevent false positives, checks - applicable to #include lines in CheckLanguage must be put here. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - include_state: An _IncludeState instance in which the headers are inserted. - error: The function to call with any errors found. - """ - fileinfo = FileInfo(filename) - line = clean_lines.lines[linenum] - - # "include" should use the new style "foo/bar.h" instead of just "bar.h" - # Only do this check if the included header follows google naming - # conventions. If not, assume that it's a 3rd party API that - # requires special include conventions. - # - # We also make an exception for Lua headers, which follow google - # naming convention but not the include convention. - match = Match(r'#include\s*"([^/]+\.h)"', line) - if match and not _THIRD_PARTY_HEADERS_PATTERN.match(match.group(1)): - error(filename, linenum, 'build/include_subdir', 4, - 'Include the directory when naming .h files') - - # we shouldn't include a file more than once. actually, there are a - # handful of instances where doing so is okay, but in general it's - # not. - match = _RE_PATTERN_INCLUDE.search(line) - if match: - include = match.group(2) - used_angle_brackets = (match.group(1) == '<') - duplicate_line = include_state.FindHeader(include) - if duplicate_line >= 0: - error(filename, linenum, 'build/include', 4, - '"%s" already included at %s:%s' % - (include, filename, duplicate_line)) - return - - for extension in GetNonHeaderExtensions(): - if (include.endswith('.' + extension) and - os.path.dirname(fileinfo.RepositoryName()) != os.path.dirname(include)): - error(filename, linenum, 'build/include', 4, - 'Do not include .' + extension + ' files from other packages') - return - - # We DO want to include a 3rd party looking header if it matches the - # filename. Otherwise we get an erroneous error "...should include its - # header" error later. - third_src_header = False - for ext in GetHeaderExtensions(): - basefilename = filename[0:len(filename) - len(fileinfo.Extension())] - headerfile = basefilename + '.' + ext - headername = FileInfo(headerfile).RepositoryName() - if headername in include or include in headername: - third_src_header = True - break - - if third_src_header or not _THIRD_PARTY_HEADERS_PATTERN.match(include): - include_state.include_list[-1].append((include, linenum)) - - # We want to ensure that headers appear in the right order: - # 1) for foo.cc, foo.h (preferred location) - # 2) c system files - # 3) cpp system files - # 4) for foo.cc, foo.h (deprecated location) - # 5) other google headers - # - # We classify each include statement as one of those 5 types - # using a number of techniques. The include_state object keeps - # track of the highest type seen, and complains if we see a - # lower type after that. - error_message = include_state.CheckNextIncludeOrder( - _ClassifyInclude(fileinfo, include, used_angle_brackets, _include_order)) - if error_message: - error(filename, linenum, 'build/include_order', 4, - '%s. Should be: %s.h, c system, c++ system, other.' % - (error_message, fileinfo.BaseName())) - canonical_include = include_state.CanonicalizeAlphabeticalOrder(include) - if not include_state.IsInAlphabeticalOrder( - clean_lines, linenum, canonical_include): - error(filename, linenum, 'build/include_alpha', 4, - 'Include "%s" not in alphabetical order' % include) - include_state.SetLastHeader(canonical_include) - - - -def _GetTextInside(text, start_pattern): - r"""Retrieves all the text between matching open and close parentheses. - - Given a string of lines and a regular expression string, retrieve all the text - following the expression and between opening punctuation symbols like - (, [, or {, and the matching close-punctuation symbol. This properly nested - occurrences of the punctuations, so for the text like - printf(a(), b(c())); - a call to _GetTextInside(text, r'printf\(') will return 'a(), b(c())'. - start_pattern must match string having an open punctuation symbol at the end. - - Args: - text: The lines to extract text. Its comments and strings must be elided. - It can be single line and can span multiple lines. - start_pattern: The regexp string indicating where to start extracting - the text. - Returns: - The extracted text. - None if either the opening string or ending punctuation could not be found. - """ - # TODO(unknown): Audit cpplint.py to see what places could be profitably - # rewritten to use _GetTextInside (and use inferior regexp matching today). - - # Give opening punctuations to get the matching close-punctuations. - matching_punctuation = {'(': ')', '{': '}', '[': ']'} - closing_punctuation = set(itervalues(matching_punctuation)) - - # Find the position to start extracting text. - match = re.search(start_pattern, text, re.M) - if not match: # start_pattern not found in text. - return None - start_position = match.end(0) - - assert start_position > 0, ( - 'start_pattern must ends with an opening punctuation.') - assert text[start_position - 1] in matching_punctuation, ( - 'start_pattern must ends with an opening punctuation.') - # Stack of closing punctuations we expect to have in text after position. - punctuation_stack = [matching_punctuation[text[start_position - 1]]] - position = start_position - while punctuation_stack and position < len(text): - if text[position] == punctuation_stack[-1]: - punctuation_stack.pop() - elif text[position] in closing_punctuation: - # A closing punctuation without matching opening punctuations. - return None - elif text[position] in matching_punctuation: - punctuation_stack.append(matching_punctuation[text[position]]) - position += 1 - if punctuation_stack: - # Opening punctuations left without matching close-punctuations. - return None - # punctuations match. - return text[start_position:position - 1] - - -# Patterns for matching call-by-reference parameters. -# -# Supports nested templates up to 2 levels deep using this messy pattern: -# < (?: < (?: < [^<>]* -# > -# | [^<>] )* -# > -# | [^<>] )* -# > -_RE_PATTERN_IDENT = r'[_a-zA-Z]\w*' # =~ [[:alpha:]][[:alnum:]]* -_RE_PATTERN_TYPE = ( - r'(?:const\s+)?(?:typename\s+|class\s+|struct\s+|union\s+|enum\s+)?' - r'(?:\w|' - r'\s*<(?:<(?:<[^<>]*>|[^<>])*>|[^<>])*>|' - r'::)+') -# A call-by-reference parameter ends with '& identifier'. -_RE_PATTERN_REF_PARAM = re.compile( - r'(' + _RE_PATTERN_TYPE + r'(?:\s*(?:\bconst\b|[*]))*\s*' - r'&\s*' + _RE_PATTERN_IDENT + r')\s*(?:=[^,()]+)?[,)]') -# A call-by-const-reference parameter either ends with 'const& identifier' -# or looks like 'const type& identifier' when 'type' is atomic. -_RE_PATTERN_CONST_REF_PARAM = ( - r'(?:.*\s*\bconst\s*&\s*' + _RE_PATTERN_IDENT + - r'|const\s+' + _RE_PATTERN_TYPE + r'\s*&\s*' + _RE_PATTERN_IDENT + r')') -# Stream types. -_RE_PATTERN_REF_STREAM_PARAM = ( - r'(?:.*stream\s*&\s*' + _RE_PATTERN_IDENT + r')') - - -def CheckLanguage(filename, clean_lines, linenum, file_extension, - include_state, nesting_state, error): - """Checks rules from the 'C++ language rules' section of cppguide.html. - - Some of these rules are hard to test (function overloading, using - uint32 inappropriately), but we do the best we can. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - file_extension: The extension (without the dot) of the filename. - include_state: An _IncludeState instance in which the headers are inserted. - nesting_state: A NestingState instance which maintains information about - the current stack of nested blocks being parsed. - error: The function to call with any errors found. - """ - # If the line is empty or consists of entirely a comment, no need to - # check it. - line = clean_lines.elided[linenum] - if not line: - return - - match = _RE_PATTERN_INCLUDE.search(line) - if match: - CheckIncludeLine(filename, clean_lines, linenum, include_state, error) - return - - # Reset include state across preprocessor directives. This is meant - # to silence warnings for conditional includes. - match = Match(r'^\s*#\s*(if|ifdef|ifndef|elif|else|endif)\b', line) - if match: - include_state.ResetSection(match.group(1)) - - - # Perform other checks now that we are sure that this is not an include line - CheckCasts(filename, clean_lines, linenum, error) - CheckGlobalStatic(filename, clean_lines, linenum, error) - CheckPrintf(filename, clean_lines, linenum, error) - - if IsHeaderExtension(file_extension): - # TODO(unknown): check that 1-arg constructors are explicit. - # How to tell it's a constructor? - # (handled in CheckForNonStandardConstructs for now) - # TODO(unknown): check that classes declare or disable copy/assign - # (level 1 error) - pass - - # Check if people are using the verboten C basic types. The only exception - # we regularly allow is "unsigned short port" for port. - if Search(r'\bshort port\b', line): - if not Search(r'\bunsigned short port\b', line): - error(filename, linenum, 'runtime/int', 4, - 'Use "unsigned short" for ports, not "short"') - else: - match = Search(r'\b(short|long(?! +double)|long long)\b', line) - if match: - error(filename, linenum, 'runtime/int', 4, - 'Use int16/int64/etc, rather than the C type %s' % match.group(1)) - - # Check if some verboten operator overloading is going on - # TODO(unknown): catch out-of-line unary operator&: - # class X {}; - # int operator&(const X& x) { return 42; } // unary operator& - # The trick is it's hard to tell apart from binary operator&: - # class Y { int operator&(const Y& x) { return 23; } }; // binary operator& - if Search(r'\boperator\s*&\s*\(\s*\)', line): - error(filename, linenum, 'runtime/operator', 4, - 'Unary operator& is dangerous. Do not use it.') - - # Check for suspicious usage of "if" like - # } if (a == b) { - if Search(r'\}\s*if\s*\(', line): - error(filename, linenum, 'readability/braces', 4, - 'Did you mean "else if"? If not, start a new line for "if".') - - # Check for potential format string bugs like printf(foo). - # We constrain the pattern not to pick things like DocidForPrintf(foo). - # Not perfect but it can catch printf(foo.c_str()) and printf(foo->c_str()) - # TODO(unknown): Catch the following case. Need to change the calling - # convention of the whole function to process multiple line to handle it. - # printf( - # boy_this_is_a_really_long_variable_that_cannot_fit_on_the_prev_line); - printf_args = _GetTextInside(line, r'(?i)\b(string)?printf\s*\(') - if printf_args: - match = Match(r'([\w.\->()]+)$', printf_args) - if match and match.group(1) != '__VA_ARGS__': - function_name = re.search(r'\b((?:string)?printf)\s*\(', - line, re.I).group(1) - error(filename, linenum, 'runtime/printf', 4, - 'Potential format string bug. Do %s("%%s", %s) instead.' - % (function_name, match.group(1))) - - # Check for potential memset bugs like memset(buf, sizeof(buf), 0). - match = Search(r'memset\s*\(([^,]*),\s*([^,]*),\s*0\s*\)', line) - if match and not Match(r"^''|-?[0-9]+|0x[0-9A-Fa-f]$", match.group(2)): - error(filename, linenum, 'runtime/memset', 4, - 'Did you mean "memset(%s, 0, %s)"?' - % (match.group(1), match.group(2))) - - if Search(r'\busing namespace\b', line): - if Search(r'\bliterals\b', line): - error(filename, linenum, 'build/namespaces_literals', 5, - 'Do not use namespace using-directives. ' - 'Use using-declarations instead.') - else: - error(filename, linenum, 'build/namespaces', 5, - 'Do not use namespace using-directives. ' - 'Use using-declarations instead.') - - # Detect variable-length arrays. - match = Match(r'\s*(.+::)?(\w+) [a-z]\w*\[(.+)];', line) - if (match and match.group(2) != 'return' and match.group(2) != 'delete' and - match.group(3).find(']') == -1): - # Split the size using space and arithmetic operators as delimiters. - # If any of the resulting tokens are not compile time constants then - # report the error. - tokens = re.split(r'\s|\+|\-|\*|\/|<<|>>]', match.group(3)) - is_const = True - skip_next = False - for tok in tokens: - if skip_next: - skip_next = False - continue - - if Search(r'sizeof\(.+\)', tok): continue - if Search(r'arraysize\(\w+\)', tok): continue - - tok = tok.lstrip('(') - tok = tok.rstrip(')') - if not tok: continue - if Match(r'\d+', tok): continue - if Match(r'0[xX][0-9a-fA-F]+', tok): continue - if Match(r'k[A-Z0-9]\w*', tok): continue - if Match(r'(.+::)?k[A-Z0-9]\w*', tok): continue - if Match(r'(.+::)?[A-Z][A-Z0-9_]*', tok): continue - # A catch all for tricky sizeof cases, including 'sizeof expression', - # 'sizeof(*type)', 'sizeof(const type)', 'sizeof(struct StructName)' - # requires skipping the next token because we split on ' ' and '*'. - if tok.startswith('sizeof'): - skip_next = True - continue - is_const = False - break - if not is_const: - error(filename, linenum, 'runtime/arrays', 1, - 'Do not use variable-length arrays. Use an appropriately named ' - "('k' followed by CamelCase) compile-time constant for the size.") - - # Check for use of unnamed namespaces in header files. Registration - # macros are typically OK, so we allow use of "namespace {" on lines - # that end with backslashes. - if (IsHeaderExtension(file_extension) - and Search(r'\bnamespace\s*{', line) - and line[-1] != '\\'): - error(filename, linenum, 'build/namespaces_headers', 4, - 'Do not use unnamed namespaces in header files. See ' - 'https://google-styleguide.googlecode.com/svn/trunk/cppguide.xml#Namespaces' - ' for more information.') - - -def CheckGlobalStatic(filename, clean_lines, linenum, error): - """Check for unsafe global or static objects. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # Match two lines at a time to support multiline declarations - if linenum + 1 < clean_lines.NumLines() and not Search(r'[;({]', line): - line += clean_lines.elided[linenum + 1].strip() - - # Check for people declaring static/global STL strings at the top level. - # This is dangerous because the C++ language does not guarantee that - # globals with constructors are initialized before the first access, and - # also because globals can be destroyed when some threads are still running. - # TODO(unknown): Generalize this to also find static unique_ptr instances. - # TODO(unknown): File bugs for clang-tidy to find these. - match = Match( - r'((?:|static +)(?:|const +))(?::*std::)?string( +const)? +' - r'([a-zA-Z0-9_:]+)\b(.*)', - line) - - # Remove false positives: - # - String pointers (as opposed to values). - # string *pointer - # const string *pointer - # string const *pointer - # string *const pointer - # - # - Functions and template specializations. - # string Function(... - # string Class::Method(... - # - # - Operators. These are matched separately because operator names - # cross non-word boundaries, and trying to match both operators - # and functions at the same time would decrease accuracy of - # matching identifiers. - # string Class::operator*() - if (match and - not Search(r'\bstring\b(\s+const)?\s*[\*\&]\s*(const\s+)?\w', line) and - not Search(r'\boperator\W', line) and - not Match(r'\s*(<.*>)?(::[a-zA-Z0-9_]+)*\s*\(([^"]|$)', match.group(4))): - if Search(r'\bconst\b', line): - error(filename, linenum, 'runtime/string', 4, - 'For a static/global string constant, use a C style string ' - 'instead: "%schar%s %s[]".' % - (match.group(1), match.group(2) or '', match.group(3))) - else: - error(filename, linenum, 'runtime/string', 4, - 'Static/global string variables are not permitted.') - - if (Search(r'\b([A-Za-z0-9_]*_)\(\1\)', line) or - Search(r'\b([A-Za-z0-9_]*_)\(CHECK_NOTNULL\(\1\)\)', line)): - error(filename, linenum, 'runtime/init', 4, - 'You seem to be initializing a member variable with itself.') - - -def CheckPrintf(filename, clean_lines, linenum, error): - """Check for printf related issues. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # When snprintf is used, the second argument shouldn't be a literal. - match = Search(r'snprintf\s*\(([^,]*),\s*([0-9]*)\s*,', line) - if match and match.group(2) != '0': - # If 2nd arg is zero, snprintf is used to calculate size. - error(filename, linenum, 'runtime/printf', 3, - 'If you can, use sizeof(%s) instead of %s as the 2nd arg ' - 'to snprintf.' % (match.group(1), match.group(2))) - - # Check if some verboten C functions are being used. - if Search(r'\bsprintf\s*\(', line): - error(filename, linenum, 'runtime/printf', 5, - 'Never use sprintf. Use snprintf instead.') - match = Search(r'\b(strcpy|strcat)\s*\(', line) - if match: - error(filename, linenum, 'runtime/printf', 4, - 'Almost always, snprintf is better than %s' % match.group(1)) - - -def IsDerivedFunction(clean_lines, linenum): - """Check if current line contains an inherited function. - - Args: - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - Returns: - True if current line contains a function with "override" - virt-specifier. - """ - # Scan back a few lines for start of current function - for i in xrange(linenum, max(-1, linenum - 10), -1): - match = Match(r'^([^()]*\w+)\(', clean_lines.elided[i]) - if match: - # Look for "override" after the matching closing parenthesis - line, _, closing_paren = CloseExpression( - clean_lines, i, len(match.group(1))) - return (closing_paren >= 0 and - Search(r'\boverride\b', line[closing_paren:])) - return False - - -def IsOutOfLineMethodDefinition(clean_lines, linenum): - """Check if current line contains an out-of-line method definition. - - Args: - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - Returns: - True if current line contains an out-of-line method definition. - """ - # Scan back a few lines for start of current function - for i in xrange(linenum, max(-1, linenum - 10), -1): - if Match(r'^([^()]*\w+)\(', clean_lines.elided[i]): - return Match(r'^[^()]*\w+::\w+\(', clean_lines.elided[i]) is not None - return False - - -def IsInitializerList(clean_lines, linenum): - """Check if current line is inside constructor initializer list. - - Args: - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - Returns: - True if current line appears to be inside constructor initializer - list, False otherwise. - """ - for i in xrange(linenum, 1, -1): - line = clean_lines.elided[i] - if i == linenum: - remove_function_body = Match(r'^(.*)\{\s*$', line) - if remove_function_body: - line = remove_function_body.group(1) - - if Search(r'\s:\s*\w+[({]', line): - # A lone colon tend to indicate the start of a constructor - # initializer list. It could also be a ternary operator, which - # also tend to appear in constructor initializer lists as - # opposed to parameter lists. - return True - if Search(r'\}\s*,\s*$', line): - # A closing brace followed by a comma is probably the end of a - # brace-initialized member in constructor initializer list. - return True - if Search(r'[{};]\s*$', line): - # Found one of the following: - # - A closing brace or semicolon, probably the end of the previous - # function. - # - An opening brace, probably the start of current class or namespace. - # - # Current line is probably not inside an initializer list since - # we saw one of those things without seeing the starting colon. - return False - - # Got to the beginning of the file without seeing the start of - # constructor initializer list. - return False - - -def CheckForNonConstReference(filename, clean_lines, linenum, - nesting_state, error): - """Check for non-const references. - - Separate from CheckLanguage since it scans backwards from current - line, instead of scanning forward. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - nesting_state: A NestingState instance which maintains information about - the current stack of nested blocks being parsed. - error: The function to call with any errors found. - """ - # Do nothing if there is no '&' on current line. - line = clean_lines.elided[linenum] - if '&' not in line: - return - - # If a function is inherited, current function doesn't have much of - # a choice, so any non-const references should not be blamed on - # derived function. - if IsDerivedFunction(clean_lines, linenum): - return - - # Don't warn on out-of-line method definitions, as we would warn on the - # in-line declaration, if it isn't marked with 'override'. - if IsOutOfLineMethodDefinition(clean_lines, linenum): - return - - # Long type names may be broken across multiple lines, usually in one - # of these forms: - # LongType - # ::LongTypeContinued &identifier - # LongType:: - # LongTypeContinued &identifier - # LongType< - # ...>::LongTypeContinued &identifier - # - # If we detected a type split across two lines, join the previous - # line to current line so that we can match const references - # accordingly. - # - # Note that this only scans back one line, since scanning back - # arbitrary number of lines would be expensive. If you have a type - # that spans more than 2 lines, please use a typedef. - if linenum > 1: - previous = None - if Match(r'\s*::(?:[\w<>]|::)+\s*&\s*\S', line): - # previous_line\n + ::current_line - previous = Search(r'\b((?:const\s*)?(?:[\w<>]|::)+[\w<>])\s*$', - clean_lines.elided[linenum - 1]) - elif Match(r'\s*[a-zA-Z_]([\w<>]|::)+\s*&\s*\S', line): - # previous_line::\n + current_line - previous = Search(r'\b((?:const\s*)?(?:[\w<>]|::)+::)\s*$', - clean_lines.elided[linenum - 1]) - if previous: - line = previous.group(1) + line.lstrip() - else: - # Check for templated parameter that is split across multiple lines - endpos = line.rfind('>') - if endpos > -1: - (_, startline, startpos) = ReverseCloseExpression( - clean_lines, linenum, endpos) - if startpos > -1 and startline < linenum: - # Found the matching < on an earlier line, collect all - # pieces up to current line. - line = '' - for i in xrange(startline, linenum + 1): - line += clean_lines.elided[i].strip() - - # Check for non-const references in function parameters. A single '&' may - # found in the following places: - # inside expression: binary & for bitwise AND - # inside expression: unary & for taking the address of something - # inside declarators: reference parameter - # We will exclude the first two cases by checking that we are not inside a - # function body, including one that was just introduced by a trailing '{'. - # TODO(unknown): Doesn't account for 'catch(Exception& e)' [rare]. - if (nesting_state.previous_stack_top and - not (isinstance(nesting_state.previous_stack_top, _ClassInfo) or - isinstance(nesting_state.previous_stack_top, _NamespaceInfo))): - # Not at toplevel, not within a class, and not within a namespace - return - - # Avoid initializer lists. We only need to scan back from the - # current line for something that starts with ':'. - # - # We don't need to check the current line, since the '&' would - # appear inside the second set of parentheses on the current line as - # opposed to the first set. - if linenum > 0: - for i in xrange(linenum - 1, max(0, linenum - 10), -1): - previous_line = clean_lines.elided[i] - if not Search(r'[),]\s*$', previous_line): - break - if Match(r'^\s*:\s+\S', previous_line): - return - - # Avoid preprocessors - if Search(r'\\\s*$', line): - return - - # Avoid constructor initializer lists - if IsInitializerList(clean_lines, linenum): - return - - # We allow non-const references in a few standard places, like functions - # called "swap()" or iostream operators like "<<" or ">>". Do not check - # those function parameters. - # - # We also accept & in static_assert, which looks like a function but - # it's actually a declaration expression. - allowed_functions = (r'(?:[sS]wap(?:<\w:+>)?|' - r'operator\s*[<>][<>]|' - r'static_assert|COMPILE_ASSERT' - r')\s*\(') - if Search(allowed_functions, line): - return - elif not Search(r'\S+\([^)]*$', line): - # Don't see an allowed function on this line. Actually we - # didn't see any function name on this line, so this is likely a - # multi-line parameter list. Try a bit harder to catch this case. - for i in xrange(2): - if (linenum > i and - Search(allowed_functions, clean_lines.elided[linenum - i - 1])): - return - - decls = ReplaceAll(r'{[^}]*}', ' ', line) # exclude function body - for parameter in re.findall(_RE_PATTERN_REF_PARAM, decls): - if (not Match(_RE_PATTERN_CONST_REF_PARAM, parameter) and - not Match(_RE_PATTERN_REF_STREAM_PARAM, parameter)): - error(filename, linenum, 'runtime/references', 2, - 'Is this a non-const reference? ' - 'If so, make const or use a pointer: ' + - ReplaceAll(' *<', '<', parameter)) - - -def CheckCasts(filename, clean_lines, linenum, error): - """Various cast related checks. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - # Check to see if they're using an conversion function cast. - # I just try to capture the most common basic types, though there are more. - # Parameterless conversion functions, such as bool(), are allowed as they are - # probably a member operator declaration or default constructor. - match = Search( - r'(\bnew\s+(?:const\s+)?|\S<\s*(?:const\s+)?)?\b' - r'(int|float|double|bool|char|int32|uint32|int64|uint64)' - r'(\([^)].*)', line) - expecting_function = ExpectingFunctionArgs(clean_lines, linenum) - if match and not expecting_function: - matched_type = match.group(2) - - # matched_new_or_template is used to silence two false positives: - # - New operators - # - Template arguments with function types - # - # For template arguments, we match on types immediately following - # an opening bracket without any spaces. This is a fast way to - # silence the common case where the function type is the first - # template argument. False negative with less-than comparison is - # avoided because those operators are usually followed by a space. - # - # function // bracket + no space = false positive - # value < double(42) // bracket + space = true positive - matched_new_or_template = match.group(1) - - # Avoid arrays by looking for brackets that come after the closing - # parenthesis. - if Match(r'\([^()]+\)\s*\[', match.group(3)): - return - - # Other things to ignore: - # - Function pointers - # - Casts to pointer types - # - Placement new - # - Alias declarations - matched_funcptr = match.group(3) - if (matched_new_or_template is None and - not (matched_funcptr and - (Match(r'\((?:[^() ]+::\s*\*\s*)?[^() ]+\)\s*\(', - matched_funcptr) or - matched_funcptr.startswith('(*)'))) and - not Match(r'\s*using\s+\S+\s*=\s*' + matched_type, line) and - not Search(r'new\(\S+\)\s*' + matched_type, line)): - error(filename, linenum, 'readability/casting', 4, - 'Using deprecated casting style. ' - 'Use static_cast<%s>(...) instead' % - matched_type) - - if not expecting_function: - CheckCStyleCast(filename, clean_lines, linenum, 'static_cast', - r'\((int|float|double|bool|char|u?int(16|32|64))\)', error) - - # This doesn't catch all cases. Consider (const char * const)"hello". - # - # (char *) "foo" should always be a const_cast (reinterpret_cast won't - # compile). - if CheckCStyleCast(filename, clean_lines, linenum, 'const_cast', - r'\((char\s?\*+\s?)\)\s*"', error): - pass - else: - # Check pointer casts for other than string constants - CheckCStyleCast(filename, clean_lines, linenum, 'reinterpret_cast', - r'\((\w+\s?\*+\s?)\)', error) - - # In addition, we look for people taking the address of a cast. This - # is dangerous -- casts can assign to temporaries, so the pointer doesn't - # point where you think. - # - # Some non-identifier character is required before the '&' for the - # expression to be recognized as a cast. These are casts: - # expression = &static_cast(temporary()); - # function(&(int*)(temporary())); - # - # This is not a cast: - # reference_type&(int* function_param); - match = Search( - r'(?:[^\w]&\(([^)*][^)]*)\)[\w(])|' - r'(?:[^\w]&(static|dynamic|down|reinterpret)_cast\b)', line) - if match: - # Try a better error message when the & is bound to something - # dereferenced by the casted pointer, as opposed to the casted - # pointer itself. - parenthesis_error = False - match = Match(r'^(.*&(?:static|dynamic|down|reinterpret)_cast\b)<', line) - if match: - _, y1, x1 = CloseExpression(clean_lines, linenum, len(match.group(1))) - if x1 >= 0 and clean_lines.elided[y1][x1] == '(': - _, y2, x2 = CloseExpression(clean_lines, y1, x1) - if x2 >= 0: - extended_line = clean_lines.elided[y2][x2:] - if y2 < clean_lines.NumLines() - 1: - extended_line += clean_lines.elided[y2 + 1] - if Match(r'\s*(?:->|\[)', extended_line): - parenthesis_error = True - - if parenthesis_error: - error(filename, linenum, 'readability/casting', 4, - ('Are you taking an address of something dereferenced ' - 'from a cast? Wrapping the dereferenced expression in ' - 'parentheses will make the binding more obvious')) - else: - error(filename, linenum, 'runtime/casting', 4, - ('Are you taking an address of a cast? ' - 'This is dangerous: could be a temp var. ' - 'Take the address before doing the cast, rather than after')) - - -def CheckCStyleCast(filename, clean_lines, linenum, cast_type, pattern, error): - """Checks for a C-style cast by looking for the pattern. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - cast_type: The string for the C++ cast to recommend. This is either - reinterpret_cast, static_cast, or const_cast, depending. - pattern: The regular expression used to find C-style casts. - error: The function to call with any errors found. - - Returns: - True if an error was emitted. - False otherwise. - """ - line = clean_lines.elided[linenum] - match = Search(pattern, line) - if not match: - return False - - # Exclude lines with keywords that tend to look like casts - context = line[0:match.start(1) - 1] - if Match(r'.*\b(?:sizeof|alignof|alignas|[_A-Z][_A-Z0-9]*)\s*$', context): - return False - - # Try expanding current context to see if we one level of - # parentheses inside a macro. - if linenum > 0: - for i in xrange(linenum - 1, max(0, linenum - 5), -1): - context = clean_lines.elided[i] + context - if Match(r'.*\b[_A-Z][_A-Z0-9]*\s*\((?:\([^()]*\)|[^()])*$', context): - return False - - # operator++(int) and operator--(int) - if context.endswith(' operator++') or context.endswith(' operator--'): - return False - - # A single unnamed argument for a function tends to look like old style cast. - # If we see those, don't issue warnings for deprecated casts. - remainder = line[match.end(0):] - if Match(r'^\s*(?:;|const\b|throw\b|final\b|override\b|[=>{),]|->)', - remainder): - return False - - # At this point, all that should be left is actual casts. - error(filename, linenum, 'readability/casting', 4, - 'Using C-style cast. Use %s<%s>(...) instead' % - (cast_type, match.group(1))) - - return True - - -def ExpectingFunctionArgs(clean_lines, linenum): - """Checks whether where function type arguments are expected. - - Args: - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - - Returns: - True if the line at 'linenum' is inside something that expects arguments - of function types. - """ - line = clean_lines.elided[linenum] - return (Match(r'^\s*MOCK_(CONST_)?METHOD\d+(_T)?\(', line) or - (linenum >= 2 and - (Match(r'^\s*MOCK_(?:CONST_)?METHOD\d+(?:_T)?\((?:\S+,)?\s*$', - clean_lines.elided[linenum - 1]) or - Match(r'^\s*MOCK_(?:CONST_)?METHOD\d+(?:_T)?\(\s*$', - clean_lines.elided[linenum - 2]) or - Search(r'\bstd::m?function\s*\<\s*$', - clean_lines.elided[linenum - 1])))) - - -_HEADERS_CONTAINING_TEMPLATES = ( - ('', ('deque',)), - ('', ('unary_function', 'binary_function', - 'plus', 'minus', 'multiplies', 'divides', 'modulus', - 'negate', - 'equal_to', 'not_equal_to', 'greater', 'less', - 'greater_equal', 'less_equal', - 'logical_and', 'logical_or', 'logical_not', - 'unary_negate', 'not1', 'binary_negate', 'not2', - 'bind1st', 'bind2nd', - 'pointer_to_unary_function', - 'pointer_to_binary_function', - 'ptr_fun', - 'mem_fun_t', 'mem_fun', 'mem_fun1_t', 'mem_fun1_ref_t', - 'mem_fun_ref_t', - 'const_mem_fun_t', 'const_mem_fun1_t', - 'const_mem_fun_ref_t', 'const_mem_fun1_ref_t', - 'mem_fun_ref', - )), - ('', ('numeric_limits',)), - ('', ('list',)), - ('', ('multimap',)), - ('', ('allocator', 'make_shared', 'make_unique', 'shared_ptr', - 'unique_ptr', 'weak_ptr')), - ('', ('queue', 'priority_queue',)), - ('', ('multiset',)), - ('', ('stack',)), - ('', ('char_traits', 'basic_string',)), - ('', ('tuple',)), - ('', ('unordered_map', 'unordered_multimap')), - ('', ('unordered_set', 'unordered_multiset')), - ('', ('pair',)), - ('', ('vector',)), - - # gcc extensions. - # Note: std::hash is their hash, ::hash is our hash - ('', ('hash_map', 'hash_multimap',)), - ('', ('hash_set', 'hash_multiset',)), - ('', ('slist',)), - ) - -_HEADERS_MAYBE_TEMPLATES = ( - ('', ('copy', 'max', 'min', 'min_element', 'sort', - 'transform', - )), - ('', ('forward', 'make_pair', 'move', 'swap')), - ) - -_RE_PATTERN_STRING = re.compile(r'\bstring\b') - -_re_pattern_headers_maybe_templates = [] -for _header, _templates in _HEADERS_MAYBE_TEMPLATES: - for _template in _templates: - # Match max(..., ...), max(..., ...), but not foo->max, foo.max or - # 'type::max()'. - _re_pattern_headers_maybe_templates.append( - (re.compile(r'[^>.]\b' + _template + r'(<.*?>)?\([^\)]'), - _template, - _header)) -# Match set, but not foo->set, foo.set -_re_pattern_headers_maybe_templates.append( - (re.compile(r'[^>.]\bset\s*\<'), - 'set<>', - '')) -# Match 'map var' and 'std::map(...)', but not 'map(...)'' -_re_pattern_headers_maybe_templates.append( - (re.compile(r'(std\b::\bmap\s*\<)|(^(std\b::\b)map\b\(\s*\<)'), - 'map<>', - '')) - -# Other scripts may reach in and modify this pattern. -_re_pattern_templates = [] -for _header, _templates in _HEADERS_CONTAINING_TEMPLATES: - for _template in _templates: - _re_pattern_templates.append( - (re.compile(r'(\<|\b)' + _template + r'\s*\<'), - _template + '<>', - _header)) - - -def FilesBelongToSameModule(filename_cc, filename_h): - """Check if these two filenames belong to the same module. - - The concept of a 'module' here is a as follows: - foo.h, foo-inl.h, foo.cc, foo_test.cc and foo_unittest.cc belong to the - same 'module' if they are in the same directory. - some/path/public/xyzzy and some/path/internal/xyzzy are also considered - to belong to the same module here. - - If the filename_cc contains a longer path than the filename_h, for example, - '/absolute/path/to/base/sysinfo.cc', and this file would include - 'base/sysinfo.h', this function also produces the prefix needed to open the - header. This is used by the caller of this function to more robustly open the - header file. We don't have access to the real include paths in this context, - so we need this guesswork here. - - Known bugs: tools/base/bar.cc and base/bar.h belong to the same module - according to this implementation. Because of this, this function gives - some false positives. This should be sufficiently rare in practice. - - Args: - filename_cc: is the path for the source (e.g. .cc) file - filename_h: is the path for the header path - - Returns: - Tuple with a bool and a string: - bool: True if filename_cc and filename_h belong to the same module. - string: the additional prefix needed to open the header file. - """ - fileinfo_cc = FileInfo(filename_cc) - if not fileinfo_cc.Extension().lstrip('.') in GetNonHeaderExtensions(): - return (False, '') - - fileinfo_h = FileInfo(filename_h) - if not IsHeaderExtension(fileinfo_h.Extension().lstrip('.')): - return (False, '') - - filename_cc = filename_cc[:-(len(fileinfo_cc.Extension()))] - matched_test_suffix = Search(_TEST_FILE_SUFFIX, fileinfo_cc.BaseName()) - if matched_test_suffix: - filename_cc = filename_cc[:-len(matched_test_suffix.group(1))] - - filename_cc = filename_cc.replace('/public/', '/') - filename_cc = filename_cc.replace('/internal/', '/') - - filename_h = filename_h[:-(len(fileinfo_h.Extension()))] - if filename_h.endswith('-inl'): - filename_h = filename_h[:-len('-inl')] - filename_h = filename_h.replace('/public/', '/') - filename_h = filename_h.replace('/internal/', '/') - - files_belong_to_same_module = filename_cc.endswith(filename_h) - common_path = '' - if files_belong_to_same_module: - common_path = filename_cc[:-len(filename_h)] - return files_belong_to_same_module, common_path - - -def UpdateIncludeState(filename, include_dict, io=codecs): - """Fill up the include_dict with new includes found from the file. - - Args: - filename: the name of the header to read. - include_dict: a dictionary in which the headers are inserted. - io: The io factory to use to read the file. Provided for testability. - - Returns: - True if a header was successfully added. False otherwise. - """ - headerfile = None - try: - with io.open(filename, 'r', 'utf8', 'replace') as headerfile: - linenum = 0 - for line in headerfile: - linenum += 1 - clean_line = CleanseComments(line) - match = _RE_PATTERN_INCLUDE.search(clean_line) - if match: - include = match.group(2) - include_dict.setdefault(include, linenum) - return True - except IOError: - return False - - - -def CheckForIncludeWhatYouUse(filename, clean_lines, include_state, error, - io=codecs): - """Reports for missing stl includes. - - This function will output warnings to make sure you are including the headers - necessary for the stl containers and functions that you use. We only give one - reason to include a header. For example, if you use both equal_to<> and - less<> in a .h file, only one (the latter in the file) of these will be - reported as a reason to include the . - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - include_state: An _IncludeState instance. - error: The function to call with any errors found. - io: The IO factory to use to read the header file. Provided for unittest - injection. - """ - required = {} # A map of header name to linenumber and the template entity. - # Example of required: { '': (1219, 'less<>') } - - for linenum in xrange(clean_lines.NumLines()): - line = clean_lines.elided[linenum] - if not line or line[0] == '#': - continue - - # String is special -- it is a non-templatized type in STL. - matched = _RE_PATTERN_STRING.search(line) - if matched: - # Don't warn about strings in non-STL namespaces: - # (We check only the first match per line; good enough.) - prefix = line[:matched.start()] - if prefix.endswith('std::') or not prefix.endswith('::'): - required[''] = (linenum, 'string') - - for pattern, template, header in _re_pattern_headers_maybe_templates: - if pattern.search(line): - required[header] = (linenum, template) - - # The following function is just a speed up, no semantics are changed. - if not '<' in line: # Reduces the cpu time usage by skipping lines. - continue - - for pattern, template, header in _re_pattern_templates: - matched = pattern.search(line) - if matched: - # Don't warn about IWYU in non-STL namespaces: - # (We check only the first match per line; good enough.) - prefix = line[:matched.start()] - if prefix.endswith('std::') or not prefix.endswith('::'): - required[header] = (linenum, template) - - # The policy is that if you #include something in foo.h you don't need to - # include it again in foo.cc. Here, we will look at possible includes. - # Let's flatten the include_state include_list and copy it into a dictionary. - include_dict = dict([item for sublist in include_state.include_list - for item in sublist]) - - # Did we find the header for this file (if any) and successfully load it? - header_found = False - - # Use the absolute path so that matching works properly. - abs_filename = FileInfo(filename).FullName() - - # For Emacs's flymake. - # If cpplint is invoked from Emacs's flymake, a temporary file is generated - # by flymake and that file name might end with '_flymake.cc'. In that case, - # restore original file name here so that the corresponding header file can be - # found. - # e.g. If the file name is 'foo_flymake.cc', we should search for 'foo.h' - # instead of 'foo_flymake.h' - abs_filename = re.sub(r'_flymake\.cc$', '.cc', abs_filename) - - # include_dict is modified during iteration, so we iterate over a copy of - # the keys. - header_keys = list(include_dict.keys()) - for header in header_keys: - (same_module, common_path) = FilesBelongToSameModule(abs_filename, header) - fullpath = common_path + header - if same_module and UpdateIncludeState(fullpath, include_dict, io): - header_found = True - - # If we can't find the header file for a .cc, assume it's because we don't - # know where to look. In that case we'll give up as we're not sure they - # didn't include it in the .h file. - # TODO(unknown): Do a better job of finding .h files so we are confident that - # not having the .h file means there isn't one. - if not header_found: - for extension in GetNonHeaderExtensions(): - if filename.endswith('.' + extension): - return - - # All the lines have been processed, report the errors found. - for required_header_unstripped in sorted(required, key=required.__getitem__): - template = required[required_header_unstripped][1] - if required_header_unstripped.strip('<>"') not in include_dict: - error(filename, required[required_header_unstripped][0], - 'build/include_what_you_use', 4, - 'Add #include ' + required_header_unstripped + ' for ' + template) - - -_RE_PATTERN_EXPLICIT_MAKEPAIR = re.compile(r'\bmake_pair\s*<') - - -def CheckMakePairUsesDeduction(filename, clean_lines, linenum, error): - """Check that make_pair's template arguments are deduced. - - G++ 4.6 in C++11 mode fails badly if make_pair's template arguments are - specified explicitly, and such use isn't intended in any case. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - match = _RE_PATTERN_EXPLICIT_MAKEPAIR.search(line) - if match: - error(filename, linenum, 'build/explicit_make_pair', - 4, # 4 = high confidence - 'For C++11-compatibility, omit template arguments from make_pair' - ' OR use pair directly OR if appropriate, construct a pair directly') - - -def CheckRedundantVirtual(filename, clean_lines, linenum, error): - """Check if line contains a redundant "virtual" function-specifier. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - # Look for "virtual" on current line. - line = clean_lines.elided[linenum] - virtual = Match(r'^(.*)(\bvirtual\b)(.*)$', line) - if not virtual: return - - # Ignore "virtual" keywords that are near access-specifiers. These - # are only used in class base-specifier and do not apply to member - # functions. - if (Search(r'\b(public|protected|private)\s+$', virtual.group(1)) or - Match(r'^\s+(public|protected|private)\b', virtual.group(3))): - return - - # Ignore the "virtual" keyword from virtual base classes. Usually - # there is a column on the same line in these cases (virtual base - # classes are rare in google3 because multiple inheritance is rare). - if Match(r'^.*[^:]:[^:].*$', line): return - - # Look for the next opening parenthesis. This is the start of the - # parameter list (possibly on the next line shortly after virtual). - # TODO(unknown): doesn't work if there are virtual functions with - # decltype() or other things that use parentheses, but csearch suggests - # that this is rare. - end_col = -1 - end_line = -1 - start_col = len(virtual.group(2)) - for start_line in xrange(linenum, min(linenum + 3, clean_lines.NumLines())): - line = clean_lines.elided[start_line][start_col:] - parameter_list = Match(r'^([^(]*)\(', line) - if parameter_list: - # Match parentheses to find the end of the parameter list - (_, end_line, end_col) = CloseExpression( - clean_lines, start_line, start_col + len(parameter_list.group(1))) - break - start_col = 0 - - if end_col < 0: - return # Couldn't find end of parameter list, give up - - # Look for "override" or "final" after the parameter list - # (possibly on the next few lines). - for i in xrange(end_line, min(end_line + 3, clean_lines.NumLines())): - line = clean_lines.elided[i][end_col:] - match = Search(r'\b(override|final)\b', line) - if match: - error(filename, linenum, 'readability/inheritance', 4, - ('"virtual" is redundant since function is ' - 'already declared as "%s"' % match.group(1))) - - # Set end_col to check whole lines after we are done with the - # first line. - end_col = 0 - if Search(r'[^\w]\s*$', line): - break - - -def CheckRedundantOverrideOrFinal(filename, clean_lines, linenum, error): - """Check if line contains a redundant "override" or "final" virt-specifier. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - # Look for closing parenthesis nearby. We need one to confirm where - # the declarator ends and where the virt-specifier starts to avoid - # false positives. - line = clean_lines.elided[linenum] - declarator_end = line.rfind(')') - if declarator_end >= 0: - fragment = line[declarator_end:] - else: - if linenum > 1 and clean_lines.elided[linenum - 1].rfind(')') >= 0: - fragment = line - else: - return - - # Check that at most one of "override" or "final" is present, not both - if Search(r'\boverride\b', fragment) and Search(r'\bfinal\b', fragment): - error(filename, linenum, 'readability/inheritance', 4, - ('"override" is redundant since function is ' - 'already declared as "final"')) - - - - -# Returns true if we are at a new block, and it is directly -# inside of a namespace. -def IsBlockInNameSpace(nesting_state, is_forward_declaration): - """Checks that the new block is directly in a namespace. - - Args: - nesting_state: The _NestingState object that contains info about our state. - is_forward_declaration: If the class is a forward declared class. - Returns: - Whether or not the new block is directly in a namespace. - """ - if is_forward_declaration: - return len(nesting_state.stack) >= 1 and ( - isinstance(nesting_state.stack[-1], _NamespaceInfo)) - - - return (len(nesting_state.stack) > 1 and - nesting_state.stack[-1].check_namespace_indentation and - isinstance(nesting_state.stack[-2], _NamespaceInfo)) - - -def ShouldCheckNamespaceIndentation(nesting_state, is_namespace_indent_item, - raw_lines_no_comments, linenum): - """This method determines if we should apply our namespace indentation check. - - Args: - nesting_state: The current nesting state. - is_namespace_indent_item: If we just put a new class on the stack, True. - If the top of the stack is not a class, or we did not recently - add the class, False. - raw_lines_no_comments: The lines without the comments. - linenum: The current line number we are processing. - - Returns: - True if we should apply our namespace indentation check. Currently, it - only works for classes and namespaces inside of a namespace. - """ - - is_forward_declaration = IsForwardClassDeclaration(raw_lines_no_comments, - linenum) - - if not (is_namespace_indent_item or is_forward_declaration): - return False - - # If we are in a macro, we do not want to check the namespace indentation. - if IsMacroDefinition(raw_lines_no_comments, linenum): - return False - - return IsBlockInNameSpace(nesting_state, is_forward_declaration) - - -# Call this method if the line is directly inside of a namespace. -# If the line above is blank (excluding comments) or the start of -# an inner namespace, it cannot be indented. -def CheckItemIndentationInNamespace(filename, raw_lines_no_comments, linenum, - error): - line = raw_lines_no_comments[linenum] - if Match(r'^\s+', line): - error(filename, linenum, 'runtime/indentation_namespace', 4, - 'Do not indent within a namespace') - - -def ProcessLine(filename, file_extension, clean_lines, line, - include_state, function_state, nesting_state, error, - extra_check_functions=None): - """Processes a single line in the file. - - Args: - filename: Filename of the file that is being processed. - file_extension: The extension (dot not included) of the file. - clean_lines: An array of strings, each representing a line of the file, - with comments stripped. - line: Number of line being processed. - include_state: An _IncludeState instance in which the headers are inserted. - function_state: A _FunctionState instance which counts function lines, etc. - nesting_state: A NestingState instance which maintains information about - the current stack of nested blocks being parsed. - error: A callable to which errors are reported, which takes 4 arguments: - filename, line number, error level, and message - extra_check_functions: An array of additional check functions that will be - run on each source line. Each function takes 4 - arguments: filename, clean_lines, line, error - """ - raw_lines = clean_lines.raw_lines - ParseNolintSuppressions(filename, raw_lines[line], line, error) - nesting_state.Update(filename, clean_lines, line, error) - CheckForNamespaceIndentation(filename, nesting_state, clean_lines, line, - error) - if nesting_state.InAsmBlock(): return - CheckForFunctionLengths(filename, clean_lines, line, function_state, error) - CheckForMultilineCommentsAndStrings(filename, clean_lines, line, error) - CheckStyle(filename, clean_lines, line, file_extension, nesting_state, error) - CheckLanguage(filename, clean_lines, line, file_extension, include_state, - nesting_state, error) - CheckForNonConstReference(filename, clean_lines, line, nesting_state, error) - CheckForNonStandardConstructs(filename, clean_lines, line, - nesting_state, error) - CheckVlogArguments(filename, clean_lines, line, error) - CheckPosixThreading(filename, clean_lines, line, error) - CheckInvalidIncrement(filename, clean_lines, line, error) - CheckMakePairUsesDeduction(filename, clean_lines, line, error) - CheckRedundantVirtual(filename, clean_lines, line, error) - CheckRedundantOverrideOrFinal(filename, clean_lines, line, error) - if extra_check_functions: - for check_fn in extra_check_functions: - check_fn(filename, clean_lines, line, error) - -def FlagCxx11Features(filename, clean_lines, linenum, error): - """Flag those c++11 features that we only allow in certain places. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - include = Match(r'\s*#\s*include\s+[<"]([^<"]+)[">]', line) - - # Flag unapproved C++ TR1 headers. - if include and include.group(1).startswith('tr1/'): - error(filename, linenum, 'build/c++tr1', 5, - ('C++ TR1 headers such as <%s> are unapproved.') % include.group(1)) - - # Flag unapproved C++11 headers. - if include and include.group(1) in ('cfenv', - 'condition_variable', - 'fenv.h', - 'future', - 'mutex', - 'thread', - 'chrono', - 'ratio', - 'regex', - 'system_error', - ): - error(filename, linenum, 'build/c++11', 5, - ('<%s> is an unapproved C++11 header.') % include.group(1)) - - # The only place where we need to worry about C++11 keywords and library - # features in preprocessor directives is in macro definitions. - if Match(r'\s*#', line) and not Match(r'\s*#\s*define\b', line): return - - # These are classes and free functions. The classes are always - # mentioned as std::*, but we only catch the free functions if - # they're not found by ADL. They're alphabetical by header. - for top_name in ( - # type_traits - 'alignment_of', - 'aligned_union', - ): - if Search(r'\bstd::%s\b' % top_name, line): - error(filename, linenum, 'build/c++11', 5, - ('std::%s is an unapproved C++11 class or function. Send c-style ' - 'an example of where it would make your code more readable, and ' - 'they may let you use it.') % top_name) - - -def FlagCxx14Features(filename, clean_lines, linenum, error): - """Flag those C++14 features that we restrict. - - Args: - filename: The name of the current file. - clean_lines: A CleansedLines instance containing the file. - linenum: The number of the line to check. - error: The function to call with any errors found. - """ - line = clean_lines.elided[linenum] - - include = Match(r'\s*#\s*include\s+[<"]([^<"]+)[">]', line) - - # Flag unapproved C++14 headers. - if include and include.group(1) in ('scoped_allocator', 'shared_mutex'): - error(filename, linenum, 'build/c++14', 5, - ('<%s> is an unapproved C++14 header.') % include.group(1)) - - -def ProcessFileData(filename, file_extension, lines, error, - extra_check_functions=None): - """Performs lint checks and reports any errors to the given error function. - - Args: - filename: Filename of the file that is being processed. - file_extension: The extension (dot not included) of the file. - lines: An array of strings, each representing a line of the file, with the - last element being empty if the file is terminated with a newline. - error: A callable to which errors are reported, which takes 4 arguments: - filename, line number, error level, and message - extra_check_functions: An array of additional check functions that will be - run on each source line. Each function takes 4 - arguments: filename, clean_lines, line, error - """ - lines = (['// marker so line numbers and indices both start at 1'] + lines + - ['// marker so line numbers end in a known way']) - - include_state = _IncludeState() - function_state = _FunctionState() - nesting_state = NestingState() - - ResetNolintSuppressions() - - CheckForCopyright(filename, lines, error) - ProcessGlobalSuppresions(lines) - RemoveMultiLineComments(filename, lines, error) - clean_lines = CleansedLines(lines) - - if IsHeaderExtension(file_extension): - CheckForHeaderGuard(filename, clean_lines, error) - - for line in xrange(clean_lines.NumLines()): - ProcessLine(filename, file_extension, clean_lines, line, - include_state, function_state, nesting_state, error, - extra_check_functions) - FlagCxx11Features(filename, clean_lines, line, error) - nesting_state.CheckCompletedBlocks(filename, error) - - CheckForIncludeWhatYouUse(filename, clean_lines, include_state, error) - - # Check that the .cc file has included its header if it exists. - if _IsSourceExtension(file_extension): - CheckHeaderFileIncluded(filename, include_state, error) - - # We check here rather than inside ProcessLine so that we see raw - # lines rather than "cleaned" lines. - CheckForBadCharacters(filename, lines, error) - - CheckForNewlineAtEOF(filename, lines, error) - -def ProcessConfigOverrides(filename): - """ Loads the configuration files and processes the config overrides. - - Args: - filename: The name of the file being processed by the linter. - - Returns: - False if the current |filename| should not be processed further. - """ - - abs_filename = os.path.abspath(filename) - cfg_filters = [] - keep_looking = True - while keep_looking: - abs_path, base_name = os.path.split(abs_filename) - if not base_name: - break # Reached the root directory. - - cfg_file = os.path.join(abs_path, "CPPLINT.cfg") - abs_filename = abs_path - if not os.path.isfile(cfg_file): - continue - - try: - with open(cfg_file) as file_handle: - for line in file_handle: - line, _, _ = line.partition('#') # Remove comments. - if not line.strip(): - continue - - name, _, val = line.partition('=') - name = name.strip() - val = val.strip() - if name == 'set noparent': - keep_looking = False - elif name == 'filter': - cfg_filters.append(val) - elif name == 'exclude_files': - # When matching exclude_files pattern, use the base_name of - # the current file name or the directory name we are processing. - # For example, if we are checking for lint errors in /foo/bar/baz.cc - # and we found the .cfg file at /foo/CPPLINT.cfg, then the config - # file's "exclude_files" filter is meant to be checked against "bar" - # and not "baz" nor "bar/baz.cc". - if base_name: - pattern = re.compile(val) - if pattern.match(base_name): - if _cpplint_state.quiet: - # Suppress "Ignoring file" warning when using --quiet. - return False - _cpplint_state.PrintInfo('Ignoring "%s": file excluded by "%s". ' - 'File path component "%s" matches ' - 'pattern "%s"\n' % - (filename, cfg_file, base_name, val)) - return False - elif name == 'linelength': - global _line_length - try: - _line_length = int(val) - except ValueError: - _cpplint_state.PrintError('Line length must be numeric.') - elif name == 'extensions': - ProcessExtensionsOption(val) - elif name == 'root': - global _root - # root directories are specified relative to CPPLINT.cfg dir. - _root = os.path.join(os.path.dirname(cfg_file), val) - elif name == 'headers': - ProcessHppHeadersOption(val) - elif name == 'includeorder': - ProcessIncludeOrderOption(val) - else: - _cpplint_state.PrintError( - 'Invalid configuration option (%s) in file %s\n' % - (name, cfg_file)) - - except IOError: - _cpplint_state.PrintError( - "Skipping config file '%s': Can't open for reading\n" % cfg_file) - keep_looking = False - - # Apply all the accumulated filters in reverse order (top-level directory - # config options having the least priority). - for cfg_filter in reversed(cfg_filters): - _AddFilters(cfg_filter) - - return True - - -def ProcessFile(filename, vlevel, extra_check_functions=None): - """Does google-lint on a single file. - - Args: - filename: The name of the file to parse. - - vlevel: The level of errors to report. Every error of confidence - >= verbose_level will be reported. 0 is a good default. - - extra_check_functions: An array of additional check functions that will be - run on each source line. Each function takes 4 - arguments: filename, clean_lines, line, error - """ - - _SetVerboseLevel(vlevel) - _BackupFilters() - old_errors = _cpplint_state.error_count - - if not ProcessConfigOverrides(filename): - _RestoreFilters() - return - - lf_lines = [] - crlf_lines = [] - try: - # Support the UNIX convention of using "-" for stdin. Note that - # we are not opening the file with universal newline support - # (which codecs doesn't support anyway), so the resulting lines do - # contain trailing '\r' characters if we are reading a file that - # has CRLF endings. - # If after the split a trailing '\r' is present, it is removed - # below. - if filename == '-': - lines = codecs.StreamReaderWriter(sys.stdin, - codecs.getreader('utf8'), - codecs.getwriter('utf8'), - 'replace').read().split('\n') - else: - with codecs.open(filename, 'r', 'utf8', 'replace') as target_file: - lines = target_file.read().split('\n') - - # Remove trailing '\r'. - # The -1 accounts for the extra trailing blank line we get from split() - for linenum in range(len(lines) - 1): - if lines[linenum].endswith('\r'): - lines[linenum] = lines[linenum].rstrip('\r') - crlf_lines.append(linenum + 1) - else: - lf_lines.append(linenum + 1) - - except IOError: - _cpplint_state.PrintError( - "Skipping input '%s': Can't open for reading\n" % filename) - _RestoreFilters() - return - - # Note, if no dot is found, this will give the entire filename as the ext. - file_extension = filename[filename.rfind('.') + 1:] - - # When reading from stdin, the extension is unknown, so no cpplint tests - # should rely on the extension. - if filename != '-' and file_extension not in GetAllExtensions(): - pass - # Ignition: never print this - # _cpplint_state.PrintError('Ignoring %s; not a valid file name ' - # '(%s)\n' % (filename, ', '.join(GetAllExtensions()))) - else: - ProcessFileData(filename, file_extension, lines, Error, - extra_check_functions) - - # If end-of-line sequences are a mix of LF and CR-LF, issue - # warnings on the lines with CR. - # - # Don't issue any warnings if all lines are uniformly LF or CR-LF, - # since critique can handle these just fine, and the style guide - # doesn't dictate a particular end of line sequence. - # - # We can't depend on os.linesep to determine what the desired - # end-of-line sequence should be, since that will return the - # server-side end-of-line sequence. - if lf_lines and crlf_lines: - # Warn on every line with CR. An alternative approach might be to - # check whether the file is mostly CRLF or just LF, and warn on the - # minority, we bias toward LF here since most tools prefer LF. - for linenum in crlf_lines: - Error(filename, linenum, 'whitespace/newline', 1, - 'Unexpected \\r (^M) found; better to use only \\n') - - # Suppress printing anything if --quiet was passed unless the error - # count has increased after processing this file. - if not _cpplint_state.quiet or old_errors != _cpplint_state.error_count: - pass - # Ignition: never print "Done Processing" - # _cpplint_state.PrintInfo('Done processing %s\n' % filename) - _RestoreFilters() - - -def PrintUsage(message): - """Prints a brief usage string and exits, optionally with an error message. - - Args: - message: The optional error message. - """ - sys.stderr.write(_USAGE % (list(GetAllExtensions()), - ','.join(list(GetAllExtensions())), - GetHeaderExtensions(), - ','.join(GetHeaderExtensions()))) - - if message: - sys.exit('\nFATAL ERROR: ' + message) - else: - sys.exit(0) - -def PrintVersion(): - sys.stdout.write('Cpplint fork (https://github.com/cpplint/cpplint)\n') - sys.stdout.write('cpplint ' + __VERSION__ + '\n') - sys.stdout.write('Python ' + sys.version + '\n') - sys.exit(0) - -def PrintCategories(): - """Prints a list of all the error-categories used by error messages. - - These are the categories used to filter messages via --filter. - """ - sys.stderr.write(''.join(' %s\n' % cat for cat in _ERROR_CATEGORIES)) - sys.exit(0) - - -def ParseArguments(args): - """Parses the command line arguments. - - This may set the output format and verbosity level as side-effects. - - Args: - args: The command line arguments: - - Returns: - The list of filenames to lint. - """ - try: - (opts, filenames) = getopt.getopt(args, '', ['help', 'output=', 'verbose=', - 'v=', - 'version', - 'counting=', - 'filter=', - 'root=', - 'repository=', - 'linelength=', - 'extensions=', - 'exclude=', - 'recursive', - 'headers=', - 'includeorder=', - 'quiet']) - except getopt.GetoptError: - PrintUsage('Invalid arguments.') - - verbosity = _VerboseLevel() - output_format = _OutputFormat() - filters = '' - quiet = _Quiet() - counting_style = '' - recursive = False - - for (opt, val) in opts: - if opt == '--help': - PrintUsage(None) - if opt == '--version': - PrintVersion() - elif opt == '--output': - if val not in ('emacs', 'vs7', 'eclipse', 'junit', 'sed', 'gsed'): - PrintUsage('The only allowed output formats are emacs, vs7, eclipse ' - 'sed, gsed and junit.') - output_format = val - elif opt == '--quiet': - quiet = True - elif opt == '--verbose' or opt == '--v': - verbosity = int(val) - elif opt == '--filter': - filters = val - if not filters: - PrintCategories() - elif opt == '--counting': - if val not in ('total', 'toplevel', 'detailed'): - PrintUsage('Valid counting options are total, toplevel, and detailed') - counting_style = val - elif opt == '--root': - global _root - _root = val - elif opt == '--repository': - global _repository - _repository = val - elif opt == '--linelength': - global _line_length - try: - _line_length = int(val) - except ValueError: - PrintUsage('Line length must be digits.') - elif opt == '--exclude': - global _excludes - if not _excludes: - _excludes = set() - _excludes.update(glob.glob(val)) - elif opt == '--extensions': - ProcessExtensionsOption(val) - elif opt == '--headers': - ProcessHppHeadersOption(val) - elif opt == '--recursive': - recursive = True - elif opt == '--includeorder': - ProcessIncludeOrderOption(val) - - if not filenames: - PrintUsage('No files were specified.') - - if recursive: - filenames = _ExpandDirectories(filenames) - - if _excludes: - filenames = _FilterExcludedFiles(filenames) - - _SetOutputFormat(output_format) - _SetQuiet(quiet) - _SetVerboseLevel(verbosity) - _SetFilters(filters) - _SetCountingStyle(counting_style) - - filenames.sort() - return filenames - -def _ExpandDirectories(filenames): - """Searches a list of filenames and replaces directories in the list with - all files descending from those directories. Files with extensions not in - the valid extensions list are excluded. - - Args: - filenames: A list of files or directories - - Returns: - A list of all files that are members of filenames or descended from a - directory in filenames - """ - expanded = set() - for filename in filenames: - if not os.path.isdir(filename): - expanded.add(filename) - continue - - for root, _, files in os.walk(filename): - for loopfile in files: - fullname = os.path.join(root, loopfile) - if fullname.startswith('.' + os.path.sep): - fullname = fullname[len('.' + os.path.sep):] - expanded.add(fullname) - - filtered = [] - for filename in expanded: - if os.path.splitext(filename)[1][1:] in GetAllExtensions(): - filtered.append(filename) - return filtered - -def _FilterExcludedFiles(fnames): - """Filters out files listed in the --exclude command line switch. File paths - in the switch are evaluated relative to the current working directory - """ - exclude_paths = [os.path.abspath(f) for f in _excludes] - # because globbing does not work recursively, exclude all subpath of all excluded entries - return [f for f in fnames - if not any(e for e in exclude_paths - if _IsParentOrSame(e, os.path.abspath(f)))] - -def _IsParentOrSame(parent, child): - """Return true if child is subdirectory of parent. - Assumes both paths are absolute and don't contain symlinks. - """ - parent = os.path.normpath(parent) - child = os.path.normpath(child) - if parent == child: - return True - - prefix = os.path.commonprefix([parent, child]) - if prefix != parent: - return False - # Note: os.path.commonprefix operates on character basis, so - # take extra care of situations like '/foo/ba' and '/foo/bar/baz' - child_suffix = child[len(prefix):] - child_suffix = child_suffix.lstrip(os.sep) - return child == os.path.join(prefix, child_suffix) - -def main(): - filenames = ParseArguments(sys.argv[1:]) - backup_err = sys.stderr - try: - # Change stderr to write with replacement characters so we don't die - # if we try to print something containing non-ASCII characters. - sys.stderr = codecs.StreamReader(sys.stderr, 'replace') - - _cpplint_state.ResetErrorCounts() - for filename in filenames: - ProcessFile(filename, _cpplint_state.verbose_level) - # If --quiet is passed, suppress printing error count unless there are errors. - if not _cpplint_state.quiet or _cpplint_state.error_count > 0: - _cpplint_state.PrintErrorCounts() - - if _cpplint_state.output_format == 'junit': - sys.stderr.write(_cpplint_state.FormatJUnitXML()) - - finally: - sys.stderr = backup_err - - sys.exit(_cpplint_state.error_count > 0) - - -if __name__ == '__main__': - main() diff --git a/tools/cpplint_to_cppcheckxml.py b/tools/cpplint_to_cppcheckxml.py deleted file mode 100644 index 2809ad9e8..000000000 --- a/tools/cpplint_to_cppcheckxml.py +++ /dev/null @@ -1,53 +0,0 @@ -#!/usr/bin/env python - -# Convert output from Google's cpplint.py to the cppcheck XML format for -# consumption by the Jenkins cppcheck plugin. - -# Reads from stdin and writes to stderr (to mimic cppcheck) - - -import sys -import re -import xml.sax.saxutils - -def cpplint_score_to_cppcheck_severity(score): - # I'm making this up - if score == 1: - return 'style' - elif score == 2: - return 'style' - elif score == 3: - return 'warning' - elif score == 4: - return 'warning' - elif score == 5: - return 'error' - -def parse(): - # TODO: do this properly, using the xml module. - # Write header - sys.stderr.write('''\n''') - sys.stderr.write('''\n''') - - # Do line-by-line conversion - r = re.compile('([^:]*):([0-9]*): ([^\[]*)\[([^\]]*)\] \[([0-9]*)\].*') - - for l in sys.stdin.readlines(): - m = r.match(l.strip()) - if not m: - continue - g = m.groups() - if len(g) != 5: - continue - fname, lineno, rawmsg, label, score = g - # Protect Jenkins from bad XML, which makes it barf - msg = xml.sax.saxutils.escape(rawmsg) - severity = cpplint_score_to_cppcheck_severity(int(score)) - sys.stderr.write('''\n'''%(fname, lineno, label, severity, msg)) - - # Write footer - sys.stderr.write('''\n''') - - -if __name__ == '__main__': - parse() From 1a2c4067608182cf6cc9a1304ff9731a13589d0c Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 22 Dec 2021 21:56:05 -0800 Subject: [PATCH 20/28] Prepare for 10.7.0~pre1 (#799) Signed-off-by: Steve Peters --- CMakeLists.txt | 5 +++-- Changelog.md | 39 +++++++++++++++++++++++++++++++++++++++ 2 files changed, 42 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index cb413fbca..9b4c5b18a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -5,7 +5,7 @@ if(COMMAND CMAKE_POLICY) CMAKE_POLICY(SET CMP0004 NEW) endif(COMMAND CMAKE_POLICY) -project (sdformat10 VERSION 10.6.0) +project (sdformat10 VERSION 10.7.0) # The protocol version has nothing to do with the package version. # It represents the current version of SDFormat implemented by the software @@ -24,7 +24,8 @@ set(IGN_CMAKE_VER ${ignition-cmake2_VERSION_MAJOR}) if (BUILD_SDF) ign_configure_project( NO_IGNITION_PREFIX - REPLACE_IGNITION_INCLUDE_PATH sdf) + REPLACE_IGNITION_INCLUDE_PATH sdf + VERSION_SUFFIX pre1) ################################################# # Find tinyxml2. diff --git a/Changelog.md b/Changelog.md index 4c7cb130f..fae61a1b4 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,44 @@ ## libsdformat 10.X +### libsdformat 10.7.0 (2021-12-23) + +1. Fix flattening logic for nested model names (merged forward from sdf6) + * [Pull request #597](https://github.com/ignitionrobotics/sdformat/pull/597) + +1. Create CODEOWNERS with azeey and scpeters + * [Pull request #650](https://github.com/ignitionrobotics/sdformat/pull/650) + +1. Fix xyz and rpy offsets in fixed joint reduction + * [Pull request #500](https://github.com/ignitionrobotics/sdformat/pull/500) + +1. Check joint parent link names in Model::Load + * [Pull request #726](https://github.com/osrf/sdformat/pull/726) + +1. Make exception for plugins when checking for name uniqueness + * [Pull request #733](https://github.com/ignitionrobotics/sdformat/pull/733) + +1. Added Force Torque Noise functions + Unit tests + * [Pull request #669](https://github.com/ignitionrobotics/sdformat/pull/669) + +1. Add Joint DOM API to access joint sensors + * [Pull request #517](https://github.com/ignitionrobotics/sdformat/pull/517) + +1. Add force torque sensor + * [Pull request #393](https://github.com/ignitionrobotics/sdformat/pull/393) + * A contribution from Nick Lamprianidis + +1. Remove outdated deprecation note from parser_urdf.hh + * [Pull request #740](https://github.com/osrf/sdformat/pull/740) + +1. Fix URDF fixed joint reduction of plugins + * [Pull request #745](https://github.com/osrf/sdformat/pull/745) + +1. Fix loading nested include with custom attributes + * [Pull request #789](https://github.com/ignitionrobotics/sdformat/pull/789) + +1. Replace custom cmake code with ign-cmake2 + * [Pull request #780](https://github.com/osrf/sdformat/pull/780) + ### libsdformat 10.6.0 (2021-09-08) 1. Parse URDF continuous joint effort/velocity limits From cf81994ceab9047a93cb0670f4642fc32c7eba08 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 27 Dec 2021 00:30:41 -0800 Subject: [PATCH 21/28] Fix test compilation with USE_INTERNAL_URDF (#800) The USE_INTERNAL_URDF logic for include and windows compiler definitions needs to be repeated for tests that add parser_urdf.cc via target_sources. An interface library is used to deduplicate the cmake logic. Signed-off-by: Steve Peters --- src/CMakeLists.txt | 55 ++++++++++++++++++++-------------------------- 1 file changed, 24 insertions(+), 31 deletions(-) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index e2e02bbdf..2d5d07167 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -5,16 +5,26 @@ ign_get_libsources_and_unittests(sources gtest_sources) # Add the source file auto-generated into the build folder from sdf/CMakeLists.txt list(APPEND sources EmbeddedSdf.cc) +# Use interface library to deduplicate cmake logic for URDF linking +add_library(using_parser_urdf INTERFACE) if (USE_INTERNAL_URDF) set(sources ${sources} - urdf/urdf_parser/model.cpp - urdf/urdf_parser/link.cpp - urdf/urdf_parser/joint.cpp - urdf/urdf_parser/pose.cpp - urdf/urdf_parser/twist.cpp - urdf/urdf_parser/urdf_model_state.cpp - urdf/urdf_parser/urdf_sensor.cpp - urdf/urdf_parser/world.cpp) + urdf/urdf_parser/model.cpp + urdf/urdf_parser/link.cpp + urdf/urdf_parser/joint.cpp + urdf/urdf_parser/pose.cpp + urdf/urdf_parser/twist.cpp + urdf/urdf_parser/urdf_model_state.cpp + urdf/urdf_parser/urdf_sensor.cpp + urdf/urdf_parser/world.cpp) + target_include_directories(using_parser_urdf INTERFACE + ${CMAKE_CURRENT_SOURCE_DIR}/urdf) + if (WIN32) + target_compile_definitions(using_parser_urdf INTERFACE -D_USE_MATH_DEFINES) + endif() +else() + target_link_libraries(using_parser_urdf INTERFACE + IgnURDFDOM::IgnURDFDOM) endif() if (BUILD_TESTING) @@ -62,12 +72,9 @@ if (BUILD_TESTING) endif() if (TARGET UNIT_ParamPassing_TEST) - if (NOT USE_INTERNAL_URDF) - target_link_libraries(UNIT_ParamPassing_TEST - IgnURDFDOM::IgnURDFDOM) - endif() target_link_libraries(UNIT_ParamPassing_TEST - TINYXML2::TINYXML2) + TINYXML2::TINYXML2 + using_parser_urdf) target_sources(UNIT_ParamPassing_TEST PRIVATE Converter.cc EmbeddedSdf.cc @@ -90,12 +97,9 @@ if (BUILD_TESTING) endif() if (TARGET UNIT_parser_urdf_TEST) - if (NOT USE_INTERNAL_URDF) - target_link_libraries(UNIT_parser_urdf_TEST - IgnURDFDOM::IgnURDFDOM) - endif() target_link_libraries(UNIT_parser_urdf_TEST - TINYXML2::TINYXML2) + TINYXML2::TINYXML2 + using_parser_urdf) target_sources(UNIT_parser_urdf_TEST PRIVATE SDFExtension.cc XmlUtils.cc @@ -112,7 +116,8 @@ target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} PUBLIC ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER} PRIVATE - TINYXML2::TINYXML2) + TINYXML2::TINYXML2 + using_parser_urdf) if (WIN32) target_compile_definitions(${PROJECT_LIBRARY_TARGET_NAME} PRIVATE URDFDOM_STATIC) @@ -126,18 +131,6 @@ target_include_directories(${PROJECT_LIBRARY_TARGET_NAME} ${CMAKE_CURRENT_SOURCE_DIR} ) -if (USE_INTERNAL_URDF) - target_include_directories(${PROJECT_LIBRARY_TARGET_NAME} - PRIVATE - ${CMAKE_CURRENT_SOURCE_DIR}/urdf - ) - if (WIN32) - target_compile_definitions(${PROJECT_LIBRARY_TARGET_NAME} PRIVATE -D_USE_MATH_DEFINES) - endif() -else() - target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} PRIVATE IgnURDFDOM::IgnURDFDOM) -endif() - if(NOT WIN32) add_subdirectory(cmd) endif() From 1741bb0fad63b8b21034c28807c654809e6583ca Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 27 Dec 2021 08:58:56 -0800 Subject: [PATCH 22/28] Prepare for 10.7.0~pre2 (#802) Signed-off-by: Steve Peters --- CMakeLists.txt | 2 +- Changelog.md | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9b4c5b18a..841548490 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -25,7 +25,7 @@ if (BUILD_SDF) ign_configure_project( NO_IGNITION_PREFIX REPLACE_IGNITION_INCLUDE_PATH sdf - VERSION_SUFFIX pre1) + VERSION_SUFFIX pre2) ################################################# # Find tinyxml2. diff --git a/Changelog.md b/Changelog.md index fae61a1b4..9e783cffd 100644 --- a/Changelog.md +++ b/Changelog.md @@ -39,6 +39,9 @@ 1. Replace custom cmake code with ign-cmake2 * [Pull request #780](https://github.com/osrf/sdformat/pull/780) +1. Fix test compilation with USE_INTERNAL_URDF + * [Pull request #800](https://github.com/ignitionrobotics/sdformat/pull/800) + ### libsdformat 10.6.0 (2021-09-08) 1. Parse URDF continuous joint effort/velocity limits From 5f326e9070a0aee1bfe24d81f26550112bad03a6 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 27 Dec 2021 13:17:02 -0800 Subject: [PATCH 23/28] Prepare for 10.7.0, final Dome release (#804) Signed-off-by: Steve Peters --- CMakeLists.txt | 2 +- Changelog.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 841548490..2000ab7d0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -25,7 +25,7 @@ if (BUILD_SDF) ign_configure_project( NO_IGNITION_PREFIX REPLACE_IGNITION_INCLUDE_PATH sdf - VERSION_SUFFIX pre2) + VERSION_SUFFIX) ################################################# # Find tinyxml2. diff --git a/Changelog.md b/Changelog.md index 9e783cffd..8b0bc632b 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,6 +1,6 @@ ## libsdformat 10.X -### libsdformat 10.7.0 (2021-12-23) +### libsdformat 10.7.0 (2021-12-27) 1. Fix flattening logic for nested model names (merged forward from sdf6) * [Pull request #597](https://github.com/ignitionrobotics/sdformat/pull/597) From bff502f7b81562d8b8e9620150ebca52cdd7b9d1 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 29 Dec 2021 11:06:23 -0800 Subject: [PATCH 24/28] sdf_custom: fix nested model expectations (#807) Account for new behavior of nested models and :: syntax. Signed-off-by: Steve Peters --- test/integration/sdf_custom.cc | 40 ++++++++++++++++++++-------------- 1 file changed, 24 insertions(+), 16 deletions(-) diff --git a/test/integration/sdf_custom.cc b/test/integration/sdf_custom.cc index 9f3ad54ab..9f4a378cd 100644 --- a/test/integration/sdf_custom.cc +++ b/test/integration/sdf_custom.cc @@ -293,45 +293,53 @@ R"( ASSERT_NE(nullptr, world2); // //model[@name=test] - const sdf::Model *model11 = world1->ModelByIndex(0); - const sdf::Model *model12 = world2->ModelByIndex(0); + const sdf::Model *model01 = world1->ModelByIndex(0); + const sdf::Model *model02 = world2->ModelByIndex(0); + ASSERT_NE(nullptr, model01); + ASSERT_NE(nullptr, model02); + EXPECT_EQ("test", model01->Name()); + EXPECT_EQ("test", model02->Name()); + EXPECT_EQ(model01->Element()->ToString(""), model02->Element()->ToString("")); + + // //model[@name=test]/model[@name=M1] + const sdf::Model *model11 = model01->ModelByIndex(0); + const sdf::Model *model12 = model02->ModelByIndex(0); ASSERT_NE(nullptr, model11); ASSERT_NE(nullptr, model12); + EXPECT_EQ("M1", model11->Name()); + EXPECT_EQ("M1", model12->Name()); EXPECT_EQ(model11->Element()->ToString(""), model12->Element()->ToString("")); - // //model[@name=test]/frame[@name=M1::__model__] - const sdf::Frame *frame1 = model11->FrameByIndex(0); - const sdf::Frame *frame2 = model12->FrameByIndex(0); - ASSERT_NE(nullptr, frame1); - ASSERT_NE(nullptr, frame2); - EXPECT_EQ(frame1->Element()->ToString(""), frame2->Element()->ToString("")); - - // //model[@name=test]/link[@name=M1::L1] + // //model[@name=test]/model[@name=M1]/link[@name=L1] const sdf::Link *model11link1 = model11->LinkByIndex(0); const sdf::Link *model12link2 = model12->LinkByIndex(0); ASSERT_NE(nullptr, model11link1); ASSERT_NE(nullptr, model12link2); + EXPECT_EQ("L1", model11link1->Name()); + EXPECT_EQ("L1", model12link2->Name()); const std::string linkCustomAttrStr = -R"( - 0 0 0 0 -0 0 - +R"( )"; EXPECT_EQ(linkCustomAttrStr, model11link1->Element()->ToString("")); EXPECT_EQ(linkCustomAttrStr, model12link2->Element()->ToString("")); - // //model[@name=test]/model[@name=M1::M2] + // //model[@name=test]/model[@name=M1]/model[@name=M2] const sdf::Model *model21 = model11->ModelByIndex(0); const sdf::Model *model22 = model12->ModelByIndex(0); ASSERT_NE(nullptr, model21); ASSERT_NE(nullptr, model22); + EXPECT_EQ("M2", model21->Name()); + EXPECT_EQ("M2", model22->Name()); EXPECT_EQ(model21->Element()->ToString(""), model22->Element()->ToString("")); - // //model[@name=test]/model[@name=M1::M2]/link[@name=M1::L1] + // //model[@name=test]/model[@name=M1]/model[@name=M2]/link[@name=L1] const sdf::Link *model21link1 = model21->LinkByIndex(0); const sdf::Link *model22link2 = model22->LinkByIndex(0); ASSERT_NE(nullptr, model21link1); ASSERT_NE(nullptr, model22link2); + EXPECT_EQ("L1", model21link1->Name()); + EXPECT_EQ("L1", model22link2->Name()); EXPECT_EQ(model21link1->Element()->ToString(""), model22link2->Element()->ToString("")); @@ -357,7 +365,7 @@ R"( const std::string customElemStr = R"( transmission_interface/SimpleTransmission - + EffortJointInterface From f03ec70fecd1426f1562bc2d20e0a87435ce4bef Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 29 Dec 2021 13:23:52 -0800 Subject: [PATCH 25/28] Fix compiler warnings (#808) Signed-off-by: Steve Peters --- src/FrameSemantics.cc | 2 -- src/World.cc | 2 +- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/src/FrameSemantics.cc b/src/FrameSemantics.cc index 6081aac97..be22a114b 100644 --- a/src/FrameSemantics.cc +++ b/src/FrameSemantics.cc @@ -313,7 +313,6 @@ Errors buildFrameAttachedToGraph( const std::string scopeContextName = "__model__"; - auto rootId = ignition::math::graph::kNullId; if (_isRoot) { // The __root__ vertex identifies the scope that contains a root level @@ -326,7 +325,6 @@ Errors buildFrameAttachedToGraph( // more complexity to the validateFrameAttachedToGraph code. _out = _out.AddScopeVertex( "", "__root__", scopeContextName, sdf::FrameType::STATIC_MODEL); - rootId = _out.ScopeVertexId(); } const auto modelId = _out.AddVertex(_model->Name(), frameType).Id(); diff --git a/src/World.cc b/src/World.cc index c19058cef..884413c1e 100644 --- a/src/World.cc +++ b/src/World.cc @@ -216,7 +216,7 @@ Errors World::Load(sdf::ElementPtr _sdf, const ParserConfig &_config) for (const auto &ifaceModelPair : this->dataPtr->interfaceModels) { - frameNames.insert(ifaceModelPair.second->Name()).second; + frameNames.insert(ifaceModelPair.second->Name()); } // Load all the physics. From 15e6793293239b3ee021b19fed6bbd447e0e0db1 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Thu, 30 Dec 2021 10:49:42 -0800 Subject: [PATCH 26/28] Fix compiler warnings (#810) Signed-off-by: Steve Peters --- src/FrameSemantics.cc | 2 -- test/integration/pose_1_9_sdf.cc | 3 --- 2 files changed, 5 deletions(-) diff --git a/src/FrameSemantics.cc b/src/FrameSemantics.cc index 4df943448..a6b4c9395 100644 --- a/src/FrameSemantics.cc +++ b/src/FrameSemantics.cc @@ -780,7 +780,6 @@ Errors wrapperBuildFrameAttachedToGraph(ScopedGraph &_out, const std::string scopeContextName = "__model__"; - auto rootId = ignition::math::graph::kNullId; if (_isRoot) { // The __root__ vertex identifies the scope that contains a root level @@ -793,7 +792,6 @@ Errors wrapperBuildFrameAttachedToGraph(ScopedGraph &_out, // more complexity to the validateFrameAttachedToGraph code. _out = _out.AddScopeVertex( "", "__root__", scopeContextName, sdf::FrameType::STATIC_MODEL); - rootId = _out.ScopeVertexId(); } const auto modelId = _out.AddVertex(_model.name, frameType).Id(); diff --git a/test/integration/pose_1_9_sdf.cc b/test/integration/pose_1_9_sdf.cc index 492ff2cdc..d806401d7 100644 --- a/test/integration/pose_1_9_sdf.cc +++ b/test/integration/pose_1_9_sdf.cc @@ -340,7 +340,6 @@ TEST(Pose1_9, PoseSet8ValuesFail) #endif buffer.str(""); - using Pose = ignition::math::Pose3d; sdf::ElementPtr poseElem(new sdf::Element); poseElem->SetName("pose"); @@ -928,8 +927,6 @@ TEST(Pose1_9, ToStringWithQuatXYZWDegreesFalse) ////////////////////////////////////////////////// TEST(Pose1_9, ToStringAfterChangingDegreeAttribute) { - using Pose = ignition::math::Pose3d; - sdf::ElementPtr poseElem(new sdf::Element); poseElem->SetName("pose"); poseElem->AddValue("pose", "0 0 0 0 0 0", true); From 6404afdf959982f759526dea8700037b50fa7758 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Mon, 3 Jan 2022 00:51:37 -0800 Subject: [PATCH 27/28] Fix parsing 'type' attibutes in plugins (#809) Signed-off-by: Louise Poubel * Add line with unrecognized type Signed-off-by: Steve Peters * Fix for custom element with attribute 'type' (#811) * Reverted changes to parser for custom element with attribute 'type', added fix in ParamPrivate::ValueFromStringImpl instead Signed-off-by: Aaron Chong Co-authored-by: Steve Peters Co-authored-by: Aaron Chong --- src/Param.cc | 17 ++++++++++------- src/Plugin_TEST.cc | 3 ++- src/parser.cc | 24 ++++++++---------------- 3 files changed, 20 insertions(+), 24 deletions(-) diff --git a/src/Param.cc b/src/Param.cc index 0d370bd3c..fcf1633f2 100644 --- a/src/Param.cc +++ b/src/Param.cc @@ -640,14 +640,17 @@ bool ParamPrivate::ValueFromStringImpl(const std::string &_typeName, std::string tmp(trimmed); std::string lowerTmp = lowercase(trimmed); - // "true" and "false" doesn't work properly - if (lowerTmp == "true") + // "true" and "false" doesn't work properly (except for string) + if (_typeName != "string" && _typeName != "std::string") { - tmp = "1"; - } - else if (lowerTmp == "false") - { - tmp = "0"; + if (lowerTmp == "true") + { + tmp = "1"; + } + else if (lowerTmp == "false") + { + tmp = "0"; + } } bool isHex = lowerTmp.compare(0, 2, "0x") == 0; diff --git a/src/Plugin_TEST.cc b/src/Plugin_TEST.cc index 35f6aee0d..ca77bcede 100644 --- a/src/Plugin_TEST.cc +++ b/src/Plugin_TEST.cc @@ -186,7 +186,8 @@ TEST(DOMPlugin, LoadWithChildren) std::string pluginStr = R"( 3D View - false + false + 0 docked ogre diff --git a/src/parser.cc b/src/parser.cc index f4dc5758d..7e9d65f46 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -1912,13 +1912,13 @@ void copyChildren(ElementPtr _sdf, for (elemXml = _xml->FirstChildElement(); elemXml; elemXml = elemXml->NextSiblingElement()) { - std::string elem_name = elemXml->Name(); + std::string elemName = elemXml->Name(); - if (_sdf->HasElementDescription(elem_name)) + if (_sdf->HasElementDescription(elemName)) { if (!_onlyUnknown) { - sdf::ElementPtr element = _sdf->AddElement(elem_name); + sdf::ElementPtr element = _sdf->AddElement(elemName); // FIXME: copy attributes for (const auto *attribute = elemXml->FirstAttribute(); @@ -1941,26 +1941,18 @@ void copyChildren(ElementPtr _sdf, { ElementPtr element(new Element); element->SetParent(_sdf); - element->SetName(elem_name); - std::optional typeName = std::nullopt; + element->SetName(elemName); for (const tinyxml2::XMLAttribute *attribute = elemXml->FirstAttribute(); attribute; attribute = attribute->Next()) { - const std::string attributeName(attribute->Name()); - if (attributeName == "type") - typeName = attribute->Value(); - - element->AddAttribute(attributeName, "string", "", 1, ""); - element->GetAttribute(attributeName)->SetFromString( - attribute->Value()); + element->AddAttribute(attribute->Name(), "string", "", 1, ""); + element->GetAttribute(attribute->Name())->SetFromString( + attribute->Value()); } if (elemXml->GetText() != nullptr) { - if (typeName.has_value()) - element->AddValue(typeName.value(), elemXml->GetText(), true); - else - element->AddValue("string", elemXml->GetText(), true); + element->AddValue("string", elemXml->GetText(), true); } copyChildren(element, elemXml, _onlyUnknown); From 26c1a478b666d749695f62deba26b9590c39171b Mon Sep 17 00:00:00 2001 From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com> Date: Thu, 6 Jan 2022 16:56:49 -0700 Subject: [PATCH 28/28] make SDF to USD a separate component of sdformat Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com> --- CMakeLists.txt | 11 +- examples/usdConverter/CMakeLists.txt | 13 + examples/usdConverter/README.md | 30 +++ examples/usdConverter/shapes.sdf | 244 ++++++++++++++++++ .../usdConverter}/usdConverter.cc | 2 +- src/cmd/CMakeLists.txt | 18 -- usd/include/sdf/CMakeLists.txt | 1 + .../include/sdf}/geometry.hh | 4 +- .../include/sdf}/joint.hh | 4 +- .../include/sdf}/light.hh | 4 +- .../include/sdf}/link.hh | 4 +- .../include/sdf}/model.hh | 4 +- .../include/sdf}/sensor.hh | 4 +- .../include/sdf}/utils.hh | 4 +- .../include/sdf}/visual.hh | 4 +- .../include/sdf}/world.hh | 4 +- usd/src/CMakeLists.txt | 20 ++ .../sdf_usd_parser => usd/src}/geometry.cc | 6 +- {src/usd/sdf_usd_parser => usd/src}/joint.cc | 4 +- {src/usd/sdf_usd_parser => usd/src}/light.cc | 4 +- {src/usd/sdf_usd_parser => usd/src}/link.cc | 10 +- {src/usd/sdf_usd_parser => usd/src}/model.cc | 8 +- {src/usd/sdf_usd_parser => usd/src}/sensor.cc | 4 +- {src/usd/sdf_usd_parser => usd/src}/visual.cc | 6 +- {src/usd/sdf_usd_parser => usd/src}/world.cc | 6 +- 25 files changed, 361 insertions(+), 62 deletions(-) create mode 100644 examples/usdConverter/CMakeLists.txt create mode 100644 examples/usdConverter/README.md create mode 100644 examples/usdConverter/shapes.sdf rename {src/cmd => examples/usdConverter}/usdConverter.cc (98%) create mode 100644 usd/include/sdf/CMakeLists.txt rename {src/usd/sdf_usd_parser => usd/include/sdf}/geometry.hh (95%) rename {src/usd/sdf_usd_parser => usd/include/sdf}/joint.hh (96%) rename {src/usd/sdf_usd_parser => usd/include/sdf}/light.hh (95%) rename {src/usd/sdf_usd_parser => usd/include/sdf}/link.hh (96%) rename {src/usd/sdf_usd_parser => usd/include/sdf}/model.hh (96%) rename {src/usd/sdf_usd_parser => usd/include/sdf}/sensor.hh (95%) rename {src/usd/sdf_usd_parser => usd/include/sdf}/utils.hh (98%) rename {src/usd/sdf_usd_parser => usd/include/sdf}/visual.hh (95%) rename {src/usd/sdf_usd_parser => usd/include/sdf}/world.hh (95%) create mode 100644 usd/src/CMakeLists.txt rename {src/usd/sdf_usd_parser => usd/src}/geometry.cc (99%) rename {src/usd/sdf_usd_parser => usd/src}/joint.cc (99%) rename {src/usd/sdf_usd_parser => usd/src}/light.cc (98%) rename {src/usd/sdf_usd_parser => usd/src}/link.cc (95%) rename {src/usd/sdf_usd_parser => usd/src}/model.cc (96%) rename {src/usd/sdf_usd_parser => usd/src}/sensor.cc (98%) rename {src/usd/sdf_usd_parser => usd/src}/visual.cc (92%) rename {src/usd/sdf_usd_parser => usd/src}/world.cc (97%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5ff7e0038..0f150351c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -109,8 +109,17 @@ if (BUILD_SDF) ign_find_package(ignition-utils1 VERSION REQUIRED) set(IGN_UTILS_VER ${ignition-utils1_VERSION_MAJOR}) + ######################################## + # Find ignition common + ign_find_package(ignition-common4 COMPONENTS graphics REQUIRED_BY usd) + set(IGN_COMMON_VER ${ignition-common4_VERSION_MAJOR}) + + ######################################## + # Find PXR + ign_find_package(pxr REQUIRED_BY usd PKGCONFIG pxr) - ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS) + ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS + COMPONENTS usd) ign_create_packages() add_subdirectory(sdf) diff --git a/examples/usdConverter/CMakeLists.txt b/examples/usdConverter/CMakeLists.txt new file mode 100644 index 000000000..1a30a0c1b --- /dev/null +++ b/examples/usdConverter/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) + +project(usdSdfConversions) + +set(SDF_VER 12) +find_package(sdformat${SDF_VER} COMPONENTS usd REQUIRED) + +add_executable(usdConverter usdConverter.cc) + +target_link_libraries(usdConverter + PUBLIC + sdformat${SDF_VER}::usd +) diff --git a/examples/usdConverter/README.md b/examples/usdConverter/README.md new file mode 100644 index 000000000..5b5fd8a20 --- /dev/null +++ b/examples/usdConverter/README.md @@ -0,0 +1,30 @@ +# Converting between SDF and USD + +This example shows how a world in a SDF file can be converted to [USD](https://graphics.pixar.com/usd/release/index.html). + +## Requirements + +You will need all of the dependencies for sdformat, along with the following additional dependencies: +* USD: [installation instructions](https://github.com/PixarAnimationStudios/USD/blob/release/README.md#getting-and-building-the-code) +* [ignition-common4](https://github.com/ignitionrobotics/ign-common) + +## Setup + +Build sdformat, and then run the following commands to build the example (run these commands from this example directory): +```bash +mkdir build +cd build +cmake .. +make +``` + +You should now have an executable named `usdConverter`, which can be used to convert a SDF world file to a USD file. +The following command converts the example `shapes.sdf` file to its USD representation, stored in a file called `shapes.usda` (run this command from the `build` directory): +```bash +./usdConverter ../shapes.sdf shapes.usda +``` + +You can now view the contents of the generated USD file with `usdview` (this should have been installed when setting up the USD dependency): +``` +usdview shapes.usda +``` diff --git a/examples/usdConverter/shapes.sdf b/examples/usdConverter/shapes.sdf new file mode 100644 index 000000000..6935ae5d3 --- /dev/null +++ b/examples/usdConverter/shapes.sdf @@ -0,0 +1,244 @@ + + + + + + 1.0 1.0 1.0 + 0.8 0.8 0.8 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0.5 0 0 0 + + + + 0.16666 + 0 + 0 + 0.16666 + 0 + 0.16666 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 0 -1.5 0.5 0 0 0 + + + + 0.1458 + 0 + 0 + 0.1458 + 0 + 0.125 + + 1.0 + + + + + 0.5 + 1.0 + + + + + + + + 0.5 + 1.0 + + + + 0 1 0 1 + 0 1 0 1 + 0 1 0 1 + + + + + + + 0 1.5 0.5 0 0 0 + + + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + 1.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + + + 0 -3.0 0.5 0 0 0 + + + + 0.074154 + 0 + 0 + 0.074154 + 0 + 0.018769 + + 1.0 + + + + + 0.2 + 0.6 + + + + + + + 0.2 + 0.6 + + + + 1 1 0 1 + 1 1 0 1 + 1 1 0 1 + + + + + + + 0 3.0 0.5 0 0 0 + + + + 0.068 + 0 + 0 + 0.058 + 0 + 0.026 + + 1.0 + + + + + 0.2 0.3 0.5 + + + + + + + 0.2 0.3 0.5 + + + + 1 0 1 1 + 1 0 1 1 + 1 0 1 1 + + + + + + diff --git a/src/cmd/usdConverter.cc b/examples/usdConverter/usdConverter.cc similarity index 98% rename from src/cmd/usdConverter.cc rename to examples/usdConverter/usdConverter.cc index e356a8345..b46ad8eab 100644 --- a/src/cmd/usdConverter.cc +++ b/examples/usdConverter/usdConverter.cc @@ -20,7 +20,7 @@ #include #include "sdf/sdf.hh" -#include "sdf_usd_parser/world.hh" +#include "sdf/world.hh" int main(int argc, const char* argv[]) { diff --git a/src/cmd/CMakeLists.txt b/src/cmd/CMakeLists.txt index 6d10bddda..e831d413a 100644 --- a/src/cmd/CMakeLists.txt +++ b/src/cmd/CMakeLists.txt @@ -42,21 +42,3 @@ file(GENERATE # Install the ruby command line library in an unversioned location. install(FILES ${cmd_script_generated} DESTINATION lib/ruby/ignition) - -#=============================================================================== -# SDF -> USD converter -add_executable(usdConverter - usdConverter.cc -) - -target_link_libraries(usdConverter - PUBLIC - ${sdf_target} -) - -install( - TARGETS - usdConverter - DESTINATION - ${BIN_INSTALL_DIR} -) diff --git a/usd/include/sdf/CMakeLists.txt b/usd/include/sdf/CMakeLists.txt new file mode 100644 index 000000000..f2909dd9d --- /dev/null +++ b/usd/include/sdf/CMakeLists.txt @@ -0,0 +1 @@ +ign_install_all_headers(COMPONENT usd) diff --git a/src/usd/sdf_usd_parser/geometry.hh b/usd/include/sdf/geometry.hh similarity index 95% rename from src/usd/sdf_usd_parser/geometry.hh rename to usd/include/sdf/geometry.hh index e61ed11bf..019db91cc 100644 --- a/src/usd/sdf_usd_parser/geometry.hh +++ b/usd/include/sdf/geometry.hh @@ -15,8 +15,8 @@ * */ -#ifndef SDF_PARSER_GEOMETRY_HH_ -#define SDF_PARSER_GEOMETRY_HH_ +#ifndef SDF_USD_GEOMETRY_HH_ +#define SDF_USD_GEOMETRY_HH_ #include diff --git a/src/usd/sdf_usd_parser/joint.hh b/usd/include/sdf/joint.hh similarity index 96% rename from src/usd/sdf_usd_parser/joint.hh rename to usd/include/sdf/joint.hh index fadf2ddc1..d5c84ce25 100644 --- a/src/usd/sdf_usd_parser/joint.hh +++ b/usd/include/sdf/joint.hh @@ -15,8 +15,8 @@ * */ -#ifndef SDF_PARSER_JOINT_HH_ -#define SDF_PARSER_JOINT_HH_ +#ifndef SDF_USD_JOINT_HH_ +#define SDF_USD_JOINT_HH_ #include diff --git a/src/usd/sdf_usd_parser/light.hh b/usd/include/sdf/light.hh similarity index 95% rename from src/usd/sdf_usd_parser/light.hh rename to usd/include/sdf/light.hh index fc37d539c..2e8aab283 100644 --- a/src/usd/sdf_usd_parser/light.hh +++ b/usd/include/sdf/light.hh @@ -15,8 +15,8 @@ * */ -#ifndef SDF_PARSER_LIGHT_HH_ -#define SDF_PARSER_LIGHT_HH_ +#ifndef SDF_USD_LIGHT_HH_ +#define SDF_USD_LIGHT_HH_ #include diff --git a/src/usd/sdf_usd_parser/link.hh b/usd/include/sdf/link.hh similarity index 96% rename from src/usd/sdf_usd_parser/link.hh rename to usd/include/sdf/link.hh index c0286a5d9..553ccda3f 100644 --- a/src/usd/sdf_usd_parser/link.hh +++ b/usd/include/sdf/link.hh @@ -15,8 +15,8 @@ * */ -#ifndef SDF_PARSER_LINK_HH_ -#define SDF_PARSER_LINK_HH_ +#ifndef SDF_USD_LINK_HH_ +#define SDF_USD_LINK_HH_ #include diff --git a/src/usd/sdf_usd_parser/model.hh b/usd/include/sdf/model.hh similarity index 96% rename from src/usd/sdf_usd_parser/model.hh rename to usd/include/sdf/model.hh index 8cfec2ec3..af83b29fd 100644 --- a/src/usd/sdf_usd_parser/model.hh +++ b/usd/include/sdf/model.hh @@ -15,8 +15,8 @@ * */ -#ifndef SDF_PARSER_MODEL_HH_ -#define SDF_PARSER_MODEL_HH_ +#ifndef SDF_USD_MODEL_HH_ +#define SDF_USD_MODEL_HH_ #include diff --git a/src/usd/sdf_usd_parser/sensor.hh b/usd/include/sdf/sensor.hh similarity index 95% rename from src/usd/sdf_usd_parser/sensor.hh rename to usd/include/sdf/sensor.hh index 244fcb741..bedd393b4 100644 --- a/src/usd/sdf_usd_parser/sensor.hh +++ b/usd/include/sdf/sensor.hh @@ -15,8 +15,8 @@ * */ -#ifndef SDF_PARSER_SENSOR_HH_ -#define SDF_PARSER_SENSOR_HH_ +#ifndef SDF_USD_SENSOR_HH_ +#define SDF_USD_SENSOR_HH_ #include diff --git a/src/usd/sdf_usd_parser/utils.hh b/usd/include/sdf/utils.hh similarity index 98% rename from src/usd/sdf_usd_parser/utils.hh rename to usd/include/sdf/utils.hh index 320470aba..15a4422c4 100644 --- a/src/usd/sdf_usd_parser/utils.hh +++ b/usd/include/sdf/utils.hh @@ -15,8 +15,8 @@ * */ -#ifndef SDF_PARSER_UTILS_HH_ -#define SDF_PARSER_UTILS_HH_ +#ifndef SDF_USD_UTILS_HH_ +#define SDF_USD_UTILS_HH_ #include #include diff --git a/src/usd/sdf_usd_parser/visual.hh b/usd/include/sdf/visual.hh similarity index 95% rename from src/usd/sdf_usd_parser/visual.hh rename to usd/include/sdf/visual.hh index 98d6586b1..b1fa143e2 100644 --- a/src/usd/sdf_usd_parser/visual.hh +++ b/usd/include/sdf/visual.hh @@ -15,8 +15,8 @@ * */ -#ifndef SDF_PARSER_VISUAL_HH_ -#define SDF_PARSER_VISUAL_HH_ +#ifndef SDF_USD_VISUAL_HH_ +#define SDF_USD_VISUAL_HH_ #include diff --git a/src/usd/sdf_usd_parser/world.hh b/usd/include/sdf/world.hh similarity index 95% rename from src/usd/sdf_usd_parser/world.hh rename to usd/include/sdf/world.hh index aeae014ba..7d6b1d0c1 100644 --- a/src/usd/sdf_usd_parser/world.hh +++ b/usd/include/sdf/world.hh @@ -15,8 +15,8 @@ * */ -#ifndef SDF_PARSER_WORLD_HH_ -#define SDF_PARSER_WORLD_HH_ +#ifndef SDF_USD_WORLD_HH_ +#define SDF_USD_WORLD_HH_ #include diff --git a/usd/src/CMakeLists.txt b/usd/src/CMakeLists.txt new file mode 100644 index 000000000..2c5b292ee --- /dev/null +++ b/usd/src/CMakeLists.txt @@ -0,0 +1,20 @@ +# Collect source files into the "sources" variable and unit test files into the +# "gtest_sources" variable. +ign_get_libsources_and_unittests(sources gtest_sources) + +ign_add_component(usd SOURCES ${sources} GET_TARGET_NAME usd_target) + +target_include_directories(${usd_target} + PUBLIC + ${PXR_INCLUDE_DIRS} +) + +target_link_libraries(${usd_target} + PUBLIC + ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER} + ignition-common${IGN_COMMON_VER}::graphics + ${PXR_LIBRARIES} +) + +# Build the unit tests +ign_build_tests(TYPE UNIT SOURCES ${gtest_sources} LIB_DEPS ${usd_target}) diff --git a/src/usd/sdf_usd_parser/geometry.cc b/usd/src/geometry.cc similarity index 99% rename from src/usd/sdf_usd_parser/geometry.cc rename to usd/src/geometry.cc index 727527c6c..8a79363f5 100644 --- a/src/usd/sdf_usd_parser/geometry.cc +++ b/usd/src/geometry.cc @@ -15,7 +15,7 @@ * */ -#include "sdf_usd_parser/geometry.hh" +#include "sdf/geometry.hh" #include #include @@ -44,7 +44,7 @@ #include "sdf/Mesh.hh" #include "sdf/Plane.hh" #include "sdf/Sphere.hh" -#include "sdf_usd_parser/utils.hh" +#include "sdf/utils.hh" namespace usd { @@ -240,7 +240,7 @@ namespace usd bool ParseSdfEllipsoid(const sdf::Geometry &_geometry, pxr::UsdStageRefPtr &_stage, const std::string &_path) { const auto sdfEllipsoid = _geometry.EllipsoidShape(); - + auto usdEllipsoid = pxr::UsdGeomSphere::Define(_stage, pxr::SdfPath(_path)); const auto &maxRadii = sdfEllipsoid->Radii().Max(); usdEllipsoid.CreateRadiusAttr().Set(maxRadii); diff --git a/src/usd/sdf_usd_parser/joint.cc b/usd/src/joint.cc similarity index 99% rename from src/usd/sdf_usd_parser/joint.cc rename to usd/src/joint.cc index 68c029b77..23bf08fc2 100644 --- a/src/usd/sdf_usd_parser/joint.cc +++ b/usd/src/joint.cc @@ -15,7 +15,7 @@ * */ -#include "sdf_usd_parser/joint.hh" +#include "sdf/joint.hh" #include #include @@ -41,7 +41,7 @@ #include "sdf/JointAxis.hh" #include "sdf/Link.hh" #include "sdf/Model.hh" -#include "sdf_usd_parser/utils.hh" +#include "sdf/utils.hh" namespace usd { diff --git a/src/usd/sdf_usd_parser/light.cc b/usd/src/light.cc similarity index 98% rename from src/usd/sdf_usd_parser/light.cc rename to usd/src/light.cc index c94cb65a5..977083565 100644 --- a/src/usd/sdf_usd_parser/light.cc +++ b/usd/src/light.cc @@ -15,7 +15,7 @@ * */ -#include "sdf_usd_parser/light.hh" +#include "sdf/light.hh" #include @@ -29,7 +29,7 @@ #include #include "sdf/Light.hh" -#include "sdf_usd_parser/utils.hh" +#include "sdf/utils.hh" namespace usd { diff --git a/src/usd/sdf_usd_parser/link.cc b/usd/src/link.cc similarity index 95% rename from src/usd/sdf_usd_parser/link.cc rename to usd/src/link.cc index c2b59a397..566930bb9 100644 --- a/src/usd/sdf_usd_parser/link.cc +++ b/usd/src/link.cc @@ -15,7 +15,7 @@ * */ -#include "sdf_usd_parser/link.hh" +#include "sdf/link.hh" #include @@ -26,10 +26,10 @@ #include #include "sdf/Link.hh" -#include "sdf_usd_parser/light.hh" -#include "sdf_usd_parser/sensor.hh" -#include "sdf_usd_parser/utils.hh" -#include "sdf_usd_parser/visual.hh" +#include "sdf/light.hh" +#include "sdf/sensor.hh" +#include "sdf/utils.hh" +#include "sdf/visual.hh" namespace usd { diff --git a/src/usd/sdf_usd_parser/model.cc b/usd/src/model.cc similarity index 96% rename from src/usd/sdf_usd_parser/model.cc rename to usd/src/model.cc index f7cbccb7d..d63b15aa4 100644 --- a/src/usd/sdf_usd_parser/model.cc +++ b/usd/src/model.cc @@ -15,7 +15,7 @@ * */ -#include "sdf_usd_parser/model.hh" +#include "sdf/model.hh" #include #include @@ -28,9 +28,9 @@ #include #include "sdf/Model.hh" -#include "sdf_usd_parser/joint.hh" -#include "sdf_usd_parser/link.hh" -#include "sdf_usd_parser/utils.hh" +#include "sdf/joint.hh" +#include "sdf/link.hh" +#include "sdf/utils.hh" namespace usd { diff --git a/src/usd/sdf_usd_parser/sensor.cc b/usd/src/sensor.cc similarity index 98% rename from src/usd/sdf_usd_parser/sensor.cc rename to usd/src/sensor.cc index f3afdf1b7..163605a3a 100644 --- a/src/usd/sdf_usd_parser/sensor.cc +++ b/usd/src/sensor.cc @@ -15,7 +15,7 @@ * */ -#include "sdf_usd_parser/sensor.hh" +#include "sdf/sensor.hh" #include @@ -32,7 +32,7 @@ #include "sdf/Camera.hh" #include "sdf/Lidar.hh" #include "sdf/Sensor.hh" -#include "sdf_usd_parser/utils.hh" +#include "sdf/utils.hh" namespace usd { diff --git a/src/usd/sdf_usd_parser/visual.cc b/usd/src/visual.cc similarity index 92% rename from src/usd/sdf_usd_parser/visual.cc rename to usd/src/visual.cc index e50c4ddbf..b6ef94159 100644 --- a/src/usd/sdf_usd_parser/visual.cc +++ b/usd/src/visual.cc @@ -15,7 +15,7 @@ * */ -#include "sdf_usd_parser/visual.hh" +#include "sdf/visual.hh" #include #include @@ -25,8 +25,8 @@ #include #include "sdf/Visual.hh" -#include "sdf_usd_parser/geometry.hh" -#include "sdf_usd_parser/utils.hh" +#include "sdf/geometry.hh" +#include "sdf/utils.hh" namespace usd { diff --git a/src/usd/sdf_usd_parser/world.cc b/usd/src/world.cc similarity index 97% rename from src/usd/sdf_usd_parser/world.cc rename to usd/src/world.cc index aad6e8e2d..9faf48068 100644 --- a/src/usd/sdf_usd_parser/world.cc +++ b/usd/src/world.cc @@ -15,7 +15,7 @@ * */ -#include "sdf_usd_parser/world.hh" +#include "sdf/world.hh" #include #include @@ -31,8 +31,8 @@ #include "sdf/Joint.hh" #include "sdf/World.hh" -#include "sdf_usd_parser/light.hh" -#include "sdf_usd_parser/model.hh" +#include "sdf/light.hh" +#include "sdf/model.hh" namespace usd {