Skip to content

Commit

Permalink
Merge branch 'ign-physics2' into claire/canonical-link
Browse files Browse the repository at this point in the history
  • Loading branch information
iche033 authored Nov 12, 2020
2 parents 888d158 + c11a47d commit 13ef221
Show file tree
Hide file tree
Showing 7 changed files with 31 additions and 11 deletions.
11 changes: 11 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,17 @@

## Ignition Physics 1.x

### Ignition Physics 1.10.0 (2020-11-04)

1. Resolved codecheck issues
* [Pull request 154](https://github.com/ignitionrobotics/ign-physics/pull/154)

1. Ignore invalid joint commands in the dartsim-plugin
* [Pull request 137](https://github.com/ignitionrobotics/ign-physics/pull/137)

1. Fix CONFIG arg in ign_find_package(DART) call
* [Pull request 119](https://github.com/ignitionrobotics/ign-physics/pull/119)

### Ignition Physics 1.9.0 (2020-09-17)

1. Support for slip compliance in the dartsim-plugin.
Expand Down
7 changes: 5 additions & 2 deletions dartsim/src/CustomMeshShape.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,14 @@
*
*/

#include "CustomMeshShape.hh"

#include <memory>
#include <string>

#include <ignition/common/Console.hh>
#include <ignition/common/SubMesh.hh>

#include "CustomMeshShape.hh"

namespace ignition {
namespace physics {
namespace dartsim {
Expand Down
5 changes: 3 additions & 2 deletions dartsim/src/EntityManagementFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,9 @@

#include "EntityManagementFeatures.hh"

#include <memory>
#include <string>

#include <dart/config.hpp>
#include <dart/collision/ode/OdeCollisionDetector.hpp>
#include <dart/constraint/ConstraintSolver.hpp>
Expand All @@ -25,8 +28,6 @@
#include <dart/collision/CollisionFilter.hpp>
#include <dart/collision/CollisionObject.hpp>

#include <string>

namespace ignition {
namespace physics {
namespace dartsim {
Expand Down
6 changes: 4 additions & 2 deletions dartsim/src/SDFFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,10 @@

#include "SDFFeatures.hh"

#include <cmath>
#include <limits>
#include <memory>

#include <dart/constraint/ConstraintSolver.hpp>
#include <dart/dynamics/BallJoint.hpp>
#include <dart/dynamics/BoxShape.hpp>
Expand All @@ -32,8 +36,6 @@
#include <dart/constraint/WeldJointConstraint.hpp>
#include <dart/dynamics/WeldJoint.hpp>

#include <cmath>

#include <ignition/common/Console.hh>
#include <ignition/math/eigen3/Conversions.hh>
#include <ignition/math/Helpers.hh>
Expand Down
5 changes: 4 additions & 1 deletion dartsim/src/ShapeFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,10 @@
*
*/

#include "ShapeFeatures.hh"

#include <memory>

#include <dart/dynamics/BoxShape.hpp>
#include <dart/dynamics/CylinderShape.hpp>
#include <dart/dynamics/MeshShape.hpp>
Expand All @@ -23,7 +27,6 @@
#include <dart/dynamics/SphereShape.hpp>

#include "CustomMeshShape.hh"
#include "ShapeFeatures.hh"

namespace ignition {
namespace physics {
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/physics/Cloneable.hh
Original file line number Diff line number Diff line change
Expand Up @@ -107,13 +107,13 @@ namespace ignition
public: MakeCloneable& operator=(MakeCloneable &&_other);

// Documentation inherited
public: std::unique_ptr<Cloneable> Clone() const override final;
public: std::unique_ptr<Cloneable> Clone() const final;

// Documentation inherited
public: void Copy(const Cloneable &_other) override final;
public: void Copy(const Cloneable &_other) final;

// Documentation inherited
public: void Copy(Cloneable &&_other) override final;
public: void Copy(Cloneable &&_other) final;
};
}
}
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/physics/RelativeQuantity.hh
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ namespace ignition
/// \brief This constructor will specify the parent frame and then forward
/// the remaining arguments to the constructor of the underlying quantity.
public: template <typename... Args>
RelativeQuantity(const FrameID &_parentID, Args&&... _args);
explicit RelativeQuantity(const FrameID &_parentID, Args&&... _args);

/// \brief Implicit conversion constructor.
public: RelativeQuantity(const Q &_rawValue);
Expand Down

0 comments on commit 13ef221

Please sign in to comment.