diff --git a/.clang-format b/.clang-format index 68766810a2d55..d0a71b0ab518c 100644 --- a/.clang-format +++ b/.clang-format @@ -66,23 +66,23 @@ IncludeCategories: Priority: 22 - Regex: '^$' Priority: 23 - - Regex: '^$' + - Regex: '^$' Priority: 24 - - Regex: '^$' + - Regex: '^$' Priority: 25 - - Regex: '^$' + - Regex: '^$' Priority: 26 - - Regex: '^$' + - Regex: '^$' Priority: 27 - - Regex: '^$' + - Regex: '^$' Priority: 28 - - Regex: '^$' + - Regex: '^$' Priority: 29 - - Regex: '^$' + - Regex: '^$' Priority: 30 - - Regex: '^$' + - Regex: '^$' Priority: 31 - - Regex: '^$' + - Regex: '^$' Priority: 32 - Regex: '^$' Priority: 33 diff --git a/dart/collision/CollisionDetector.hpp b/dart/collision/CollisionDetector.hpp index b22120a76c180..e6ae192ac161e 100644 --- a/dart/collision/CollisionDetector.hpp +++ b/dart/collision/CollisionDetector.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_COLLISIONDETECTOR_HPP_ #define DART_COLLISION_COLLISIONDETECTOR_HPP_ +#include + #include #include #include @@ -56,7 +58,8 @@ namespace collision { class CollisionObject; -class CollisionDetector : public std::enable_shared_from_this +class DART_API CollisionDetector + : public std::enable_shared_from_this { public: friend class CollisionObject; diff --git a/dart/collision/CollisionFilter.hpp b/dart/collision/CollisionFilter.hpp index 5bfadcad430bc..85502a958be1a 100644 --- a/dart/collision/CollisionFilter.hpp +++ b/dart/collision/CollisionFilter.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_COLLISIONFILTER_HPP_ #define DART_COLLISION_COLLISIONFILTER_HPP_ +#include + #include #include @@ -47,7 +49,7 @@ namespace collision { class CollisionObject; -class CollisionFilter +class DART_API CollisionFilter { public: /// Destructor. @@ -68,7 +70,7 @@ class CollisionFilter const CollisionObject* object1, const CollisionObject* object2) const = 0; }; -class CompositeCollisionFilter : public CollisionFilter +class DART_API CompositeCollisionFilter : public CollisionFilter { public: /// Adds a collision filter to this CompositeCollisionFilter. @@ -90,7 +92,7 @@ class CompositeCollisionFilter : public CollisionFilter std::unordered_set mFilters; }; -class BodyNodeCollisionFilter : public CollisionFilter +class DART_API BodyNodeCollisionFilter : public CollisionFilter { public: /// Add a BodyNode pair to the blacklist. diff --git a/dart/collision/CollisionGroup.hpp b/dart/collision/CollisionGroup.hpp index 563c55c46b399..3e62b5e646073 100644 --- a/dart/collision/CollisionGroup.hpp +++ b/dart/collision/CollisionGroup.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_COLLISIONGROUP_HPP_ #define DART_COLLISION_COLLISIONGROUP_HPP_ +#include + #include #include #include @@ -52,7 +54,7 @@ namespace dart { namespace collision { -class CollisionGroup +class DART_API CollisionGroup { public: /// Constructor diff --git a/dart/collision/CollisionObject.hpp b/dart/collision/CollisionObject.hpp index 4483b1b700d54..8ed8626474e4f 100644 --- a/dart/collision/CollisionObject.hpp +++ b/dart/collision/CollisionObject.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_COLLISIONOBJECT_HPP_ #define DART_COLLISION_COLLISIONOBJECT_HPP_ +#include + #include #include @@ -42,7 +44,7 @@ namespace dart { namespace collision { -class CollisionObject +class DART_API CollisionObject { public: friend class CollisionGroup; diff --git a/dart/collision/CollisionOption.hpp b/dart/collision/CollisionOption.hpp index 176b195db645b..8573ba229178c 100644 --- a/dart/collision/CollisionOption.hpp +++ b/dart/collision/CollisionOption.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_COLLISIONOPTION_HPP_ #define DART_COLLISION_COLLISIONOPTION_HPP_ +#include + #include #include @@ -42,7 +44,7 @@ namespace collision { class CollisionFilter; -struct CollisionOption +struct DART_API CollisionOption { /// Flag whether the collision detector computes contact information (contact /// point, normal, and penetration depth). If it is set to false, only the diff --git a/dart/collision/CollisionResult.hpp b/dart/collision/CollisionResult.hpp index cc79873df7c80..4d2ed5736e892 100644 --- a/dart/collision/CollisionResult.hpp +++ b/dart/collision/CollisionResult.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_COLLISIONRESULT_HPP_ #define DART_COLLISION_COLLISIONRESULT_HPP_ +#include + #include #include @@ -49,7 +51,7 @@ class ShapeFrame; namespace collision { -class CollisionResult +class DART_API CollisionResult { public: /// Add one contact diff --git a/dart/collision/Contact.hpp b/dart/collision/Contact.hpp index 2947c83d200f0..efadd34e4ad46 100644 --- a/dart/collision/Contact.hpp +++ b/dart/collision/Contact.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_CONTACT_HPP_ #define DART_COLLISION_CONTACT_HPP_ +#include + #include #include @@ -43,7 +45,7 @@ namespace dart { namespace collision { /// Contact information -struct Contact +struct DART_API Contact { /// Default constructor Contact(); diff --git a/dart/collision/DistanceFilter.hpp b/dart/collision/DistanceFilter.hpp index f032ff57c6510..5213e56808805 100644 --- a/dart/collision/DistanceFilter.hpp +++ b/dart/collision/DistanceFilter.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_DISTANCEFILTER_HPP_ #define DART_COLLISION_DISTANCEFILTER_HPP_ +#include + namespace dart { namespace dynamics { @@ -43,13 +45,13 @@ namespace collision { class CollisionObject; -struct DistanceFilter +struct DART_API DistanceFilter { virtual bool needDistance( const CollisionObject* object1, const CollisionObject* object2) const = 0; }; -struct BodyNodeDistanceFilter : DistanceFilter +struct DART_API BodyNodeDistanceFilter : DistanceFilter { bool needDistance( const CollisionObject* object1, diff --git a/dart/collision/DistanceOption.hpp b/dart/collision/DistanceOption.hpp index 508a619126494..4868389fb3e10 100644 --- a/dart/collision/DistanceOption.hpp +++ b/dart/collision/DistanceOption.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_DISTANCE_OPTION_HPP_ #define DART_COLLISION_DISTANCE_OPTION_HPP_ +#include + #include #include @@ -42,7 +44,7 @@ namespace collision { struct DistanceFilter; -struct DistanceOption +struct DART_API DistanceOption { /// Whether to calculate the nearest points. /// diff --git a/dart/collision/DistanceResult.hpp b/dart/collision/DistanceResult.hpp index c0c8ac13787ee..35885bc1110d9 100644 --- a/dart/collision/DistanceResult.hpp +++ b/dart/collision/DistanceResult.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_DISTANCE_RESULT_HPP_ #define DART_COLLISION_DISTANCE_RESULT_HPP_ +#include + #include namespace dart { @@ -43,7 +45,7 @@ class ShapeFrame; namespace collision { -struct DistanceResult +struct DART_API DistanceResult { /// Minimum \b singed distance between the checked Shape pairs. /// diff --git a/dart/collision/RaycastOption.hpp b/dart/collision/RaycastOption.hpp index 838eca4495c21..874e96a90c2da 100644 --- a/dart/collision/RaycastOption.hpp +++ b/dart/collision/RaycastOption.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_RAYCASTOPTION_HPP_ #define DART_COLLISION_RAYCASTOPTION_HPP_ +#include + #include #include @@ -40,7 +42,7 @@ namespace dart { namespace collision { -struct RaycastOption +struct DART_API RaycastOption { /// Constructor RaycastOption(bool enableAllHits = false, bool sortByClosest = false); diff --git a/dart/collision/RaycastResult.hpp b/dart/collision/RaycastResult.hpp index 3e29712646f13..c20c2b95788e9 100644 --- a/dart/collision/RaycastResult.hpp +++ b/dart/collision/RaycastResult.hpp @@ -33,6 +33,8 @@ #ifndef DART_COLLISION_RAYCASTRESULT_HPP_ #define DART_COLLISION_RAYCASTRESULT_HPP_ +#include + #include #include @@ -42,7 +44,7 @@ namespace collision { class CollisionObject; -struct RayHit +struct DART_API RayHit { /// The collision object the ray hit const CollisionObject* mCollisionObject; @@ -60,7 +62,7 @@ struct RayHit RayHit(); }; -struct RaycastResult +struct DART_API RaycastResult { /// Clear the result void clear(); diff --git a/dart/common/Aspect.hpp b/dart/common/Aspect.hpp index d31096a4ccfb1..55f95d4c03f83 100644 --- a/dart/common/Aspect.hpp +++ b/dart/common/Aspect.hpp @@ -33,6 +33,8 @@ #ifndef DART_COMMON_ASPECT_HPP_ #define DART_COMMON_ASPECT_HPP_ +#include + #include #include #include diff --git a/dart/common/MemoryAllocator.hpp b/dart/common/MemoryAllocator.hpp index 101c7f81a2d8b..fff87a684fdd2 100644 --- a/dart/common/MemoryAllocator.hpp +++ b/dart/common/MemoryAllocator.hpp @@ -35,6 +35,8 @@ #include +#include + #include #include diff --git a/dart/common/Observer.hpp b/dart/common/Observer.hpp index 2fabe2d322d0e..6257a85735cc5 100644 --- a/dart/common/Observer.hpp +++ b/dart/common/Observer.hpp @@ -33,6 +33,8 @@ #ifndef DART_COMMON_OBSERVER_HPP_ #define DART_COMMON_OBSERVER_HPP_ +#include + #include namespace dart { @@ -48,7 +50,7 @@ class Subject; /// dart::sub_ptr is a templated smart pointer that will change itself into a /// nullptr when its Subject is destroyed. It offers one of the easiest ways to /// take advantage of the Subject/Observer pattern. -class Observer +class DART_API Observer { public: friend class Subject; diff --git a/dart/common/Resource.hpp b/dart/common/Resource.hpp index 12014c7ed6ca5..2d7f91d2ff225 100644 --- a/dart/common/Resource.hpp +++ b/dart/common/Resource.hpp @@ -33,6 +33,8 @@ #ifndef DART_COMMON_RESOURCE_HPP_ #define DART_COMMON_RESOURCE_HPP_ +#include + #include #include @@ -46,7 +48,7 @@ namespace common { /// It is expected that each \a ResourceRetriever will provide a concrete / /// instantiation of the Resource class. This interface exposes an similar API /// to that of the the standard C file manipulation functions. -class Resource +class DART_API Resource { public: /// \brief Position to seek relative to. diff --git a/dart/common/ResourceRetriever.hpp b/dart/common/ResourceRetriever.hpp index 938229c2e081c..48da494adacd0 100644 --- a/dart/common/ResourceRetriever.hpp +++ b/dart/common/ResourceRetriever.hpp @@ -44,7 +44,7 @@ namespace common { /// ResourceRetriever provides methods for testing for the existance of and /// accessing the content of a resource specified by URI. -class ResourceRetriever +class DART_API ResourceRetriever { public: virtual ~ResourceRetriever() = default; diff --git a/dart/common/SharedLibrary.hpp b/dart/common/SharedLibrary.hpp index 99e2ebc1351c8..cd27f1a0e37ad 100644 --- a/dart/common/SharedLibrary.hpp +++ b/dart/common/SharedLibrary.hpp @@ -33,6 +33,8 @@ #ifndef DART_COMMON_SHAREDLIBRARY_HPP_ #define DART_COMMON_SHAREDLIBRARY_HPP_ +#include + #include #include #include @@ -84,7 +86,7 @@ class SharedLibraryManager; } // namespace detail /// SharedLibrary is a RAII object wrapping a shared library. -class SharedLibrary +class DART_API SharedLibrary { protected: enum ProtectedConstructionTag diff --git a/dart/common/Stopwatch.hpp b/dart/common/Stopwatch.hpp index 2f6971de5c047..9e646a1c9a0e7 100644 --- a/dart/common/Stopwatch.hpp +++ b/dart/common/Stopwatch.hpp @@ -33,6 +33,8 @@ #ifndef DART_COMMON_STOPWATCH_HPP_ #define DART_COMMON_STOPWATCH_HPP_ +#include + #include #include @@ -114,22 +116,22 @@ class Stopwatch final /// tic(); /// auto elapsedS = toc(); // prints and returns the elapsed time /// \endcode -void tic(); +DART_API void tic(); /// Returns the elapsed time in seconds since the last tic() call. -double toc(bool print = false); +DART_API double toc(bool print = false); /// Returns the elapsed time in seconds since the last tic() call. -double tocS(bool print = false); +DART_API double tocS(bool print = false); /// Returns the elapsed time in milliseconds since the last tic() call. -double tocMS(bool print = false); +DART_API double tocMS(bool print = false); /// Returns the elapsed time in microseconds since the last tic() call. -double tocUS(bool print = false); +DART_API double tocUS(bool print = false); /// Returns the elapsed time in nanoseconds since the last tic() call. -double tocNS(bool print = false); +DART_API double tocNS(bool print = false); using StopwatchS = Stopwatch; using StopwatchMS = Stopwatch; diff --git a/dart/common/String.hpp b/dart/common/String.hpp index 1657648be3472..7ab07f5765b97 100644 --- a/dart/common/String.hpp +++ b/dart/common/String.hpp @@ -33,37 +33,39 @@ #ifndef DART_COMMON_STRING_HPP_ #define DART_COMMON_STRING_HPP_ +#include + #include #include namespace dart::common { /// Converts string to upper cases -std::string toUpper(std::string str); +DART_API [[nodiscard]] std::string toUpper(std::string str); /// Converts string to upper cases in place -void toUpperInPlace(std::string& str); +DART_API void toUpperInPlace(std::string& str); /// Converts string to lower cases -std::string toLower(std::string str); +DART_API [[nodiscard]] std::string toLower(std::string str); /// Converts string to lower cases in place -void toLowerInPlace(std::string& str); +DART_API void toLowerInPlace(std::string& str); /// Trims both sides of string -std::string trim( +DART_API [[nodiscard]] std::string trim( const std::string& str, const std::string& whitespaces = " \n\r\t"); /// Trims left side of string -std::string trimLeft( +DART_API [[nodiscard]] std::string trimLeft( const std::string& str, const std::string& whitespaces = " \n\r\t"); /// Trims right side of string -std::string trimRight( +DART_API [[nodiscard]] std::string trimRight( const std::string& str, const std::string& whitespaces = " \n\r\t"); /// Splits string given delimiters -std::vector split( +DART_API [[nodiscard]] std::vector split( const std::string& str, const std::string& delimiters = " \n\r\t"); } // namespace dart::common diff --git a/dart/common/Uri.hpp b/dart/common/Uri.hpp index 1dd3b06f8258f..25ef64efcc259 100644 --- a/dart/common/Uri.hpp +++ b/dart/common/Uri.hpp @@ -34,6 +34,7 @@ #define DART_COMMON_URI_HPP_ #include + #include namespace dart { diff --git a/dart/dynamics/ArrowShape.hpp b/dart/dynamics/ArrowShape.hpp index 31bdf7c948da7..59a4e1d86a930 100644 --- a/dart/dynamics/ArrowShape.hpp +++ b/dart/dynamics/ArrowShape.hpp @@ -38,7 +38,7 @@ namespace dart { namespace dynamics { -class ArrowShape : public MeshShape +class DART_API ArrowShape : public MeshShape { public: struct Properties diff --git a/dart/dynamics/BallJoint.hpp b/dart/dynamics/BallJoint.hpp index 9eccb52083f23..801bc44f2e2fd 100644 --- a/dart/dynamics/BallJoint.hpp +++ b/dart/dynamics/BallJoint.hpp @@ -41,7 +41,7 @@ namespace dart { namespace dynamics { /// class BallJoint -class BallJoint : public GenericJoint +class DART_API BallJoint : public GenericJoint { public: friend class Skeleton; diff --git a/dart/dynamics/BoxShape.hpp b/dart/dynamics/BoxShape.hpp index 6c2444d9ce47a..eed8d531a44ed 100644 --- a/dart/dynamics/BoxShape.hpp +++ b/dart/dynamics/BoxShape.hpp @@ -38,7 +38,7 @@ namespace dart { namespace dynamics { -class BoxShape : public Shape +class DART_API BoxShape : public Shape { public: /// \brief Constructor. diff --git a/dart/dynamics/Branch.hpp b/dart/dynamics/Branch.hpp index 1ea82d287bce4..b09611e6ecba2 100644 --- a/dart/dynamics/Branch.hpp +++ b/dart/dynamics/Branch.hpp @@ -41,7 +41,7 @@ namespace dynamics { /// Branch is a specialized type of Linkage that represents a complete subtree /// of a Skeleton. The Branch will start at a specific BodyNode and will include /// every BodyNode that descends from it, all the way to the leaves. -class Branch : public Linkage +class DART_API Branch : public Linkage { public: struct Criteria diff --git a/dart/dynamics/CapsuleShape.hpp b/dart/dynamics/CapsuleShape.hpp index 4c2810feb157a..76de2b2af62ff 100644 --- a/dart/dynamics/CapsuleShape.hpp +++ b/dart/dynamics/CapsuleShape.hpp @@ -40,7 +40,7 @@ namespace dynamics { /// CapsuleShape represents a three-dimensional geometric shape consisting of a /// cylinder with hemispherical ends. -class CapsuleShape : public Shape +class DART_API CapsuleShape : public Shape { public: /// Constructor. diff --git a/dart/dynamics/Chain.hpp b/dart/dynamics/Chain.hpp index fe614bb355d2d..c6065c59bedf1 100644 --- a/dart/dynamics/Chain.hpp +++ b/dart/dynamics/Chain.hpp @@ -43,7 +43,7 @@ namespace dynamics { /// specified BodyNode and include every BodyNode on the way to a target /// BodyNode, except it will stop if it encounters a branching (BodyNode with /// multiple child BodyNodes) or a FreeJoint. -class Chain : public Linkage +class DART_API Chain : public Linkage { public: struct Criteria diff --git a/dart/dynamics/ConeShape.hpp b/dart/dynamics/ConeShape.hpp index 8d74f07cd3abc..345cd7161bec7 100644 --- a/dart/dynamics/ConeShape.hpp +++ b/dart/dynamics/ConeShape.hpp @@ -40,7 +40,7 @@ namespace dynamics { /// ConeShape represents a three-dimensional geometric shape that tapers /// smoothly from a flat circular base to a point called the apex or vertex. -class ConeShape : public Shape +class DART_API ConeShape : public Shape { public: /// Constructor. diff --git a/dart/dynamics/CylinderShape.hpp b/dart/dynamics/CylinderShape.hpp index 3a8f6ef3f1759..daf73ee3ebd29 100644 --- a/dart/dynamics/CylinderShape.hpp +++ b/dart/dynamics/CylinderShape.hpp @@ -38,7 +38,7 @@ namespace dart { namespace dynamics { -class CylinderShape : public Shape +class DART_API CylinderShape : public Shape { public: /// \brief Constructor. diff --git a/dart/dynamics/DegreeOfFreedom.hpp b/dart/dynamics/DegreeOfFreedom.hpp index 8daa0b88c94bc..5543e23f5dbf7 100644 --- a/dart/dynamics/DegreeOfFreedom.hpp +++ b/dart/dynamics/DegreeOfFreedom.hpp @@ -33,6 +33,8 @@ #ifndef DART_DYNAMICS_DEGREEOFFREEDOM_HPP_ #define DART_DYNAMICS_DEGREEOFFREEDOM_HPP_ +#include + #include #include @@ -53,7 +55,7 @@ class BodyNode; /// DegreeOfFreedom class is a proxy class for accessing single degrees of /// freedom (aka generalized coordinates) of the Skeleton. DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class DegreeOfFreedom : public virtual common::Subject +class DART_API DegreeOfFreedom : public virtual common::Subject { public: friend class Joint; diff --git a/dart/dynamics/EllipsoidShape.hpp b/dart/dynamics/EllipsoidShape.hpp index c28717c8c8f83..c294cc5f79e0c 100644 --- a/dart/dynamics/EllipsoidShape.hpp +++ b/dart/dynamics/EllipsoidShape.hpp @@ -38,7 +38,7 @@ namespace dart { namespace dynamics { -class EllipsoidShape : public Shape +class DART_API EllipsoidShape : public Shape { public: /// \brief Constructor. diff --git a/dart/dynamics/EndEffector.hpp b/dart/dynamics/EndEffector.hpp index b5c1da3a9a208..8c6c4779a872c 100644 --- a/dart/dynamics/EndEffector.hpp +++ b/dart/dynamics/EndEffector.hpp @@ -49,12 +49,13 @@ class Skeleton; class EndEffector; //============================================================================== -class Support final : public common::AspectWithStateAndVersionedProperties< - Support, - detail::SupportStateData, - detail::SupportPropertiesData, - EndEffector, - &detail::SupportUpdate> +class DART_API Support final + : public common::AspectWithStateAndVersionedProperties< + Support, + detail::SupportStateData, + detail::SupportPropertiesData, + EndEffector, + &detail::SupportUpdate> { public: DART_COMMON_ASPECT_STATE_PROPERTY_CONSTRUCTORS(Support) @@ -75,10 +76,10 @@ class Support final : public common::AspectWithStateAndVersionedProperties< }; //============================================================================== -class EndEffector final : public common::EmbedPropertiesOnTopOf< - EndEffector, - detail::EndEffectorProperties, - detail::EndEffectorCompositeBase> +class DART_API EndEffector final : public common::EmbedPropertiesOnTopOf< + EndEffector, + detail::EndEffectorProperties, + detail::EndEffectorCompositeBase> { public: friend class Skeleton; diff --git a/dart/dynamics/EulerJoint.hpp b/dart/dynamics/EulerJoint.hpp index d07157e5cc99d..00d7598e809ea 100644 --- a/dart/dynamics/EulerJoint.hpp +++ b/dart/dynamics/EulerJoint.hpp @@ -39,7 +39,7 @@ namespace dart { namespace dynamics { /// class EulerJoint -class EulerJoint : public detail::EulerJointBase +class DART_API EulerJoint : public detail::EulerJointBase { public: friend class Skeleton; diff --git a/dart/dynamics/FixedFrame.hpp b/dart/dynamics/FixedFrame.hpp index d4d2c5d121562..3337750ac8a02 100644 --- a/dart/dynamics/FixedFrame.hpp +++ b/dart/dynamics/FixedFrame.hpp @@ -47,7 +47,7 @@ namespace dynamics { /// its relative transform is set. However, classes that inherit the FixedFrame /// class may alter its relative transform or change what its parent Frame is. DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class FixedFrame +class DART_API FixedFrame : public virtual Frame, public virtual common::VersionCounter, public common::EmbedProperties diff --git a/dart/dynamics/FixedJacobianNode.hpp b/dart/dynamics/FixedJacobianNode.hpp index c2c54ee57fabb..dbb5b7f07d301 100644 --- a/dart/dynamics/FixedJacobianNode.hpp +++ b/dart/dynamics/FixedJacobianNode.hpp @@ -38,8 +38,9 @@ namespace dart { namespace dynamics { -class FixedJacobianNode : public detail::FixedJacobianNodeCompositeBase, - public AccessoryNode +class DART_API FixedJacobianNode + : public detail::FixedJacobianNodeCompositeBase, + public AccessoryNode { public: /// Set the current relative transform of this Fixed Frame diff --git a/dart/dynamics/Frame.hpp b/dart/dynamics/Frame.hpp index e1f43d9df3150..8230b5a5746e3 100644 --- a/dart/dynamics/Frame.hpp +++ b/dart/dynamics/Frame.hpp @@ -55,7 +55,7 @@ namespace dynamics { /// so-called "diamond problem". Because of that, the Entity's constructor will /// be called directly by the most derived class's constructor. DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class Frame : public virtual Entity +class DART_API Frame : public virtual Entity { public: friend class Entity; diff --git a/dart/dynamics/FreeJoint.hpp b/dart/dynamics/FreeJoint.hpp index 67f684c22e306..bba06ca32ceb9 100644 --- a/dart/dynamics/FreeJoint.hpp +++ b/dart/dynamics/FreeJoint.hpp @@ -45,7 +45,7 @@ namespace dart { namespace dynamics { /// class FreeJoint -class FreeJoint : public GenericJoint +class DART_API FreeJoint : public GenericJoint { public: friend class Skeleton; diff --git a/dart/dynamics/Group.hpp b/dart/dynamics/Group.hpp index 0327adb3f3278..02d32db771eda 100644 --- a/dart/dynamics/Group.hpp +++ b/dart/dynamics/Group.hpp @@ -38,7 +38,7 @@ namespace dart { namespace dynamics { -class Group : public ReferentialSkeleton +class DART_API Group : public ReferentialSkeleton { public: /// Create a Group out of a set of BodyNodes. If _includeJoints is true, the diff --git a/dart/dynamics/HierarchicalIK.hpp b/dart/dynamics/HierarchicalIK.hpp index d912ad957cad8..ec847c896a744 100644 --- a/dart/dynamics/HierarchicalIK.hpp +++ b/dart/dynamics/HierarchicalIK.hpp @@ -60,7 +60,7 @@ typedef std::vector > > /// put into the IK modules' Problems. Any additional constraints or objectives /// that you want the HierarchicalIK to solve should be put directly into the /// HierarchicalIK's Problem. -class HierarchicalIK : public common::Subject +class DART_API HierarchicalIK : public common::Subject { public: /// Virtual destructor diff --git a/dart/dynamics/IkFast.hpp b/dart/dynamics/IkFast.hpp index 0644ef9a25f45..9aa9e1e875958 100644 --- a/dart/dynamics/IkFast.hpp +++ b/dart/dynamics/IkFast.hpp @@ -47,7 +47,7 @@ namespace dynamics { /// /// The detail of IkFast can be found here: /// http://openrave.org/docs/0.8.2/openravepy/ikfast/ -class IkFast : public InverseKinematics::Analytical +class DART_API IkFast : public InverseKinematics::Analytical { public: /// Inverse kinematics types supported by IkFast diff --git a/dart/dynamics/Inertia.hpp b/dart/dynamics/Inertia.hpp index d2bbd5014b122..df9195432ee0a 100644 --- a/dart/dynamics/Inertia.hpp +++ b/dart/dynamics/Inertia.hpp @@ -33,6 +33,8 @@ #ifndef DART_DYNAMICS_INERTIA_HPP_ #define DART_DYNAMICS_INERTIA_HPP_ +#include + #include #include @@ -40,7 +42,7 @@ namespace dart { namespace dynamics { -class Inertia +class DART_API Inertia { public: /// Enumeration for minimal inertia parameters diff --git a/dart/dynamics/InverseKinematics.hpp b/dart/dynamics/InverseKinematics.hpp index 1dafe924f4564..6eeec51c63578 100644 --- a/dart/dynamics/InverseKinematics.hpp +++ b/dart/dynamics/InverseKinematics.hpp @@ -75,7 +75,7 @@ const double DefaultIKLinearWeight = 1.0; /// safely cloned over to another JacobianNode, as long as every /// optimizer::Function that depends on the JacobianNode inherits the /// InverseKinematics::Function class and correctly overloads the clone function -class InverseKinematics : public common::Subject +class DART_API InverseKinematics : public common::Subject { public: /// Create an InverseKinematics module for a specified node diff --git a/dart/dynamics/JacobianNode.hpp b/dart/dynamics/JacobianNode.hpp index 5adb0f4ce60aa..a645fbda48054 100644 --- a/dart/dynamics/JacobianNode.hpp +++ b/dart/dynamics/JacobianNode.hpp @@ -51,7 +51,7 @@ class InverseKinematics; /// EndEffectors to both be used as references for IK modules. This is a pure /// abstract class. DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class JacobianNode : public virtual Frame, public Node +class DART_API JacobianNode : public virtual Frame, public Node { public: /// Virtual destructor diff --git a/dart/dynamics/Joint.hpp b/dart/dynamics/Joint.hpp index a49a787fdaae0..79f77d3fc1a67 100644 --- a/dart/dynamics/Joint.hpp +++ b/dart/dynamics/Joint.hpp @@ -59,9 +59,10 @@ class DegreeOfFreedom; /// class Joint DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class Joint : public virtual common::Subject, - public virtual common::VersionCounter, - public common::EmbedProperties +class DART_API Joint + : public virtual common::Subject, + public virtual common::VersionCounter, + public common::EmbedProperties { public: using CompositeProperties = common::Composite::Properties; diff --git a/dart/dynamics/LineSegmentShape.hpp b/dart/dynamics/LineSegmentShape.hpp index 5d611bd8a68ac..3e6b261331a89 100644 --- a/dart/dynamics/LineSegmentShape.hpp +++ b/dart/dynamics/LineSegmentShape.hpp @@ -42,7 +42,7 @@ namespace dynamics { /// can consist of a single line segment or many interconnected line segments. /// Note: LineSegmentShape may NOT be used as a collision shape for BodyNodes, /// but it may be used for visualization purposes. -class LineSegmentShape : public Shape +class DART_API LineSegmentShape : public Shape { public: /// Default constructor diff --git a/dart/dynamics/Linkage.hpp b/dart/dynamics/Linkage.hpp index f4d7487f46dc0..3e916e9fad841 100644 --- a/dart/dynamics/Linkage.hpp +++ b/dart/dynamics/Linkage.hpp @@ -51,7 +51,7 @@ namespace dynamics { /// so that they match whatever assembly they had the last time /// Linkage::reassemble() was called (or the assembly that they had when the /// Linkage was constructed, if Linkage::reassemble has never been called). -class Linkage : public ReferentialSkeleton +class DART_API Linkage : public ReferentialSkeleton { public: /// The Criteria class is used to specify how a Linkage should be constructed diff --git a/dart/dynamics/Marker.hpp b/dart/dynamics/Marker.hpp index 7cbf7e15a75b9..c42dc430346c6 100644 --- a/dart/dynamics/Marker.hpp +++ b/dart/dynamics/Marker.hpp @@ -45,10 +45,10 @@ namespace dynamics { class BodyNode; -class Marker final : public common::EmbedPropertiesOnTopOf< - Marker, - detail::MarkerProperties, - FixedJacobianNode> +class DART_API Marker final : public common::EmbedPropertiesOnTopOf< + Marker, + detail::MarkerProperties, + FixedJacobianNode> { public: using ConstraintType = detail::MarkerProperties::ConstraintType; diff --git a/dart/dynamics/MeshShape.hpp b/dart/dynamics/MeshShape.hpp index acf4b9e39c84b..e028d124419d7 100644 --- a/dart/dynamics/MeshShape.hpp +++ b/dart/dynamics/MeshShape.hpp @@ -44,7 +44,7 @@ namespace dart { namespace dynamics { -class MeshShape : public Shape +class DART_API MeshShape : public Shape { public: enum ColorMode diff --git a/dart/dynamics/MetaSkeleton.hpp b/dart/dynamics/MetaSkeleton.hpp index a83affc750222..589668f48e647 100644 --- a/dart/dynamics/MetaSkeleton.hpp +++ b/dart/dynamics/MetaSkeleton.hpp @@ -59,7 +59,7 @@ class DegreeOfFreedom; /// MetaSkeleton is a pure abstract base class that provides a common interface /// for obtaining data (such as Jacobians and Mass Matrices) from groups of /// BodyNodes. -class MetaSkeleton : public common::Subject +class DART_API MetaSkeleton : public common::Subject { public: using NameChangedSignal = common::Signal; diff --git a/dart/dynamics/Node.hpp b/dart/dynamics/Node.hpp index 41505d7db8ffe..4feda96f36eb1 100644 --- a/dart/dynamics/Node.hpp +++ b/dart/dynamics/Node.hpp @@ -76,8 +76,8 @@ class NodeDestructor final /// In most cases, when creating your own custom Node class, you will also want /// to inherit from AccessoryNode using CRTP. DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class Node : public virtual common::Subject, - public virtual common::VersionCounter +class DART_API Node : public virtual common::Subject, + public virtual common::VersionCounter { public: friend class BodyNode; diff --git a/dart/dynamics/PlanarJoint.hpp b/dart/dynamics/PlanarJoint.hpp index a175de33e9dc6..6256e7061b8df 100644 --- a/dart/dynamics/PlanarJoint.hpp +++ b/dart/dynamics/PlanarJoint.hpp @@ -44,7 +44,7 @@ namespace dynamics { /// First and second coordiantes represent translation along first and second /// translational axes, respectively. Third coordinate represents rotation /// along rotational axis. -class PlanarJoint : public detail::PlanarJointBase +class DART_API PlanarJoint : public detail::PlanarJointBase { public: friend class Skeleton; diff --git a/dart/dynamics/PlaneShape.hpp b/dart/dynamics/PlaneShape.hpp index e50b2e3f23947..abb720fcf6168 100644 --- a/dart/dynamics/PlaneShape.hpp +++ b/dart/dynamics/PlaneShape.hpp @@ -39,7 +39,7 @@ namespace dart { namespace dynamics { /// PlaneShape represents infinite plane has normal and offset as properties. -class PlaneShape : public Shape +class DART_API PlaneShape : public Shape { public: /// Constructor diff --git a/dart/dynamics/PointCloudShape.hpp b/dart/dynamics/PointCloudShape.hpp index b55d8b1bdaa6b..0f66c6db9ac9f 100644 --- a/dart/dynamics/PointCloudShape.hpp +++ b/dart/dynamics/PointCloudShape.hpp @@ -43,7 +43,7 @@ namespace dart { namespace dynamics { /// The PointCloudShape represents point cloud data. -class PointCloudShape : public Shape +class DART_API PointCloudShape : public Shape { public: enum ColorMode diff --git a/dart/dynamics/PointMass.hpp b/dart/dynamics/PointMass.hpp index e9c1f5f411c42..7582783355478 100644 --- a/dart/dynamics/PointMass.hpp +++ b/dart/dynamics/PointMass.hpp @@ -50,7 +50,7 @@ class SoftBodyNode; class PointMassNotifier; /// -class PointMass : public common::Subject +class DART_API PointMass : public common::Subject { public: friend class SoftBodyNode; diff --git a/dart/dynamics/PrismaticJoint.hpp b/dart/dynamics/PrismaticJoint.hpp index 7cfa1feafa611..c12006f06e98c 100644 --- a/dart/dynamics/PrismaticJoint.hpp +++ b/dart/dynamics/PrismaticJoint.hpp @@ -39,7 +39,7 @@ namespace dart { namespace dynamics { /// class RevoluteJoint -class PrismaticJoint : public detail::PrismaticJointBase +class DART_API PrismaticJoint : public detail::PrismaticJointBase { public: friend class Skeleton; diff --git a/dart/dynamics/PyramidShape.hpp b/dart/dynamics/PyramidShape.hpp index a6d661f81206d..efa93ed6d152d 100644 --- a/dart/dynamics/PyramidShape.hpp +++ b/dart/dynamics/PyramidShape.hpp @@ -46,7 +46,7 @@ namespace dynamics { /// to the apex is aligned with the Z-axis while the lateral and the /// longitudinal lengths of the base are aligned with the X-axis and Y-axis, /// respectively. -class PyramidShape : public Shape +class DART_API PyramidShape : public Shape { public: /// Constructor. diff --git a/dart/dynamics/ReferentialSkeleton.hpp b/dart/dynamics/ReferentialSkeleton.hpp index d128aa31ca132..e4046bd2da6f7 100644 --- a/dart/dynamics/ReferentialSkeleton.hpp +++ b/dart/dynamics/ReferentialSkeleton.hpp @@ -44,7 +44,7 @@ namespace dynamics { /// ReferentialSkeleton is a base class used to implement Linkage, Group, and /// other classes that are used to reference subsections of Skeletons. -class ReferentialSkeleton : public MetaSkeleton +class DART_API ReferentialSkeleton : public MetaSkeleton { public: /// Remove copy operator diff --git a/dart/dynamics/RevoluteJoint.hpp b/dart/dynamics/RevoluteJoint.hpp index c4581cd523663..5999cae161130 100644 --- a/dart/dynamics/RevoluteJoint.hpp +++ b/dart/dynamics/RevoluteJoint.hpp @@ -39,7 +39,7 @@ namespace dart { namespace dynamics { /// class RevoluteJoint -class RevoluteJoint : public detail::RevoluteJointBase +class DART_API RevoluteJoint : public detail::RevoluteJointBase { public: friend class Skeleton; diff --git a/dart/dynamics/ScrewJoint.hpp b/dart/dynamics/ScrewJoint.hpp index eee12d9a1e98e..d37747092d026 100644 --- a/dart/dynamics/ScrewJoint.hpp +++ b/dart/dynamics/ScrewJoint.hpp @@ -39,7 +39,7 @@ namespace dart { namespace dynamics { /// class ScrewJoint -class ScrewJoint : public detail::ScrewJointBase +class DART_API ScrewJoint : public detail::ScrewJointBase { public: friend class Skeleton; diff --git a/dart/dynamics/Shape.hpp b/dart/dynamics/Shape.hpp index 2480eed8b2662..75fca37113ca5 100644 --- a/dart/dynamics/Shape.hpp +++ b/dart/dynamics/Shape.hpp @@ -52,9 +52,9 @@ namespace dart { namespace dynamics { DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class Shape : public virtual common::Subject, - public virtual common::VersionCounter, - public common::Castable +class DART_API Shape : public virtual common::Subject, + public virtual common::VersionCounter, + public common::Castable { public: using VersionChangedSignal diff --git a/dart/dynamics/ShapeFrame.hpp b/dart/dynamics/ShapeFrame.hpp index 9c0ee2d30aa66..7d35ab127baca 100644 --- a/dart/dynamics/ShapeFrame.hpp +++ b/dart/dynamics/ShapeFrame.hpp @@ -48,10 +48,11 @@ namespace dart { namespace dynamics { //============================================================================== -class VisualAspect final : public common::AspectWithVersionedProperties< - VisualAspect, - detail::VisualAspectProperties, - ShapeFrame> +class DART_API VisualAspect final + : public common::AspectWithVersionedProperties< + VisualAspect, + detail::VisualAspectProperties, + ShapeFrame> { public: using Base = common::AspectWithVersionedProperties< @@ -111,10 +112,11 @@ class VisualAspect final : public common::AspectWithVersionedProperties< }; //============================================================================== -class CollisionAspect final : public common::AspectWithVersionedProperties< - CollisionAspect, - detail::CollisionAspectProperties, - ShapeFrame> +class DART_API CollisionAspect final + : public common::AspectWithVersionedProperties< + CollisionAspect, + detail::CollisionAspectProperties, + ShapeFrame> { public: CollisionAspect(const CollisionAspect&) = delete; @@ -129,10 +131,11 @@ class CollisionAspect final : public common::AspectWithVersionedProperties< }; //============================================================================== -class DynamicsAspect final : public common::AspectWithVersionedProperties< - DynamicsAspect, - detail::DynamicsAspectProperties, - ShapeFrame> +class DART_API DynamicsAspect final + : public common::AspectWithVersionedProperties< + DynamicsAspect, + detail::DynamicsAspectProperties, + ShapeFrame> { public: using Base = common::AspectWithVersionedProperties< @@ -187,9 +190,9 @@ class DynamicsAspect final : public common::AspectWithVersionedProperties< //============================================================================== DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class ShapeFrame : public virtual common::VersionCounter, - public detail::ShapeFrameCompositeBase, - public virtual Frame +class DART_API ShapeFrame : public virtual common::VersionCounter, + public detail::ShapeFrameCompositeBase, + public virtual Frame { public: friend class BodyNode; diff --git a/dart/dynamics/ShapeNode.hpp b/dart/dynamics/ShapeNode.hpp index 2e66e481b373a..ac5e6f908dbcf 100644 --- a/dart/dynamics/ShapeNode.hpp +++ b/dart/dynamics/ShapeNode.hpp @@ -46,7 +46,7 @@ class VisualAspect; class CollisionAspect; class DynamicsAspect; -class ShapeNode : public detail::ShapeNodeCompositeBase +class DART_API ShapeNode : public detail::ShapeNodeCompositeBase { public: friend class BodyNode; diff --git a/dart/dynamics/SharedLibraryIkFast.hpp b/dart/dynamics/SharedLibraryIkFast.hpp index 97cd7a77af75d..875a3dfc74b1a 100644 --- a/dart/dynamics/SharedLibraryIkFast.hpp +++ b/dart/dynamics/SharedLibraryIkFast.hpp @@ -44,7 +44,7 @@ namespace dynamics { /// /// The detail of IkFast can be found here: /// http://openrave.org/docs/0.8.2/openravepy/ikfast/ -class SharedLibraryIkFast : public IkFast +class DART_API SharedLibraryIkFast : public IkFast { public: /// Constructor diff --git a/dart/dynamics/SimpleFrame.hpp b/dart/dynamics/SimpleFrame.hpp index 2d31df42c1d3b..236b6a25bde41 100644 --- a/dart/dynamics/SimpleFrame.hpp +++ b/dart/dynamics/SimpleFrame.hpp @@ -48,7 +48,7 @@ namespace dynamics { /// (such as position, velocity, and acceleration) can be modified. Conversely, /// the SimpleFrame class is nothing but a simple abstract Frame whose /// properties can be arbitrarily set and modified by the user. -class SimpleFrame : public Detachable, public ShapeFrame +class DART_API SimpleFrame : public Detachable, public ShapeFrame { public: DART_DEFINE_ALIGNED_SHARED_OBJECT_CREATOR(SimpleFrame) diff --git a/dart/dynamics/Skeleton.hpp b/dart/dynamics/Skeleton.hpp index 9d4259802e24e..8785447f10a6d 100644 --- a/dart/dynamics/Skeleton.hpp +++ b/dart/dynamics/Skeleton.hpp @@ -54,10 +54,11 @@ namespace dynamics { /// class Skeleton DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class Skeleton : public virtual common::VersionCounter, - public MetaSkeleton, - public SkeletonSpecializedFor, - public detail::SkeletonAspectBase +class DART_API Skeleton + : public virtual common::VersionCounter, + public MetaSkeleton, + public SkeletonSpecializedFor, + public detail::SkeletonAspectBase { public: // Some of non-virtual functions of MetaSkeleton are hidden because of the diff --git a/dart/dynamics/SoftBodyNode.hpp b/dart/dynamics/SoftBodyNode.hpp index 877776c353323..5a4f23f3d41f3 100644 --- a/dart/dynamics/SoftBodyNode.hpp +++ b/dart/dynamics/SoftBodyNode.hpp @@ -42,7 +42,7 @@ namespace dynamics { /// /// This class is implementation of Sumit Jain and C. Karen Liu's paper: /// http://www.cc.gatech.edu/graphics/projects/Sumit/homepage/projects/softcontacts/index.html -class SoftBodyNode : public detail::SoftBodyNodeBase +class DART_API SoftBodyNode : public detail::SoftBodyNodeBase { public: using UniqueProperties = detail::SoftBodyNodeUniqueProperties; diff --git a/dart/dynamics/SoftMeshShape.hpp b/dart/dynamics/SoftMeshShape.hpp index a9212f93e94dc..75bbf8c98b6c1 100644 --- a/dart/dynamics/SoftMeshShape.hpp +++ b/dart/dynamics/SoftMeshShape.hpp @@ -44,7 +44,7 @@ namespace dynamics { class SoftBodyNode; // TODO(JS): Implement -class SoftMeshShape : public Shape +class DART_API SoftMeshShape : public Shape { public: friend class SoftBodyNode; diff --git a/dart/dynamics/SphereShape.hpp b/dart/dynamics/SphereShape.hpp index 404518ea756c9..7f9657120866d 100644 --- a/dart/dynamics/SphereShape.hpp +++ b/dart/dynamics/SphereShape.hpp @@ -38,7 +38,7 @@ namespace dart { namespace dynamics { -class SphereShape : public Shape +class DART_API SphereShape : public Shape { public: /// Constructor. diff --git a/dart/dynamics/TranslationalJoint.hpp b/dart/dynamics/TranslationalJoint.hpp index c02eda2efdbb8..63d4c4e555456 100644 --- a/dart/dynamics/TranslationalJoint.hpp +++ b/dart/dynamics/TranslationalJoint.hpp @@ -41,7 +41,7 @@ namespace dart { namespace dynamics { /// class TranslationalJoint -class TranslationalJoint : public GenericJoint +class DART_API TranslationalJoint : public GenericJoint { public: friend class Skeleton; diff --git a/dart/dynamics/TranslationalJoint2D.hpp b/dart/dynamics/TranslationalJoint2D.hpp index ce00ccf54c2bd..f2058164f6f86 100644 --- a/dart/dynamics/TranslationalJoint2D.hpp +++ b/dart/dynamics/TranslationalJoint2D.hpp @@ -44,7 +44,7 @@ namespace dynamics { /// /// First and second coordiantes represent the translations along first and /// second translational axes, respectively. -class TranslationalJoint2D : public detail::TranslationalJoint2DBase +class DART_API TranslationalJoint2D : public detail::TranslationalJoint2DBase { public: friend class Skeleton; diff --git a/dart/dynamics/UniversalJoint.hpp b/dart/dynamics/UniversalJoint.hpp index 96c0b81b54043..de6ea44a1ed52 100644 --- a/dart/dynamics/UniversalJoint.hpp +++ b/dart/dynamics/UniversalJoint.hpp @@ -39,7 +39,7 @@ namespace dart { namespace dynamics { /// class UniversalJoint -class UniversalJoint : public detail::UniversalJointBase +class DART_API UniversalJoint : public detail::UniversalJointBase { public: friend class Skeleton; diff --git a/dart/dynamics/VoxelGridShape.hpp b/dart/dynamics/VoxelGridShape.hpp index f480e8f5b3e00..a93246437ffc6 100644 --- a/dart/dynamics/VoxelGridShape.hpp +++ b/dart/dynamics/VoxelGridShape.hpp @@ -48,7 +48,7 @@ namespace dart { namespace dynamics { /// VoxelGridShape represents a probabilistic 3D occupancy voxel grid. -class VoxelGridShape : public Shape +class DART_API VoxelGridShape : public Shape { public: /// Constructor. diff --git a/dart/dynamics/WeldJoint.hpp b/dart/dynamics/WeldJoint.hpp index e2a185ae91a5e..1ae7f2796a22d 100644 --- a/dart/dynamics/WeldJoint.hpp +++ b/dart/dynamics/WeldJoint.hpp @@ -43,7 +43,7 @@ namespace dart { namespace dynamics { /// class WeldJoint -class WeldJoint : public ZeroDofJoint +class DART_API WeldJoint : public ZeroDofJoint { public: friend class Skeleton; diff --git a/dart/dynamics/ZeroDofJoint.hpp b/dart/dynamics/ZeroDofJoint.hpp index 6f64a2220c706..9eb9efc4e79d2 100644 --- a/dart/dynamics/ZeroDofJoint.hpp +++ b/dart/dynamics/ZeroDofJoint.hpp @@ -44,7 +44,7 @@ class BodyNode; class Skeleton; /// class ZeroDofJoint -class ZeroDofJoint : public Joint +class DART_API ZeroDofJoint : public Joint { public: struct Properties : Joint::Properties diff --git a/dart/math/Geometry.hpp b/dart/math/Geometry.hpp index e8982b82de530..e0f9c3cba56ef 100644 --- a/dart/math/Geometry.hpp +++ b/dart/math/Geometry.hpp @@ -33,6 +33,8 @@ #ifndef DART_MATH_GEOMETRY_HPP_ #define DART_MATH_GEOMETRY_HPP_ +#include + #include #include @@ -44,114 +46,114 @@ namespace dart { namespace math { /// \brief -Eigen::Matrix3d makeSkewSymmetric(const Eigen::Vector3d& _v); +DART_API Eigen::Matrix3d makeSkewSymmetric(const Eigen::Vector3d& _v); /// \brief -Eigen::Vector3d fromSkewSymmetric(const Eigen::Matrix3d& _m); +DART_API Eigen::Vector3d fromSkewSymmetric(const Eigen::Matrix3d& _m); //------------------------------------------------------------------------------ /// \brief -Eigen::Quaterniond expToQuat(const Eigen::Vector3d& _v); +DART_API Eigen::Quaterniond expToQuat(const Eigen::Vector3d& _v); /// \brief -Eigen::Vector3d quatToExp(const Eigen::Quaterniond& _q); +DART_API Eigen::Vector3d quatToExp(const Eigen::Quaterniond& _q); /// \brief -Eigen::Vector3d rotatePoint( +DART_API Eigen::Vector3d rotatePoint( const Eigen::Quaterniond& _q, const Eigen::Vector3d& _pt); /// \brief -Eigen::Vector3d rotatePoint( +DART_API Eigen::Vector3d rotatePoint( const Eigen::Quaterniond& _q, double _x, double _y, double _z); /// \brief -Eigen::Matrix3d quatDeriv(const Eigen::Quaterniond& _q, int _el); +DART_API Eigen::Matrix3d quatDeriv(const Eigen::Quaterniond& _q, int _el); /// \brief -Eigen::Matrix3d quatSecondDeriv( +DART_API Eigen::Matrix3d quatSecondDeriv( const Eigen::Quaterniond& _q, int _el1, int _el2); //------------------------------------------------------------------------------ /// \brief Given Euler XYX angles, return a 3x3 rotation matrix, which is /// equivalent to RotX(angle(0)) * RotY(angle(1)) * RotX(angle(2)). -Eigen::Matrix3d eulerXYXToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerXYXToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerXYZ angles, return a 3x3 rotation matrix, which is /// equivalent to RotX(angle(0)) * RotY(angle(1)) * RotZ(angle(2)). -Eigen::Matrix3d eulerXYZToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerXYZToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerXZX angles, return a 3x3 rotation matrix, which is /// equivalent to RotX(angle(0)) * RotZ(angle(1)) * RotX(angle(2)). -Eigen::Matrix3d eulerXZXToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerXZXToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerXZY angles, return a 3x3 rotation matrix, which is /// equivalent to RotX(angle(0)) * RotZ(angle(1)) * RotY(angle(2)). -Eigen::Matrix3d eulerXZYToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerXZYToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerYXY angles, return a 3x3 rotation matrix, which is /// equivalent to RotY(angle(0)) * RotX(angle(1)) * RotY(angle(2)). -Eigen::Matrix3d eulerYXYToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerYXYToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerYXZ angles, return a 3x3 rotation matrix, which is /// equivalent to RotY(angle(0)) * RotX(angle(1)) * RotZ(angle(2)). -Eigen::Matrix3d eulerYXZToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerYXZToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerYZX angles, return a 3x3 rotation matrix, which is /// equivalent to RotY(angle(0)) * RotZ(angle(1)) * RotX(angle(2)). -Eigen::Matrix3d eulerYZXToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerYZXToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerYZY angles, return a 3x3 rotation matrix, which is /// equivalent to RotY(angle(0)) * RotZ(angle(1)) * RotY(angle(2)). -Eigen::Matrix3d eulerYZYToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerYZYToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerZXY angles, return a 3x3 rotation matrix, which is /// equivalent to RotZ(angle(0)) * RotX(angle(1)) * RotY(angle(2)). -Eigen::Matrix3d eulerZXYToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerZXYToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerZYX angles, return a 3x3 rotation matrix, which is /// equivalent to RotZ(angle(0)) * RotY(angle(1)) * RotX(angle(2)). /// singularity : angle[1] = -+ 0.5*PI -Eigen::Matrix3d eulerZYXToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerZYXToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerZXZ angles, return a 3x3 rotation matrix, which is /// equivalent to RotZ(angle(0)) * RotX(angle(1)) * RotZ(angle(2)). -Eigen::Matrix3d eulerZXZToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerZXZToMatrix(const Eigen::Vector3d& _angle); /// \brief Given EulerZYZ angles, return a 3x3 rotation matrix, which is /// equivalent to RotZ(angle(0)) * RotY(angle(1)) * RotZ(angle(2)). /// singularity : angle[1] = 0, PI -Eigen::Matrix3d eulerZYZToMatrix(const Eigen::Vector3d& _angle); +DART_API Eigen::Matrix3d eulerZYZToMatrix(const Eigen::Vector3d& _angle); //------------------------------------------------------------------------------ /// \brief get the Euler XYX angle from R -Eigen::Vector3d matrixToEulerXYX(const Eigen::Matrix3d& _R); +DART_API Eigen::Vector3d matrixToEulerXYX(const Eigen::Matrix3d& _R); /// \brief get the Euler XYZ angle from R -Eigen::Vector3d matrixToEulerXYZ(const Eigen::Matrix3d& _R); +DART_API Eigen::Vector3d matrixToEulerXYZ(const Eigen::Matrix3d& _R); ///// \brief get the Euler XZX angle from R // Eigen::Vector3d matrixToEulerXZX(const Eigen::Matrix3d& R); /// \brief get the Euler XZY angle from R -Eigen::Vector3d matrixToEulerXZY(const Eigen::Matrix3d& _R); +DART_API Eigen::Vector3d matrixToEulerXZY(const Eigen::Matrix3d& _R); ///// \brief get the Euler YXY angle from R // Eigen::Vector3d matrixToEulerYXY(const Eigen::Matrix3d& R); /// \brief get the Euler YXZ angle from R -Eigen::Vector3d matrixToEulerYXZ(const Eigen::Matrix3d& _R); +DART_API Eigen::Vector3d matrixToEulerYXZ(const Eigen::Matrix3d& _R); /// \brief get the Euler YZX angle from R -Eigen::Vector3d matrixToEulerYZX(const Eigen::Matrix3d& _R); +DART_API Eigen::Vector3d matrixToEulerYZX(const Eigen::Matrix3d& _R); ///// \brief get the Euler YZY angle from R // Eigen::Vector3d matrixToEulerYZY(const Eigen::Matrix3d& R); /// \brief get the Euler ZXY angle from R -Eigen::Vector3d matrixToEulerZXY(const Eigen::Matrix3d& _R); +DART_API Eigen::Vector3d matrixToEulerZXY(const Eigen::Matrix3d& _R); /// \brief get the Euler ZYX angle from R -Eigen::Vector3d matrixToEulerZYX(const Eigen::Matrix3d& _R); +DART_API Eigen::Vector3d matrixToEulerZYX(const Eigen::Matrix3d& _R); ///// \brief get the Euler ZXZ angle from R // Eigen::Vector3d matrixToEulerZXZ(const Eigen::Matrix3d& R); @@ -161,35 +163,36 @@ Eigen::Vector3d matrixToEulerZYX(const Eigen::Matrix3d& _R); //------------------------------------------------------------------------------ /// \brief Exponential mapping -Eigen::Isometry3d expMap(const Eigen::Vector6d& _S); +DART_API Eigen::Isometry3d expMap(const Eigen::Vector6d& _S); /// \brief fast version of Exp(se3(s, 0)) /// \todo This expAngular() can be replaced by Eigen::AngleAxis() but we need /// to verify that they have exactly same functionality. /// See: https://github.com/dartsim/dart/issues/88 -Eigen::Isometry3d expAngular(const Eigen::Vector3d& _s); +DART_API Eigen::Isometry3d expAngular(const Eigen::Vector3d& _s); /// \brief Computes the Rotation matrix from a given expmap vector. -Eigen::Matrix3d expMapRot(const Eigen::Vector3d& _expmap); +DART_API Eigen::Matrix3d expMapRot(const Eigen::Vector3d& _expmap); /// \brief Computes the Jacobian of the expmap -Eigen::Matrix3d expMapJac(const Eigen::Vector3d& _expmap); +DART_API Eigen::Matrix3d expMapJac(const Eigen::Vector3d& _expmap); /// \brief Computes the time derivative of the expmap Jacobian. -Eigen::Matrix3d expMapJacDot( +DART_API Eigen::Matrix3d expMapJacDot( const Eigen::Vector3d& _expmap, const Eigen::Vector3d& _qdot); /// \brief computes the derivative of the Jacobian of the expmap wrt to _qi /// indexed dof; _qi \f$ \in \f$ {0,1,2} -Eigen::Matrix3d expMapJacDeriv(const Eigen::Vector3d& _expmap, int _qi); +DART_API Eigen::Matrix3d expMapJacDeriv( + const Eigen::Vector3d& _expmap, int _qi); /// \brief Log mapping /// \note When @f$|Log(R)| = @pi@f$, Exp(LogR(R) = Exp(-Log(R)). /// The implementation returns only the positive one. -Eigen::Vector3d logMap(const Eigen::Matrix3d& _R); +DART_API Eigen::Vector3d logMap(const Eigen::Matrix3d& _R); /// \brief Log mapping -Eigen::Vector6d logMap(const Eigen::Isometry3d& _T); +DART_API Eigen::Vector6d logMap(const Eigen::Isometry3d& _T); //------------------------------------------------------------------------------ /// \brief Rectify the rotation part so as that it satifies the orthogonality @@ -207,10 +210,11 @@ Eigen::Vector6d logMap(const Eigen::Isometry3d& _T); /// \brief adjoint mapping /// \note @f$Ad_TV = ( Rw@,, ~p @times Rw + Rv)@f$, /// where @f$T=(R,p)@in SE(3), @quad V=(w,v)@in se(3) @f$. -Eigen::Vector6d AdT(const Eigen::Isometry3d& _T, const Eigen::Vector6d& _V); +DART_API Eigen::Vector6d AdT( + const Eigen::Isometry3d& _T, const Eigen::Vector6d& _V); /// \brief Get linear transformation matrix of Adjoint mapping -Eigen::Matrix6d getAdTMatrix(const Eigen::Isometry3d& T); +DART_API Eigen::Matrix6d getAdTMatrix(const Eigen::Isometry3d& T); /// Adjoint mapping for dynamic size Jacobian template @@ -256,14 +260,15 @@ typename Derived::PlainObject AdTJacFixed( } /// \brief Fast version of Ad([R 0; 0 1], V) -Eigen::Vector6d AdR(const Eigen::Isometry3d& _T, const Eigen::Vector6d& _V); +DART_API Eigen::Vector6d AdR( + const Eigen::Isometry3d& _T, const Eigen::Vector6d& _V); /// \brief fast version of Ad(T, se3(w, 0)) -Eigen::Vector6d AdTAngular( +DART_API Eigen::Vector6d AdTAngular( const Eigen::Isometry3d& _T, const Eigen::Vector3d& _w); /// \brief fast version of Ad(T, se3(0, v)) -Eigen::Vector6d AdTLinear( +DART_API Eigen::Vector6d AdTLinear( const Eigen::Isometry3d& _T, const Eigen::Vector3d& _v); ///// \brief fast version of Ad([I p; 0 1], V) @@ -328,7 +333,8 @@ typename Derived::PlainObject adJac( } /// \brief fast version of Ad(Inv(T), V) -Eigen::Vector6d AdInvT(const Eigen::Isometry3d& _T, const Eigen::Vector6d& _V); +DART_API Eigen::Vector6d AdInvT( + const Eigen::Isometry3d& _T, const Eigen::Vector6d& _V); /// Adjoint mapping for dynamic size Jacobian template @@ -386,22 +392,25 @@ typename Derived::PlainObject AdInvTJacFixed( // se3 AdInvR(const SE3& T, const se3& V); /// \brief Fast version of Ad(Inv([R 0; 0 1]), se3(0, v)) -Eigen::Vector6d AdInvRLinear( +DART_API Eigen::Vector6d AdInvRLinear( const Eigen::Isometry3d& _T, const Eigen::Vector3d& _v); /// \brief dual adjoint mapping /// \note @f$Ad^{@,*}_TF = ( R^T (m - p@times f)@,,~ R^T f)@f$, /// where @f$T=(R,p)@in SE(3), F=(m,f)@in se(3)^*@f$. -Eigen::Vector6d dAdT(const Eigen::Isometry3d& _T, const Eigen::Vector6d& _F); +DART_API Eigen::Vector6d dAdT( + const Eigen::Isometry3d& _T, const Eigen::Vector6d& _F); ///// \brief fast version of Ad(Inv(T), dse3(Eigen_Vec3(0), F)) // dse3 dAdTLinear(const SE3& T, const Vec3& F); /// \brief fast version of dAd(Inv(T), F) -Eigen::Vector6d dAdInvT(const Eigen::Isometry3d& _T, const Eigen::Vector6d& _F); +DART_API Eigen::Vector6d dAdInvT( + const Eigen::Isometry3d& _T, const Eigen::Vector6d& _F); /// \brief fast version of dAd(Inv([R 0; 0 1]), F) -Eigen::Vector6d dAdInvR(const Eigen::Isometry3d& _T, const Eigen::Vector6d& _F); +DART_API Eigen::Vector6d dAdInvR( + const Eigen::Isometry3d& _T, const Eigen::Vector6d& _F); ///// \brief fast version of dAd(Inv(SE3(p)), dse3(Eigen_Vec3(0), F)) // dse3 dAdInvPLinear(const Vec3& p, const Vec3& F); @@ -409,7 +418,8 @@ Eigen::Vector6d dAdInvR(const Eigen::Isometry3d& _T, const Eigen::Vector6d& _F); /// \brief adjoint mapping /// \note @f$ad_X Y = ( w_X @times w_Y@,,~w_X @times v_Y - w_Y @times v_X),@f$, /// where @f$X=(w_X,v_X)@in se(3), @quad Y=(w_Y,v_Y)@in se(3) @f$. -Eigen::Vector6d ad(const Eigen::Vector6d& _X, const Eigen::Vector6d& _Y); +DART_API Eigen::Vector6d ad( + const Eigen::Vector6d& _X, const Eigen::Vector6d& _Y); /// \brief fast version of ad(se3(Eigen_Vec3(0), v), S) // Vec3 ad_Vec3_se3(const Vec3& v, const se3& S); @@ -420,14 +430,16 @@ Eigen::Vector6d ad(const Eigen::Vector6d& _X, const Eigen::Vector6d& _Y); /// \brief dual adjoint mapping /// \note @f$ad^{@,*}_V F = (m @times w + f @times v@,,~ f @times w),@f$ /// , where @f$F=(m,f)@in se^{@,*}(3), @quad V=(w,v)@in se(3) @f$. -Eigen::Vector6d dad(const Eigen::Vector6d& _s, const Eigen::Vector6d& _t); +DART_API Eigen::Vector6d dad( + const Eigen::Vector6d& _s, const Eigen::Vector6d& _t); /// \brief -Inertia transformInertia(const Eigen::Isometry3d& _T, const Inertia& _AI); +DART_API Inertia +transformInertia(const Eigen::Isometry3d& _T, const Inertia& _AI); /// Use the Parallel Axis Theorem to compute the moment of inertia of a body /// whose center of mass has been shifted from the origin -Eigen::Matrix3d parallelAxisTheorem( +DART_API Eigen::Matrix3d parallelAxisTheorem( const Eigen::Matrix3d& _original, const Eigen::Vector3d& _comShift, double _mass); @@ -442,29 +454,29 @@ enum AxisType /// Compute a rotation matrix from a vector. One axis of the rotated coordinates /// by the rotation matrix matches the input axis where the axis is specified /// by axisType. -Eigen::Matrix3d computeRotation( +DART_API Eigen::Matrix3d computeRotation( const Eigen::Vector3d& axis, AxisType axisType = AxisType::AXIS_X); /// Compute a transform from a vector and a position. The rotation of the result /// transform is computed by computeRotationMatrix(), and the translation is /// just the input translation. -Eigen::Isometry3d computeTransform( +DART_API Eigen::Isometry3d computeTransform( const Eigen::Vector3d& axis, const Eigen::Vector3d& translation, AxisType axisType = AxisType::AXIS_X); /// Generate frame given origin and z-axis DART_DEPRECATED(6.0) -Eigen::Isometry3d getFrameOriginAxisZ( +DART_API Eigen::Isometry3d getFrameOriginAxisZ( const Eigen::Vector3d& _origin, const Eigen::Vector3d& _axisZ); /// \brief Check if determinant of _R is equat to 1 and all the elements are not /// NaN values. -bool verifyRotation(const Eigen::Matrix3d& _R); +DART_API bool verifyRotation(const Eigen::Matrix3d& _R); /// \brief Check if determinant of the rotational part of _T is equat to 1 and /// all the elements are not NaN values. -bool verifyTransform(const Eigen::Isometry3d& _T); +DART_API bool verifyTransform(const Eigen::Isometry3d& _T); /// Compute the angle (in the range of -pi to +pi) which ignores any full /// rotations @@ -509,7 +521,7 @@ typedef common::aligned_vector SupportPolygon; /// and then compute their convex hull, which will take the form of a polgyon. /// _axis1 and _axis2 must both have unit length for this function to work /// correctly. -SupportPolygon computeSupportPolgyon( +DART_API SupportPolygon computeSupportPolgyon( const SupportGeometry& _geometry, const Eigen::Vector3d& _axis1 = Eigen::Vector3d::UnitX(), const Eigen::Vector3d& _axis2 = Eigen::Vector3d::UnitY()); @@ -518,18 +530,18 @@ SupportPolygon computeSupportPolgyon( /// std::vector which will have the same size as the returned /// SupportPolygon, and each entry will contain the original index of each point /// in the SupportPolygon -SupportPolygon computeSupportPolgyon( +DART_API SupportPolygon computeSupportPolgyon( std::vector& _originalIndices, const SupportGeometry& _geometry, const Eigen::Vector3d& _axis1 = Eigen::Vector3d::UnitX(), const Eigen::Vector3d& _axis2 = Eigen::Vector3d::UnitY()); /// Computes the convex hull of a set of 2D points -SupportPolygon computeConvexHull(const SupportPolygon& _points); +DART_API SupportPolygon computeConvexHull(const SupportPolygon& _points); /// Computes the convex hull of a set of 2D points and fills in _originalIndices /// with the original index of each entry in the returned SupportPolygon -SupportPolygon computeConvexHull( +DART_API SupportPolygon computeConvexHull( std::vector& _originalIndices, const SupportPolygon& _points); /// Generates a 3D convex hull given vertices and indices. @@ -549,7 +561,8 @@ computeConvexHull3D( const std::vector>& vertices, bool optimize = true); /// Compute the centroid of a polygon, assuming the polygon is a convex hull -Eigen::Vector2d computeCentroidOfHull(const SupportPolygon& _convexHull); +DART_API Eigen::Vector2d computeCentroidOfHull( + const SupportPolygon& _convexHull); /// Intersection_t is returned by the computeIntersection() function to indicate /// whether there was a valid intersection between the two line segments @@ -565,7 +578,7 @@ enum IntersectionResult /// Compute the intersection between a line segment that goes from a1 -> a2 and /// a line segment that goes from b1 -> b2. -IntersectionResult computeIntersection( +DART_API IntersectionResult computeIntersection( Eigen::Vector2d& _intersectionPoint, const Eigen::Vector2d& a1, const Eigen::Vector2d& a2, @@ -573,36 +586,36 @@ IntersectionResult computeIntersection( const Eigen::Vector2d& b2); /// Compute a 2D cross product -double cross(const Eigen::Vector2d& _v1, const Eigen::Vector2d& _v2); +DART_API double cross(const Eigen::Vector2d& _v1, const Eigen::Vector2d& _v2); /// Returns true if the point _p is inside the support polygon -bool isInsideSupportPolygon( +DART_API bool isInsideSupportPolygon( const Eigen::Vector2d& _p, const SupportPolygon& _support, bool _includeEdge = true); /// Returns the point which is closest to _p that also lays on the line segment /// that goes from _s1 -> _s2 -Eigen::Vector2d computeClosestPointOnLineSegment( +DART_API Eigen::Vector2d computeClosestPointOnLineSegment( const Eigen::Vector2d& _p, const Eigen::Vector2d& _s1, const Eigen::Vector2d& _s2); /// Returns the point which is closest to _p that also lays on the edge of the /// support polygon -Eigen::Vector2d computeClosestPointOnSupportPolygon( +DART_API Eigen::Vector2d computeClosestPointOnSupportPolygon( const Eigen::Vector2d& _p, const SupportPolygon& _support); /// Same as closestPointOnSupportPolygon, but also fills in _index1 and _index2 /// with the indices of the line segment -Eigen::Vector2d computeClosestPointOnSupportPolygon( +DART_API Eigen::Vector2d computeClosestPointOnSupportPolygon( std::size_t& _index1, std::size_t& _index2, const Eigen::Vector2d& _p, const SupportPolygon& _support); // Represents a bounding box with minimum and maximum coordinates. -class BoundingBox +class DART_API BoundingBox { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/dart/optimizer/GenericMultiObjectiveProblem.hpp b/dart/optimizer/GenericMultiObjectiveProblem.hpp index 2ebe9c2390be4..cf4762b17ceaf 100644 --- a/dart/optimizer/GenericMultiObjectiveProblem.hpp +++ b/dart/optimizer/GenericMultiObjectiveProblem.hpp @@ -45,7 +45,7 @@ namespace dart { namespace optimizer { -class GenericMultiObjectiveProblem : public MultiObjectiveProblem +class DART_API GenericMultiObjectiveProblem : public MultiObjectiveProblem { public: /// Constructor diff --git a/dart/optimizer/GradientDescentSolver.hpp b/dart/optimizer/GradientDescentSolver.hpp index 13ab0e5683f55..5e98377a88344 100644 --- a/dart/optimizer/GradientDescentSolver.hpp +++ b/dart/optimizer/GradientDescentSolver.hpp @@ -46,7 +46,7 @@ namespace optimizer { /// objective function and assigned weights) to solve nonlinear problems. Note /// that this is not a good option for Problems with difficult constraint /// functions that need to be solved exactly. -class GradientDescentSolver : public Solver +class DART_API GradientDescentSolver : public Solver { public: static const std::string Type; diff --git a/dart/optimizer/MultiObjectiveProblem.hpp b/dart/optimizer/MultiObjectiveProblem.hpp index e61c68f6f4b16..2c508b91cc3f9 100644 --- a/dart/optimizer/MultiObjectiveProblem.hpp +++ b/dart/optimizer/MultiObjectiveProblem.hpp @@ -44,7 +44,7 @@ namespace dart { namespace optimizer { -class MultiObjectiveProblem +class DART_API MultiObjectiveProblem { public: /// Constructor diff --git a/dart/optimizer/MultiObjectiveSolver.hpp b/dart/optimizer/MultiObjectiveSolver.hpp index f948728bd045a..5db4520ff013b 100644 --- a/dart/optimizer/MultiObjectiveSolver.hpp +++ b/dart/optimizer/MultiObjectiveSolver.hpp @@ -54,7 +54,7 @@ class MultiObjectiveProblem; /// for various problem types. This base class allows the different /// MultiObjectiveSolver implementations to be swapped out with each other /// quickly and easily to help with testing, benchmarking, and experimentation. -class MultiObjectiveSolver +class DART_API MultiObjectiveSolver { public: /// The MultiObjectiveSolver::Properties class contains Solver parameters that diff --git a/dart/optimizer/Population.hpp b/dart/optimizer/Population.hpp index 1fab564add055..c0469754e4250 100644 --- a/dart/optimizer/Population.hpp +++ b/dart/optimizer/Population.hpp @@ -46,7 +46,7 @@ namespace optimizer { class MultiObjectiveProblem; -class Population +class DART_API Population { public: /// Constructor diff --git a/dart/optimizer/Problem.hpp b/dart/optimizer/Problem.hpp index 8ce5c326561de..5ee028e912b71 100644 --- a/dart/optimizer/Problem.hpp +++ b/dart/optimizer/Problem.hpp @@ -33,10 +33,10 @@ #ifndef DART_OPTIMIZER_PROBLEM_HPP_ #define DART_OPTIMIZER_PROBLEM_HPP_ -#include - #include +#include + #include #include diff --git a/dart/simulation/Recording.hpp b/dart/simulation/Recording.hpp index b6c5351833f1b..fc58bd89845ec 100644 --- a/dart/simulation/Recording.hpp +++ b/dart/simulation/Recording.hpp @@ -54,7 +54,7 @@ class Skeleton; namespace simulation { /// \brief class Recording -class Recording +class DART_API Recording { public: /// \brief Create Recording with a list of skeletons diff --git a/dart/simulation/World.hpp b/dart/simulation/World.hpp index dc65bd0ca927b..4ea77f476e6bd 100644 --- a/dart/simulation/World.hpp +++ b/dart/simulation/World.hpp @@ -83,7 +83,7 @@ DART_COMMON_DECLARE_SHARED_WEAK(World) /// class World DART_DECLARE_CLASS_WITH_VIRTUAL_BASE_BEGIN -class World : public virtual common::Subject +class DART_API World : public virtual common::Subject { public: using NameChangedSignal = common::Signal