Skip to content

Commit

Permalink
rename core collision plugin loader to cache
Browse files Browse the repository at this point in the history
to avoid the naming conflict with the old class in moveit_ros.
It's basically an enhanced cache, so the name seems fine to me.
  • Loading branch information
v4hn committed Aug 30, 2021
1 parent 8cf9840 commit e235d92
Show file tree
Hide file tree
Showing 7 changed files with 23 additions and 25 deletions.
2 changes: 0 additions & 2 deletions MIGRATION.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,6 @@ API changes in MoveIt releases
- Removed deprecated header `moveit/macros/deprecation.h`. Use `[[deprecated]]` instead.
- All uses of `MOVEIT_CLASS_FORWARD` et. al. must now be followed by a semicolon for consistency (and to get -pedantic builds to pass for the codebase).
- In case you start RViz in a namespace, the default topic for the trajectory visualization display now uses the relative instead of the absolute namespace (i.e. `<ns>/move_group/display_planned_path` instead of `/move_group/display_planned_path`).
- `collision_detection::CollisionPluginLoader` was renamed to `collision_detection::ROSCollisionPluginLoader`
A new class `collision_detection::CollisionPluginLoader` provides the core functionality, while the former class just adds the method `setupScene`.

## ROS Melodic

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/collision_detection/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ add_library(${MOVEIT_LIB_NAME}
src/world.cpp
src/world_diff.cpp
src/collision_env.cpp
src/collision_plugin_loader.cpp
src/collision_plugin_cache.cpp
)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,11 @@
namespace collision_detection
{
/** Helper class to activate a specific collision plugin for a PlanningScene */
class CollisionPluginLoader
class CollisionPluginCache
{
public:
CollisionPluginLoader();
~CollisionPluginLoader();
CollisionPluginCache();
~CollisionPluginCache();

/**
* @brief Activate a specific collision plugin for the given planning scene instance.
Expand All @@ -56,8 +56,8 @@ class CollisionPluginLoader
bool activate(const std::string& name, const planning_scene::PlanningScenePtr& scene, bool exclusive);

private:
MOVEIT_CLASS_FORWARD(CollisionPluginLoaderImpl);
CollisionPluginLoaderImplPtr loader_;
MOVEIT_CLASS_FORWARD(CollisionPluginCacheImpl);
CollisionPluginCacheImplPtr cache_;
};

} // namespace collision_detection
Original file line number Diff line number Diff line change
Expand Up @@ -32,23 +32,23 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include <moveit/collision_detection/collision_plugin_loader.h>
#include <moveit/collision_detection/collision_plugin_cache.h>
#include <pluginlib/class_loader.hpp>
#include <memory>

static const std::string LOGNAME = "collision_detection";

namespace collision_detection
{
class CollisionPluginLoader::CollisionPluginLoaderImpl
class CollisionPluginCache::CollisionPluginCacheImpl
{
public:
CollisionPluginLoaderImpl()
CollisionPluginCacheImpl()
{
try
{
loader_ = std::make_shared<pluginlib::ClassLoader<CollisionPlugin>>("moveit_core",
"collision_detection::CollisionPlugin");
cache_ = std::make_shared<pluginlib::ClassLoader<CollisionPlugin>>("moveit_core",
"collision_detection::CollisionPlugin");
}
catch (pluginlib::PluginlibException& e)
{
Expand All @@ -61,7 +61,7 @@ class CollisionPluginLoader::CollisionPluginLoaderImpl
CollisionPluginPtr plugin;
try
{
plugin = loader_->createUniqueInstance(name);
plugin = cache_->createUniqueInstance(name);
plugins_[name] = plugin;
}
catch (pluginlib::PluginlibException& ex)
Expand Down Expand Up @@ -91,21 +91,21 @@ class CollisionPluginLoader::CollisionPluginLoaderImpl
}

private:
std::shared_ptr<pluginlib::ClassLoader<CollisionPlugin>> loader_;
std::shared_ptr<pluginlib::ClassLoader<CollisionPlugin>> cache_;
std::map<std::string, CollisionPluginPtr> plugins_;
};

CollisionPluginLoader::CollisionPluginLoader()
CollisionPluginCache::CollisionPluginCache()
{
loader_ = std::make_shared<CollisionPluginLoaderImpl>();
cache_ = std::make_shared<CollisionPluginCacheImpl>();
}

CollisionPluginLoader::~CollisionPluginLoader() = default;
CollisionPluginCache::~CollisionPluginCache() = default;

bool CollisionPluginLoader::activate(const std::string& name, const planning_scene::PlanningScenePtr& scene,
bool exclusive)
bool CollisionPluginCache::activate(const std::string& name, const planning_scene::PlanningScenePtr& scene,
bool exclusive)
{
return loader_->activate(name, scene, exclusive);
return cache_->activate(name, scene, exclusive);
}

} // namespace collision_detection
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,12 @@
#pragma once

#include <ros/ros.h>
#include <moveit/collision_detection/collision_plugin_loader.h>
#include <moveit/collision_detection/collision_plugin_cache.h>

namespace collision_detection
{
/** Augment CollisionPluginLoader with a method to fetch the plugin name from the ROS parameter server */
class ROSCollisionPluginLoader : public CollisionPluginLoader
class CollisionPluginLoader : public CollisionPluginCache
{
public:
/** @brief Fetch plugin name from parameter server and activate the plugin for the given scene */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
static const std::string LOGNAME = "collision_detection";
namespace collision_detection
{
void ROSCollisionPluginLoader::setupScene(ros::NodeHandle& nh, const planning_scene::PlanningScenePtr& scene)
void CollisionPluginLoader::setupScene(ros::NodeHandle& nh, const planning_scene::PlanningScenePtr& scene)
{
if (!scene)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -581,7 +581,7 @@ class PlanningSceneMonitor : private boost::noncopyable
robot_model_loader::RobotModelLoaderPtr rm_loader_;
moveit::core::RobotModelConstPtr robot_model_;

collision_detection::ROSCollisionPluginLoader collision_loader_;
collision_detection::CollisionPluginLoader collision_loader_;

class DynamicReconfigureImpl;
DynamicReconfigureImpl* reconfigure_impl_;
Expand Down

0 comments on commit e235d92

Please sign in to comment.