Skip to content

Commit

Permalink
Leverage forward declarations to improve compile times
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Mar 11, 2024
1 parent 3ef3b93 commit f9665d4
Show file tree
Hide file tree
Showing 289 changed files with 5,877 additions and 3,894 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -52,25 +52,29 @@ namespace tesseract_collision::tesseract_collision_bullet
class BulletDiscreteBVHManagerFactory : public DiscreteContactManagerFactory
{
public:
DiscreteContactManager::UPtr create(const std::string& name, const YAML::Node& config) const override final;
std::unique_ptr<DiscreteContactManager> create(const std::string& name,
const YAML::Node& config) const override final;
};

class BulletDiscreteSimpleManagerFactory : public DiscreteContactManagerFactory
{
public:
DiscreteContactManager::UPtr create(const std::string& name, const YAML::Node& config) const override final;
std::unique_ptr<DiscreteContactManager> create(const std::string& name,
const YAML::Node& config) const override final;
};

class BulletCastBVHManagerFactory : public ContinuousContactManagerFactory
{
public:
ContinuousContactManager::UPtr create(const std::string& name, const YAML::Node& config) const override final;
std::unique_ptr<ContinuousContactManager> create(const std::string& name,
const YAML::Node& config) const override final;
};

class BulletCastSimpleManagerFactory : public ContinuousContactManagerFactory
{
public:
ContinuousContactManager::UPtr create(const std::string& name, const YAML::Node& config) const override final;
std::unique_ptr<ContinuousContactManager> create(const std::string& name,
const YAML::Node& config) const override final;
};

TESSERACT_PLUGIN_ANCHOR_DECL(BulletFactoriesAnchor)
Expand Down
19 changes: 11 additions & 8 deletions tesseract_collision/bullet/src/bullet_factories.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,9 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/bullet/bullet_discrete_simple_manager.h>
#include <tesseract_collision/bullet/tesseract_collision_configuration.h>

#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/continuous_contact_manager.h>

namespace tesseract_collision::tesseract_collision_bullet
{
TesseractCollisionConfigurationInfo getConfigInfo(const YAML::Node& config)
Expand All @@ -59,26 +62,26 @@ TesseractCollisionConfigurationInfo getConfigInfo(const YAML::Node& config)
return config_info;
}

DiscreteContactManager::UPtr BulletDiscreteBVHManagerFactory::create(const std::string& name,
const YAML::Node& config) const
std::unique_ptr<tesseract_collision::DiscreteContactManager>
BulletDiscreteBVHManagerFactory::create(const std::string& name, const YAML::Node& config) const
{
return std::make_unique<BulletDiscreteBVHManager>(name, getConfigInfo(config));
}

DiscreteContactManager::UPtr BulletDiscreteSimpleManagerFactory::create(const std::string& name,
const YAML::Node& config) const
std::unique_ptr<DiscreteContactManager> BulletDiscreteSimpleManagerFactory::create(const std::string& name,
const YAML::Node& config) const
{
return std::make_unique<BulletDiscreteSimpleManager>(name, getConfigInfo(config));
}

ContinuousContactManager::UPtr BulletCastBVHManagerFactory::create(const std::string& name,
const YAML::Node& config) const
std::unique_ptr<ContinuousContactManager> BulletCastBVHManagerFactory::create(const std::string& name,
const YAML::Node& config) const
{
return std::make_unique<BulletCastBVHManager>(name, getConfigInfo(config));
}

ContinuousContactManager::UPtr BulletCastSimpleManagerFactory::create(const std::string& name,
const YAML::Node& config) const
std::unique_ptr<ContinuousContactManager> BulletCastSimpleManagerFactory::create(const std::string& name,
const YAML::Node& config) const
{
return std::make_unique<BulletCastSimpleManager>(name, getConfigInfo(config));
}
Expand Down
6 changes: 3 additions & 3 deletions tesseract_collision/bullet/src/bullet_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ std::shared_ptr<btCollisionShape> createShapePrimitive(const tesseract_geometry:
managed_shapes.resize(octree.getTreeDepth() + 1);
switch (geom->getSubType())
{
case tesseract_geometry::Octree::SubType::BOX:
case tesseract_geometry::OctreeSubType::BOX:
{
for (auto it = octree.begin(static_cast<unsigned char>(octree.getTreeDepth())), end = octree.end(); it != end;
++it)
Expand Down Expand Up @@ -257,7 +257,7 @@ std::shared_ptr<btCollisionShape> createShapePrimitive(const tesseract_geometry:

return subshape;
}
case tesseract_geometry::Octree::SubType::SPHERE_INSIDE:
case tesseract_geometry::OctreeSubType::SPHERE_INSIDE:
{
for (auto it = octree.begin(static_cast<unsigned char>(octree.getTreeDepth())), end = octree.end(); it != end;
++it)
Expand Down Expand Up @@ -292,7 +292,7 @@ std::shared_ptr<btCollisionShape> createShapePrimitive(const tesseract_geometry:

return subshape;
}
case tesseract_geometry::Octree::SubType::SPHERE_OUTSIDE:
case tesseract_geometry::OctreeSubType::SPHERE_OUTSIDE:
{
for (auto it = octree.begin(static_cast<unsigned char>(octree.getTreeDepth())), end = octree.end(); it != end;
++it)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,11 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <string>
#include <memory>
#include <map>
#include <yaml-cpp/yaml.h>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/continuous_contact_manager.h>
#include <tesseract_common/filesystem.h>
#include <tesseract_common/plugin_loader.h>
#include <tesseract_common/types.h>
#include <tesseract_common/plugin_info.h>

// clang-format off
#define TESSERACT_ADD_DISCRETE_MANAGER_PLUGIN(DERIVED_CLASS, ALIAS) \
Expand All @@ -51,6 +49,8 @@ namespace tesseract_collision
{
/** @brief Forward declare Plugin Factory */
class ContactManagersPluginFactory;
class DiscreteContactManager;
class ContinuousContactManager;

/** @brief Define a discrete contact manager plugin which the factory can create an instance */
class DiscreteContactManagerFactory
Expand All @@ -59,14 +59,19 @@ class DiscreteContactManagerFactory
using Ptr = std::shared_ptr<DiscreteContactManagerFactory>;
using ConstPtr = std::shared_ptr<const DiscreteContactManagerFactory>;

virtual ~DiscreteContactManagerFactory() = default;
DiscreteContactManagerFactory() = default;
virtual ~DiscreteContactManagerFactory();
DiscreteContactManagerFactory(const DiscreteContactManagerFactory&) = default;
DiscreteContactManagerFactory& operator=(const DiscreteContactManagerFactory&) = default;
DiscreteContactManagerFactory(DiscreteContactManagerFactory&&) = default;
DiscreteContactManagerFactory& operator=(DiscreteContactManagerFactory&&) = default;

/**
* @brief Create Discrete Contact Manager Object
* @param name The name of the contact manager object
* @return If failed to create, nullptr is returned.
*/
virtual DiscreteContactManager::UPtr create(const std::string& name, const YAML::Node& config) const = 0;
virtual std::unique_ptr<DiscreteContactManager> create(const std::string& name, const YAML::Node& config) const = 0;

protected:
static const std::string SECTION_NAME;
Expand All @@ -80,14 +85,20 @@ class ContinuousContactManagerFactory
using Ptr = std::shared_ptr<ContinuousContactManagerFactory>;
using ConstPtr = std::shared_ptr<const ContinuousContactManagerFactory>;

virtual ~ContinuousContactManagerFactory() = default;
ContinuousContactManagerFactory() = default;
virtual ~ContinuousContactManagerFactory();
ContinuousContactManagerFactory(const ContinuousContactManagerFactory&) = default;
ContinuousContactManagerFactory& operator=(const ContinuousContactManagerFactory&) = default;
ContinuousContactManagerFactory(ContinuousContactManagerFactory&&) = default;
ContinuousContactManagerFactory& operator=(ContinuousContactManagerFactory&&) = default;

/**
* @brief Create Inverse Kinematics Object
* @param name The name of the contact manager object
* @return If failed to create, nullptr is returned.
*/
virtual ContinuousContactManager::UPtr create(const std::string& solver_name, const YAML::Node& config) const = 0;
virtual std::unique_ptr<ContinuousContactManager> create(const std::string& solver_name,
const YAML::Node& config) const = 0;

protected:
static const std::string SECTION_NAME;
Expand Down Expand Up @@ -237,30 +248,30 @@ class ContactManagersPluginFactory
* @details This looks for discrete contact manager plugin info. If not found nullptr is returned.
* @param name The name
*/
DiscreteContactManager::UPtr createDiscreteContactManager(const std::string& name) const;
std::unique_ptr<DiscreteContactManager> createDiscreteContactManager(const std::string& name) const;

/**
* @brief Get discrete contact manager object given plugin info
* @param name The name
* @param plugin_info The plugin information to create kinematics object
*/
DiscreteContactManager::UPtr createDiscreteContactManager(const std::string& name,
const tesseract_common::PluginInfo& plugin_info) const;
std::unique_ptr<DiscreteContactManager>
createDiscreteContactManager(const std::string& name, const tesseract_common::PluginInfo& plugin_info) const;

/**
* @brief Get continuous contact manager object given name
* @details This looks for continuous contact manager plugin info. If not found nullptr is returned.
* @param name The name
*/
ContinuousContactManager::UPtr createContinuousContactManager(const std::string& name) const;
std::unique_ptr<ContinuousContactManager> createContinuousContactManager(const std::string& name) const;

/**
* @brief Get continuous contact manager object given plugin info
* @param name The name
* @param plugin_info The plugin information to create kinematics object
*/
ContinuousContactManager::UPtr createContinuousContactManager(const std::string& name,
const tesseract_common::PluginInfo& plugin_info) const;
std::unique_ptr<ContinuousContactManager>
createContinuousContactManager(const std::string& name, const tesseract_common::PluginInfo& plugin_info) const;

/**
* @brief Save the plugin information to a yaml config file
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class ContinuousContactManager
using ConstUPtr = std::unique_ptr<const ContinuousContactManager>;

ContinuousContactManager() = default;
virtual ~ContinuousContactManager() = default;
virtual ~ContinuousContactManager();
ContinuousContactManager(const ContinuousContactManager&) = delete;
ContinuousContactManager& operator=(const ContinuousContactManager&) = delete;
ContinuousContactManager(ContinuousContactManager&&) = delete;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,9 @@
#ifndef TESSERACT_COLLISION_CONVEX_DECOMPOSITION_H
#define TESSERACT_COLLISION_CONVEX_DECOMPOSITION_H

#include <vector>
#include <memory>
#include <tesseract_common/types.h>
#include <tesseract_geometry/impl/convex_mesh.h>
#include <tesseract_common/eigen_types.h>
#include <tesseract_geometry/fwd.h>

namespace tesseract_collision
{
Expand All @@ -53,8 +52,8 @@ class ConvexDecomposition
* index
* @return
*/
virtual std::vector<tesseract_geometry::ConvexMesh::Ptr> compute(const tesseract_common::VectorVector3d& vertices,
const Eigen::VectorXi& faces) const = 0;
virtual std::vector<std::shared_ptr<tesseract_geometry::ConvexMesh>>
compute(const tesseract_common::VectorVector3d& vertices, const Eigen::VectorXi& faces) const = 0;
};

} // namespace tesseract_collision
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class DiscreteContactManager
using ConstUPtr = std::unique_ptr<const DiscreteContactManager>;

DiscreteContactManager() = default;
virtual ~DiscreteContactManager() = default;
virtual ~DiscreteContactManager();
DiscreteContactManager(const DiscreteContactManager&) = delete;
DiscreteContactManager& operator=(const DiscreteContactManager&) = delete;
DiscreteContactManager(DiscreteContactManager&&) = delete;
Expand Down
62 changes: 62 additions & 0 deletions tesseract_collision/core/include/tesseract_collision/core/fwd.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
/**
* @file types.h
* @brief Tesseracts Collision Forward Declarations
*
* @author Levi Armstrong
* @date February 17, 2024
* @version TODO
* @bug No known bugs
*
* @copyright Copyright (c) 2024, Levi Armstrong
*
* @par License
* Software License Agreement (Apache License)
* @par
* 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
* @par
* 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 TESSERACT_COLLISION_CORE_TESSERACT_COLLISION_FWD_H
#define TESSERACT_COLLISION_CORE_TESSERACT_COLLISION_FWD_H

namespace tesseract_collision
{
// types.h
enum class ContinuousCollisionType;
enum class ContactTestType;
struct ContactResult;
class ContactResultMap;
struct ContactRequest;
struct ContactTestData;
enum class CollisionEvaluatorType;
enum class CollisionCheckProgramType;
enum class ACMOverrideType;
struct ContactManagerConfig;
struct CollisionCheckConfig;
struct ContactTrajectorySubstepResults;
struct ContactTrajectoryStepResults;
struct ContactTrajectoryResults;

// contact_managers_plugin_factory.h
class DiscreteContactManagerFactory;
class ContinuousContactManagerFactory;
class ContactManagersPluginFactory;

// convex_decomposition.h
class ConvexDecomposition;

// discrete_contact_manager.h
class DiscreteContactManager;

// continuous_contact_manager.h
class ContinuousContactManager;
} // namespace tesseract_collision

#endif // TESSERACT_COLLISION_CORE_TESSERACT_COLLISION_FWD_H
Original file line number Diff line number Diff line change
Expand Up @@ -26,17 +26,7 @@
#ifndef TESSERACT_COLLISION_SERIALIZATION_H
#define TESSERACT_COLLISION_SERIALIZATION_H

#include <tesseract_common/macros.h>
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <boost/archive/xml_oarchive.hpp>
#include <boost/archive/xml_iarchive.hpp>
#include <boost/archive/binary_oarchive.hpp>
#include <boost/archive/binary_iarchive.hpp>
#include <boost/serialization/tracking.hpp>
#include <boost/serialization/tracking_enum.hpp>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_collision/core/types.h>
#include <tesseract_collision/core/fwd.h>

namespace boost::serialization
{
Expand Down
18 changes: 10 additions & 8 deletions tesseract_collision/core/include/tesseract_collision/core/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,20 +36,22 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <array>
#include <unordered_map>
#include <functional>
#include <tesseract_geometry/geometry.h>
#include <tesseract_common/types.h>
#include <tesseract_common/collision_margin_data.h>
#include <tesseract_common/allowed_collision_matrix.h>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_common/fwd.h>
#include <tesseract_common/eigen_types.h>
#include <tesseract_common/collision_margin_data.h>
#include <tesseract_geometry/fwd.h>

namespace tesseract_collision
{
using CollisionShapesConst = std::vector<tesseract_geometry::Geometry::ConstPtr>;
using CollisionShapeConstPtr = tesseract_geometry::Geometry::ConstPtr;
using CollisionShapePtr = tesseract_geometry::Geometry::Ptr;
using CollisionShapeConstPtr = std::shared_ptr<const tesseract_geometry::Geometry>;
using CollisionShapePtr = std::shared_ptr<tesseract_geometry::Geometry>;
using CollisionShapesConst = std::vector<CollisionShapeConstPtr>;
using CollisionMarginData = tesseract_common::CollisionMarginData;
using CollisionMarginOverrideType = tesseract_common::CollisionMarginOverrideType;
using PairsCollisionMarginData = tesseract_common::PairsCollisionMarginData;
using PairsCollisionMarginData =
std::unordered_map<std::pair<std::string, std::string>, double, tesseract_common::PairHash>;

/**
* @brief Should return true if contact allowed, otherwise false.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,6 @@
#include <tesseract_common/macros.h>
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <tesseract_collision/core/types.h>
#include <tesseract_collision/core/continuous_contact_manager.h>
#include <tesseract_collision/core/discrete_contact_manager.h>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

namespace tesseract_collision
Expand Down
Loading

0 comments on commit f9665d4

Please sign in to comment.