Skip to content

Commit

Permalink
Exposed plugin implementations for linking by downstream projects (#45)
Browse files Browse the repository at this point in the history
  • Loading branch information
marip8 authored May 11, 2023
1 parent 542626d commit a4afc2c
Show file tree
Hide file tree
Showing 12 changed files with 424 additions and 242 deletions.
16 changes: 8 additions & 8 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,13 @@ add_library(
src/types.cpp
src/reach_visualizer.cpp
src/reach_study.cpp
src/reach_study_comparison.cpp)
src/reach_study_comparison.cpp
# Implementations
src/plugins/multiplicative_evaluator.cpp
src/plugins/point_cloud_target_pose_generator.cpp
src/plugins/console_logger.cpp
src/plugins/boost_progress_console_logger.cpp
src/plugins/no_op.cpp)
target_link_libraries(
${PROJECT_NAME}
PUBLIC ${PROJECT_NAME}_interface
Expand All @@ -72,13 +78,7 @@ target_cxx_version(${PROJECT_NAME} PUBLIC VERSION 14)
list(APPEND TARGETS ${PROJECT_NAME})

# Plugins Library
add_library(
${PROJECT_NAME}_plugins SHARED
src/plugins/multiplicative_evaluator.cpp
src/plugins/point_cloud_target_pose_generator.cpp
src/plugins/console_logger.cpp
src/plugins/boost_progress_console_logger.cpp
src/plugins/no_op.cpp)
add_library(${PROJECT_NAME}_plugins SHARED src/plugins/plugins.cpp)
target_link_libraries(
${PROJECT_NAME}_plugins
PUBLIC ${PROJECT_NAME}
Expand Down
52 changes: 52 additions & 0 deletions include/reach/plugins/boost_progress_console_logger.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
/*
* Copyright 2019 Southwest Research Institute
*
* 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
*
* 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 REACH_PLUGINS_BOOST_PROGRESS_CONSOLE_LOGGER_H
#define REACH_PLUGINS_BOOST_PROGRESS_CONSOLE_LOGGER_H

#include <reach/interfaces/logger.h>

#include <boost/shared_ptr.hpp>
#include <boost/progress.hpp>
#include <mutex>

namespace reach
{
/**
* @brief Thread-safe logger that prints messages to the console via stdout, with boost progress bar progress logging
*/
class BoostProgressConsoleLogger : public Logger
{
public:
BoostProgressConsoleLogger();

void setMaxProgress(unsigned long max_progress) override;
void printProgress(unsigned long progress) const override;
void printResults(const ReachResultSummary& results) const override;
void print(const std::string& message) const override;

protected:
mutable std::mutex mutex_;
mutable boost::shared_ptr<boost::progress_display> display_;
};

struct BoostProgressConsoleLoggerFactory : public LoggerFactory
{
Logger::Ptr create(const YAML::Node& /*config*/) const override;
};

} // namespace reach

#endif // REACH_PLUGINS_BOOST_PROGRESS_CONSOLE_LOGGER_H
48 changes: 48 additions & 0 deletions include/reach/plugins/console_logger.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
/*
* Copyright 2019 Southwest Research Institute
*
* 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
*
* 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 REACH_PLUGINS_CONSOLE_LOGGER_H
#define REACH_PLUGINS_CONSOLE_LOGGER_H

#include <reach/interfaces/logger.h>

#include <mutex>

namespace reach
{
/**
* @brief Thread-safe logger that prints messages to the console via stdout
*/
class ConsoleLogger : public Logger
{
public:
void setMaxProgress(unsigned long progress) override;
void printProgress(unsigned long progress) const override;
void printResults(const ReachResultSummary& results) const override;
void print(const std::string& message) const override;

protected:
mutable std::mutex mutex_;
unsigned long max_progress_{ 0 };
};

struct ConsoleLoggerFactory : public LoggerFactory
{
Logger::Ptr create(const YAML::Node& /*config*/) const override;
};

} // namespace reach

#endif // REACH_PLUGINS_CONSOLE_LOGGER_H
49 changes: 49 additions & 0 deletions include/reach/plugins/multiplicative_evaluator.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
/*
* Copyright 2019 Southwest Research Institute
*
* 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
*
* 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 REACH_PLUGINS_MULTIPLICATIVE_EVALUATOR_H
#define REACH_PLUGINS_MULTIPLICATIVE_EVALUATOR_H

#include <reach/interfaces/evaluator.h>

#include <boost_plugin_loader/plugin_loader.hpp>

namespace reach
{
class MultiplicativeEvaluator : public Evaluator
{
public:
MultiplicativeEvaluator(std::vector<Evaluator::ConstPtr> evaluators);

double calculateScore(const std::map<std::string, double>& pose) const override;

private:
std::vector<Evaluator::ConstPtr> evaluators_;
};

class MultiplicativeEvaluatorFactory : public EvaluatorFactory
{
public:
MultiplicativeEvaluatorFactory();

Evaluator::ConstPtr create(const YAML::Node& config) const override;

private:
mutable boost_plugin_loader::PluginLoader loader_;
};

} // namespace reach

#endif // REACH_PLUGINS_MULTIPLICATIVE_EVALUATOR_H
66 changes: 66 additions & 0 deletions include/reach/plugins/no_op.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
/*
* Copyright 2019 Southwest Research Institute
*
* 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
*
* 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 REACH_PLUGINS_NOOP_H
#define REACH_PLUGINS_NOOP_H

#include <reach/interfaces/evaluator.h>
#include <reach/interfaces/ik_solver.h>
#include <reach/interfaces/display.h>

#include <boost/shared_ptr.hpp>

namespace reach
{
struct NoOpEvaluator : public Evaluator
{
double calculateScore(const std::map<std::string, double>&) const override;
};

struct NoOpEvaluatorFactory : public EvaluatorFactory
{
virtual Evaluator::ConstPtr create(const YAML::Node&) const override;
};

struct NoOpIKSolver : public IKSolver
{
public:
std::vector<std::string> getJointNames() const override;

std::vector<std::vector<double>> solveIK(const Eigen::Isometry3d&,
const std::map<std::string, double>&) const override;
};

struct NoOpIKSolverFactory : public IKSolverFactory
{
IKSolver::ConstPtr create(const YAML::Node&) const override;
};

struct NoOpDisplay : public Display
{
void showEnvironment() const override;
void updateRobotPose(const std::map<std::string, double>&) const override;
void showReachNeighborhood(const std::map<std::size_t, ReachRecord>&) const override;
void showResults(const ReachResult&) const override;
};

struct NoOpDisplayFactory : public DisplayFactory
{
Display::ConstPtr create(const YAML::Node&) const override;
};

} // namespace reach

#endif // REACH_PLUGINS_NOOP_H
42 changes: 42 additions & 0 deletions include/reach/plugins/point_cloud_target_pose_generator.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
/*
* Copyright 2019 Southwest Research Institute
*
* 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
*
* 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 REACH_PLUGINS_POINT_CLOUD_TARGET_POSE_GENERATOR_H
#define REACH_PLUGINS_POINT_CLOUD_TARGET_POSE_GENERATOR_H

#include <reach/interfaces/target_pose_generator.h>

namespace reach
{
class PointCloudTargetPoseGenerator : public TargetPoseGenerator
{
public:
PointCloudTargetPoseGenerator(std::string filename);

VectorIsometry3d generate() const override;

private:
std::string filename_;
};

struct PointCloudTargetPoseGeneratorFactory : public TargetPoseGeneratorFactory
{
using TargetPoseGeneratorFactory::TargetPoseGeneratorFactory;
TargetPoseGenerator::ConstPtr create(const YAML::Node& config) const override;
};

} // namespace reach

#endif // REACH_PLUGINS_POINT_CLOUD_TARGET_POSE_GENERATOR_H
82 changes: 31 additions & 51 deletions src/plugins/boost_progress_console_logger.cpp
Original file line number Diff line number Diff line change
@@ -1,62 +1,42 @@
#include <reach/interfaces/logger.h>
#include <reach/plugins/boost_progress_console_logger.h>
#include <reach/types.h>

#include <boost/progress.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/make_shared.hpp>
#include <iostream>
#include <mutex>

namespace reach
{
/**
* @brief Thread-safe logger that prints messages to the console via stdout, with boost progress bar progress logging
*/
class BoostProgressConsoleLogger : public Logger
BoostProgressConsoleLogger::BoostProgressConsoleLogger() : display_(nullptr)
{
public:
BoostProgressConsoleLogger() : display_(nullptr)
{
}

void setMaxProgress(unsigned long max_progress) override
{
std::lock_guard<std::mutex> lock{ mutex_ };
display_ = boost::make_shared<boost::progress_display>(max_progress);
}

void printProgress(unsigned long progress) const override
{
std::lock_guard<std::mutex> lock{ mutex_ };
if (progress > display_->count())
*display_ += progress - display_->count();
}

void printResults(const ReachResultSummary& results) const override
{
print(results.print());
}

void print(const std::string& message) const override
{
std::lock_guard<std::mutex> lock{ mutex_ };
std::cout << message << std::endl;
}

protected:
mutable std::mutex mutex_;
mutable boost::shared_ptr<boost::progress_display> display_;
};

struct BoostProgressConsoleLoggerFactory : public LoggerFactory
}

void BoostProgressConsoleLogger::setMaxProgress(unsigned long max_progress)
{
Logger::Ptr create(const YAML::Node& /*config*/) const override
{
return std::make_shared<BoostProgressConsoleLogger>();
}
};
std::lock_guard<std::mutex> lock{ mutex_ };
display_ = boost::make_shared<boost::progress_display>(max_progress);
}

} // namespace reach
void BoostProgressConsoleLogger::printProgress(unsigned long progress) const
{
std::lock_guard<std::mutex> lock{ mutex_ };
if (progress > display_->count())
*display_ += progress - display_->count();
}

void BoostProgressConsoleLogger::printResults(const ReachResultSummary& results) const
{
print(results.print());
}

#include <reach/plugin_utils.h>
EXPORT_LOGGER_PLUGIN(reach::BoostProgressConsoleLoggerFactory, BoostProgressConsoleLogger)
void BoostProgressConsoleLogger::print(const std::string& message) const
{
std::lock_guard<std::mutex> lock{ mutex_ };
std::cout << message << std::endl;
}

Logger::Ptr BoostProgressConsoleLoggerFactory::create(const YAML::Node& /*config*/) const
{
return std::make_shared<BoostProgressConsoleLogger>();
}

} // namespace reach
Loading

0 comments on commit a4afc2c

Please sign in to comment.