Skip to content

Commit

Permalink
Merge 11 onto main
Browse files Browse the repository at this point in the history
Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey committed Sep 8, 2021
2 parents 96ac74e + 46fd794 commit 9b7e6f9
Show file tree
Hide file tree
Showing 97 changed files with 5,977 additions and 1,512 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,4 @@
build
build_*
*.*.sw?
.vscode
21 changes: 21 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -274,6 +274,27 @@ else (build_errors)
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)

# Ignore vendored directories.
file(WRITE ${PROJECT_BINARY_DIR}/cppcheck.suppress
"*:${PROJECT_SOURCE_DIR}/src/urdf/*\n"
)
ign_setup_target_for_codecheck()

########################################
# Make the package config file
set(PC_CONFIG_INSTALL_DIR ${LIB_INSTALL_DIR}/pkgconfig)
Expand Down
56 changes: 56 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -354,6 +354,62 @@

### libsdformat 9.X.X (202X-XX-XX)

### libsdformat 9.6.0 (2021-08-18)

1. Adds `enable_metrics` flag to Sensor.
* [Pull request #665](https://github.com/ignitionrobotics/sdformat/pull/665)

1. Add GPS sensor DOM to sdf9
* [Pull request #453](https://github.com/ignitionrobotics/sdformat/pull/453)

1. Support parsing elements that are not part of the schema
* [Pull request #638](https://github.com/ignitionrobotics/sdformat/pull/638)

1. Add lightmap to 1.7 spec and PBR material DOM
* [Pull request #429](https://github.com/ignitionrobotics/sdformat/pull/429)

1. Fix urdf link extension tags
* [Pull request #628](https://github.com/ignitionrobotics/sdformat/pull/628)

1. Updated material spec
* [Pull request #644](https://github.com/ignitionrobotics/sdformat/pull/644)

1. Minor fix to Migration guide
* [Pull request #630](https://github.com/ignitionrobotics/sdformat/pull/630)

1. Error: move << operator from .hh to .cc file
* [Pull request #625](https://github.com/ignitionrobotics/sdformat/pull/625)

1. Update build system to allow overriding CXX flags and using clang on Linux
* [Pull request #621](https://github.com/ignitionrobotics/sdformat/pull/621)

1. Add Element::FindElement as an alternative to Element::GetElement
* [Pull request #620](https://github.com/ignitionrobotics/sdformat/pull/620)

1. Add ValidateGraphs methods to Model/World (sdf9)
* [Pull request #602](https://github.com/ignitionrobotics/sdformat/pull/602)

1. Fix ABI break
* [Pull request #605](https://github.com/ignitionrobotics/sdformat/pull/605)

1. Making PrintValues() and ToString() able to not print default elements
* [Pull request #575](https://github.com/ignitionrobotics/sdformat/pull/575)

1. Add API for determining if an element was set by the user
* [Pull request #542](https://github.com/ignitionrobotics/sdformat/pull/542)

1. Methods for removing attributes from an element
* [Pull request #555](https://github.com/ignitionrobotics/sdformat/pull/555)

1. Improve docs of collision_bitmask.
* [Pull request #521](https://github.com/ignitionrobotics/sdformat/pull/521)

1. Add camera type aliases to docs.
* [Pull request #514](https://github.com/ignitionrobotics/sdformat/pull/514)

1. Add action-ignition-ci
* [Pull request #501](https://github.com/ignitionrobotics/sdformat/pull/452)

### libsdformat 9.5.0 (2021-02-11)

1. Add Windows installation
Expand Down
9 changes: 7 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,8 @@ TODO(eric.cousineau): Move terminology section to sdf_tutorials?

## Test coverage

[![codecov](https://codecov.io/gh/osrf/sdformat/branch/master/graph/badge.svg)](https://codecov.io/gh/osrf/sdformat)
<!-- Note: The branch name in the codecov URL should be updated when forward porting -->
[![codecov](https://codecov.io/gh/ignitionrobotics/sdformat/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/sdformat/branch/main)

# Installation

Expand All @@ -44,7 +45,11 @@ The Source Installation instructions should be used if you need the very latest
### Ubuntu

On Ubuntu systems, `apt-get` can be used to install `sdformat`:
```
```sh
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
sudo apt-get update

sudo apt install libsdformat<#>-dev libsdformat<#>
```

Expand Down
4 changes: 2 additions & 2 deletions cmake/SearchForStuff.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -102,8 +102,8 @@ endmacro()

########################################
# Find ignition cmake2
# Only for using the testing macros, not really
# being use to configure the whole project
# 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})

Expand Down
1 change: 1 addition & 0 deletions include/sdf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ set (headers
Material.hh
Mesh.hh
Model.hh
NavSat.hh
Noise.hh
Param.hh
parser.hh
Expand Down
2 changes: 1 addition & 1 deletion include/sdf/Console.hh
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ namespace sdf
/// \brief Constructor.
/// \param[in] _stream Pointer to an output stream operator. Can be
/// NULL/nullptr.
public: ConsoleStream(std::ostream *_stream) :
public: explicit ConsoleStream(std::ostream *_stream) :
stream(_stream) {}

/// \brief Redirect whatever is passed in to both our ostream
Expand Down
6 changes: 3 additions & 3 deletions include/sdf/Element.hh
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,7 @@ namespace sdf
const std::string &_type,
const std::string &_defaultvalue,
bool _required,
const std::string &_description="");
const std::string &_description = "");

/// \brief Add a value to this Element.
/// \param[in] _type Type of data the parameter will hold.
Expand All @@ -217,7 +217,7 @@ namespace sdf
/// \throws sdf::AssertionInternalError if an invalid type is given.
public: void AddValue(const std::string &_type,
const std::string &_defaultValue, bool _required,
const std::string &_description="");
const std::string &_description = "");

/// \brief Add a value to this Element. This override allows passing min and
/// max values of the parameter.
Expand Down Expand Up @@ -553,7 +553,7 @@ namespace sdf
const std::string &_type,
const std::string &_defaultValue,
bool _required,
const std::string &_description="");
const std::string &_description = "");


/// \brief Private data pointer
Expand Down
4 changes: 4 additions & 0 deletions include/sdf/Exception.hh
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,7 @@ namespace sdf
/// \param[in] _line Line number where the error occurred
/// \param[in] _msg Error message
public: InternalError(const char *_file, std::int64_t _line,
// cppcheck-suppress passedByValue
const std::string _msg);

/// \brief Destructor
Expand All @@ -140,8 +141,11 @@ namespace sdf
/// \param[in] _msg Function where assertion failed
public: AssertionInternalError(const char *_file,
std::int64_t _line,
// cppcheck-suppress passedByValue
const std::string _expr,
// cppcheck-suppress passedByValue
const std::string _function,
// cppcheck-suppress passedByValue
const std::string _msg = "");
/// \brief Destructor
public: virtual ~AssertionInternalError();
Expand Down
10 changes: 10 additions & 0 deletions include/sdf/Imu.hh
Original file line number Diff line number Diff line change
Expand Up @@ -232,6 +232,16 @@ namespace sdf
/// \param[in] _frame The name of the parent frame.
public: void SetCustomRpyParentFrame(const std::string &_frame);

/// \brief Get whether orientation data generation is enabled.
/// \return True if orientation data generation is enabled orientation data,
/// false otherwise.
public: bool OrientationEnabled() const;

/// \brief Set whether to enable orientation data generation.
/// \param[in] _enabled True to enabled orientation data, false to disable
/// it.
public: void SetOrientationEnabled(bool _enabled);

/// \brief Return true if both Imu objects contain the same values.
/// \param[_in] _imu Imu value to compare.
/// \returen True if 'this' == _imu.
Expand Down
2 changes: 1 addition & 1 deletion include/sdf/Model.hh
Original file line number Diff line number Diff line change
Expand Up @@ -315,7 +315,7 @@ namespace sdf
/// relative to the current model, delimited by "::".
/// \return An immutable pointer to the canonical link and the nested
/// name of the link relative to the current model.
// TODO (addisu): If the canonical link is inside an interface model, this
// TODO(addisu): If the canonical link is inside an interface model, this
// function returns {nullptr, name}. This can be problematic for downstream
// applications.
public: std::pair<const Link *, std::string> CanonicalLinkAndRelativeName()
Expand Down
141 changes: 141 additions & 0 deletions include/sdf/NavSat.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,141 @@
/*
* 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_NAVSAT_HH_
#define SDF_NAVSAT_HH_

#include <ignition/utils/ImplPtr.hh>
#include <sdf/Error.hh>
#include <sdf/Element.hh>
#include <sdf/Noise.hh>
#include <sdf/sdf_config.h>

#include <ignition/math/Angle.hh>

namespace sdf
{
// Inline bracket to help doxygen filtering.
inline namespace SDF_VERSION_NAMESPACE {
//
/// \brief NavSat contains information about a NavSat sensor.
/// This sensor can be attached to a link. The NavSat sensor can be defined
/// SDF XML by the "navsat" type.
///
/// # Example SDF XML using navsat type:
///
/// ~~~{.xml}
/// <sensor name="navsat_sensor" type="navsat">
/// <pose>1 2 3 0 0 0</pose>
/// <topic>/navsat</topic>
/// <navsat>
/// <position_sensing>
/// <horizontal>
/// <noise type="gaussian">
/// <mean>0.98</mean>
/// <stddev>0.76</stddev>
/// </noise>
/// </horizontal>
/// <vertical>
/// <noise type="gaussian">
/// <mean>0.98</mean>
/// <stddev>0.76</stddev>
/// </noise>
/// </vertical>
/// </position_sensing>
/// <velocity_sensing>
/// <horizontal>
/// <noise type="gaussian">
/// <mean>0.98</mean>
/// <stddev>0.76</stddev>
/// </noise>
/// </horizontal>
/// <vertical>
/// <noise type="gaussian">
/// <mean>0.98</mean>
/// <stddev>0.76</stddev>
/// </noise>
/// </vertical>
/// </velocity_sensing>
/// </navsat>
/// </sensor>
/// ~~~
class SDFORMAT_VISIBLE NavSat
{
/// \brief Default constructor
public: NavSat();
/// \brief Load the navsat based on an 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 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 Set the noise values for the horizontal position sensor
/// \param[in] _noise Noise values to set to
public: void SetHorizontalPositionNoise(const Noise &_noise);

/// \brief Get noise value for horizontal position sensor
/// \return Noise values
public: const Noise &HorizontalPositionNoise() const;

/// \brief Set the noise values for the vertical position sensor
/// \param[in] _noise Noise values to set to
public: void SetVerticalPositionNoise(const Noise &_noise);

/// \brief Get noise value for vertical position sensor
/// \return Noise values
public: const Noise &VerticalPositionNoise() const;

/// \brief Set the noise values for the horizontal velocity sensor
/// \param[in] _noise Noise values to set to
public: void SetHorizontalVelocityNoise(const Noise &_noise);

/// \brief Get noise value for horizontal velocity sensor
/// \return Noise values
public: const Noise &HorizontalVelocityNoise() const;

/// \brief Set the noise values for the vertical velocity sensor
/// \param[in] _noise Noise values to set to
public: void SetVerticalVelocityNoise(const Noise &_noise);

/// \brief Get noise value for vertical velocity sensor
/// \return Noise values
public: const Noise &VerticalVelocityNoise() const;

/// \brief Return true if both NavSat objects contain the same values.
/// \param[_in] _navsat NavSat value to compare.
/// \return True if 'this' == _navsat.
public: bool operator==(const NavSat &_navsat) const;

/// \brief Return true this NavSat object does not contain the same
/// values as the passed in parameter.
/// \param[_in] _navsat NavSat value to compare.
/// \return True if 'this' != _navsat.
public: bool operator!=(const NavSat &_navsat) const;

/// \brief Private data pointer.
IGN_UTILS_IMPL_PTR(dataPtr)
};
}
}
#endif
3 changes: 3 additions & 0 deletions include/sdf/Param.hh
Original file line number Diff line number Diff line change
Expand Up @@ -350,6 +350,8 @@ namespace sdf

/// \def ParamVariant
/// \brief Variant type def.
/// Note: When a new variant is added, add variant to functions
/// ParamPrivate::TypeToString and ParamPrivate::ValueFromStringImpl
public: typedef std::variant<bool, char, std::string, int, std::uint64_t,
unsigned int, double, float, sdf::Time,
ignition::math::Angle,
Expand Down Expand Up @@ -400,6 +402,7 @@ namespace sdf
template<typename T>
std::string ParamPrivate::TypeToString() const
{
// cppcheck-suppress syntaxError
if constexpr (std::is_same_v<T, bool>)
return "bool";
else if constexpr (std::is_same_v<T, char>)
Expand Down
1 change: 1 addition & 0 deletions include/sdf/ParticleEmitter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#ifndef SDF_PARTICLE_EMITTER_HH_
#define SDF_PARTICLE_EMITTER_HH_

#include <memory>
#include <string>

#include <ignition/math/Pose3.hh>
Expand Down
Loading

0 comments on commit 9b7e6f9

Please sign in to comment.