Skip to content

Commit

Permalink
Enable shared lib build with MSVC
Browse files Browse the repository at this point in the history
  • Loading branch information
jslee02 committed Jan 14, 2023
1 parent 3201394 commit d78c328
Show file tree
Hide file tree
Showing 50 changed files with 231 additions and 49 deletions.
5 changes: 3 additions & 2 deletions .github/workflows/ci_windows.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@ on:

jobs:
build_2022:
name: ${{ matrix.build_type }}
name: shared=${{ matrix.build_shared_libs }}.${{ matrix.build_type }}
runs-on: windows-2022
strategy:
fail-fast: false
matrix:
toolset: [""]
build_type: [Release]
build_shared_libs: [OFF] # TODO(JS): Add ON once shared lib build is resolved
build_shared_libs: [ON, OFF]
build_dartpy: [OFF] # Build tests and dartpy exclusively
# and building dartpy is disabled for now due to the lack of sufficient disk space in the CI
env:
Expand Down Expand Up @@ -50,6 +50,7 @@ jobs:
-DDART_MSVC_DEFAULT_OPTIONS=ON ^
-DDART_VERBOSE=ON ^
-DBUILD_SHARED_LIBS=${{ matrix.build_shared_libs }} ^
-DDART_BUILD_COMP_gui=OFF ^
-DDART_IN_CI=ON
cmake --build . --config %BUILD_TYPE% --target tests --parallel
ctest --rerun-failed --output-on-failure -C %BUILD_TYPE%
Expand Down
6 changes: 6 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -239,13 +239,19 @@ if(MSVC)
add_compile_options(/wd4267)
add_compile_options(/wd4305)
add_compile_options(/wd4334)
add_compile_options(/wd4506)
add_compile_options(/wd4838)
add_compile_options(/wd4996)

add_compile_options(/bigobj)

# Enable multi-threaded compilation.
add_compile_options(/MP)

add_link_options(/OPT:NOREF /FORCE:MULTIPLE)

set(CMAKE_INSTALL_UCRT_LIBRARIES ON)

elseif(CMAKE_COMPILER_IS_GNUCXX)

add_compile_options(-Wall -Wextra -fPIC)
Expand Down
14 changes: 14 additions & 0 deletions cmake/DARTMacros.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,18 @@ function(dart_generate_export_header)
"#define ${base_name}_API \\\n"
" DETAIL_${base_name}_API\n"
"\n"
"#ifdef _MSC_VER\n"
" #define ${base_name}_TEMPL_INST_DECL_API\n"
"#else\n"
" #define ${base_name}_TEMPL_INST_DECL_API ${base_name}_API\n"
"#endif\n"
"\n"
"#ifdef _MSC_VER\n"
" #define ${base_name}_TEMPL_INST_DEF_API ${base_name}_API\n"
"#else\n"
" #define ${base_name}_TEMPL_INST_DEF_API\n"
"#endif\n"
"\n"
"#include \"detail/${_ARG_EXPORT_FILE_NAME}\"\n"
)

Expand Down Expand Up @@ -920,6 +932,8 @@ function(dart_build_tests)
target_link_libraries(${target_name} PRIVATE ${dart_lib})
endforeach()

set_target_properties (${target_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY ${DART_BINARY_DIR}/bin)

if(dart_build_tests_TEST_LIST)
list(APPEND ${dart_build_tests_TEST_LIST} ${target_name})
endif()
Expand Down
1 change: 1 addition & 0 deletions dart/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${DART_BINARY_DIR}/lib")
set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${DART_BINARY_DIR}/lib")
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${DART_BINARY_DIR}/bin")

#===============================================================================
# Components: (dependency component), {external dependency}, [optional external dependency]
Expand Down
41 changes: 41 additions & 0 deletions dart/collision/Empty.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
/*
* Copyright (c) 2011-2023, The DART development contributors
* All rights reserved.
*
* The list of contributors can be found at:
* https://github.com/dartsim/dart/blob/master/LICENSE
*
* This file is provided under the following "BSD-style" License:
* 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 HOLDER 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.
*/

#pragma once

#include <dart/collision/Export.hpp>

namespace dart::collision {

DART_COLLISION_API void empty();

} // namespace dart
41 changes: 41 additions & 0 deletions dart/collision/empty.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
/*
* Copyright (c) 2011-2023, The DART development contributors
* All rights reserved.
*
* The list of contributors can be found at:
* https://github.com/dartsim/dart/blob/master/LICENSE
*
* This file is provided under the following "BSD-style" License:
* 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 HOLDER 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.
*/

#include "dart/collision/Empty.hpp"

namespace dart::collision {

void empty() {
// Do nothing
}

} // namespace dart
2 changes: 1 addition & 1 deletion dart/common/Stopwatch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ namespace dart::common {
template <
typename UnitType,
typename ClockType = std::chrono::high_resolution_clock>
class DART_COMMON_API Stopwatch final
class Stopwatch final
{
public:
/// Constructor
Expand Down
1 change: 1 addition & 0 deletions dart/common/detail/Cloneable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,7 @@ MakeCloneable<Base, Mixin>& MakeCloneable<Base, Mixin>::operator=(
MakeCloneable&& other)
{
static_cast<Mixin&>(*this) = std::move(static_cast<Mixin&&>(other));
return *this;
}

//==============================================================================
Expand Down
1 change: 1 addition & 0 deletions dart/dynamics/BalanceConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@

#include "dart/dynamics/BalanceConstraint.hpp"

#include "dart/dynamics/BodyNode.hpp"
#include "dart/dynamics/EndEffector.hpp"
#include "dart/dynamics/Skeleton.hpp"

Expand Down
2 changes: 1 addition & 1 deletion dart/dynamics/BallJoint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class DART_DYNAMICS_API BallJoint : public GenericJoint<math::SO3Space>

using Base = GenericJoint<math::SO3Space>;

struct Properties : Base::Properties
struct DART_DYNAMICS_API Properties : Base::Properties
{
DART_DEFINE_ALIGNED_SHARED_OBJECT_CREATOR(Properties)

Expand Down
2 changes: 1 addition & 1 deletion dart/dynamics/Branch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace dynamics {
class DART_DYNAMICS_API Branch : public Linkage
{
public:
struct Criteria
struct DART_DYNAMICS_API Criteria
{
/// Constructor. Requires a starting BodyNode.
Criteria(BodyNode* _start);
Expand Down
2 changes: 2 additions & 0 deletions dart/dynamics/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@ dart_add_component(
assimp octomap
TARGET_LINK_LIBRARIES_PUBLIC
assimp octomap
TARGET_LINK_LIBRARIES_PRIVATE
${PROJECT_NAME}${DART_MAJOR_VERSION}-external-odelcpsolver
TARGET_COMPILE_FEATURES_PUBLIC
cxx_std_17
SUB_DIRECTORIES
Expand Down
3 changes: 3 additions & 0 deletions dart/dynamics/CollisionGroup.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,6 +404,9 @@ class DART_DYNAMICS_API CollisionGroup
// (e.g., by world cloning).

private:
CollisionGroup& operator=(const CollisionGroup&) = delete;
CollisionGroup(const CollisionGroup&) = delete;

/// This class watches when ShapeFrames get deleted so that they can be safely
/// removes from the CollisionGroup. We cannot have a weak_ptr to a ShapeFrame
/// because some are managed by std::shared_ptr while others are managed by
Expand Down
1 change: 1 addition & 0 deletions dart/dynamics/ConstraintBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@

#include "dart/dynamics/ConstraintBase.hpp"

#include "dart/dynamics/BodyNode.hpp"
#include "dart/dynamics/Skeleton.hpp"

namespace dart {
Expand Down
1 change: 1 addition & 0 deletions dart/dynamics/DegreeOfFreedom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@

#include "dart/dynamics/DegreeOfFreedom.hpp"

#include "dart/dynamics/BodyNode.hpp"
#include "dart/dynamics/Joint.hpp"
#include "dart/dynamics/Skeleton.hpp"

Expand Down
2 changes: 2 additions & 0 deletions dart/dynamics/FixedJacobianNode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,8 @@ class DART_DYNAMICS_API FixedJacobianNode
/// \}

protected:
FixedJacobianNode() = default;

/// Constructor
FixedJacobianNode(BodyNode* parent, const Eigen::Isometry3d& transform);

Expand Down
2 changes: 1 addition & 1 deletion dart/dynamics/FreeJoint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class DART_DYNAMICS_API FreeJoint : public GenericJoint<math::SE3Space>

using Base = GenericJoint<math::SE3Space>;

struct Properties : Base::Properties
struct DART_DYNAMICS_API Properties : Base::Properties
{
DART_DEFINE_ALIGNED_SHARED_OBJECT_CREATOR(Properties)

Expand Down
26 changes: 13 additions & 13 deletions dart/dynamics/InverseKinematics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -488,7 +488,7 @@ typedef InverseKinematics IK;
/// InverseKinematics module that it belongs to gets cloned. Any Function
/// classes in the Problem that do not inherit InverseKinematics::Function
/// will just be copied over by reference.
class InverseKinematics::Function
class DART_DYNAMICS_API InverseKinematics::Function
{
public:
/// Enable this function to be cloned to a new IK module.
Expand All @@ -501,7 +501,7 @@ class InverseKinematics::Function
//==============================================================================
/// ErrorMethod is a base class for different ways of computing the error of
/// an InverseKinematics module.
class InverseKinematics::ErrorMethod : public common::Subject
class DART_DYNAMICS_API InverseKinematics::ErrorMethod : public common::Subject
{
public:
typedef std::pair<Eigen::Vector6d, Eigen::Vector6d> Bounds;
Expand Down Expand Up @@ -766,10 +766,10 @@ class InverseKinematics::TaskSpaceRegion : public ErrorMethod
//==============================================================================
/// GradientMethod is a base class for different ways of computing the
/// gradient of an InverseKinematics module.
class InverseKinematics::GradientMethod : public common::Subject
class DART_DYNAMICS_API InverseKinematics::GradientMethod : public common::Subject
{
public:
struct Properties
struct DART_DYNAMICS_API Properties
{
/// The component-wise clamp for this GradientMethod
double mComponentWiseClamp;
Expand Down Expand Up @@ -904,10 +904,10 @@ class InverseKinematics::GradientMethod : public common::Subject
/// damping helps with this), and each cycle might take more time to compute
/// than the JacobianTranspose method (although the JacobianDLS method will
/// usually converge in fewer cycles than JacobianTranspose).
class InverseKinematics::JacobianDLS : public GradientMethod
class DART_DYNAMICS_API InverseKinematics::JacobianDLS : public GradientMethod
{
public:
struct UniqueProperties
struct DART_DYNAMICS_API UniqueProperties
{
/// Damping coefficient
double mDamping;
Expand All @@ -916,7 +916,7 @@ class InverseKinematics::JacobianDLS : public GradientMethod
UniqueProperties(double damping = DefaultIKDLSCoefficient);
};

struct Properties : GradientMethod::Properties, UniqueProperties
struct DART_DYNAMICS_API Properties : GradientMethod::Properties, UniqueProperties
{
/// Default constructor
Properties(
Expand Down Expand Up @@ -962,7 +962,7 @@ class InverseKinematics::JacobianDLS : public GradientMethod
/// very smooth but imprecise, requiring more iterations before converging
/// and being less precise in general. This method is suitable for animations
/// where smoothness is prefered over precision.
class InverseKinematics::JacobianTranspose : public GradientMethod
class DART_DYNAMICS_API InverseKinematics::JacobianTranspose : public GradientMethod
{
public:
/// Constructor
Expand Down Expand Up @@ -995,7 +995,7 @@ class InverseKinematics::JacobianTranspose : public GradientMethod
/// counter-productive for analytical methods which do not typically rely on
/// convergence; analytical methods can usually solve the entire error vector
/// directly.
class InverseKinematics::Analytical : public GradientMethod
class DART_DYNAMICS_API InverseKinematics::Analytical : public GradientMethod
{
public:
/// Bitwise enumerations that are used to describe some properties of each
Expand Down Expand Up @@ -1036,7 +1036,7 @@ class InverseKinematics::Analytical : public GradientMethod
};
// TODO(JS): Change to enum class?

struct Solution
struct DART_DYNAMICS_API Solution
{
/// Default constructor
Solution(
Expand All @@ -1058,7 +1058,7 @@ class InverseKinematics::Analytical : public GradientMethod
const InverseKinematics* _ik)>
QualityComparison;

struct UniqueProperties
struct DART_DYNAMICS_API UniqueProperties
{
/// Flag for how to use the extra DOFs in the IK module.
ExtraDofUtilization mExtraDofUtilization;
Expand All @@ -1084,7 +1084,7 @@ class InverseKinematics::Analytical : public GradientMethod
void resetQualityComparisonFunction();
};

struct Properties : GradientMethod::Properties, UniqueProperties
struct DART_DYNAMICS_API Properties : GradientMethod::Properties, UniqueProperties
{
// Default constructor
Properties(
Expand Down Expand Up @@ -1314,7 +1314,7 @@ class InverseKinematics::Objective final : public Function,
/// instantiated by a user. Call InverseKinematics::resetProblem() to set the
/// first equality constraint of the module's Problem to an
/// InverseKinematics::Constraint.
class InverseKinematics::Constraint final : public Function,
class DART_DYNAMICS_API InverseKinematics::Constraint final : public Function,
public optimization::Function
{
public:
Expand Down
2 changes: 2 additions & 0 deletions dart/dynamics/JacobianNode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -273,6 +273,8 @@ class DART_DYNAMICS_API JacobianNode : public virtual Frame, public Node
void dirtyJacobianDeriv();

protected:
JacobianNode() = default;

/// Constructor
JacobianNode(BodyNode* bn);

Expand Down
Loading

0 comments on commit d78c328

Please sign in to comment.