moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
data_warehouse.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2021, PickNik Robotics
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of PickNik Robotics nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: David V. Lu!! */
36
39#include <pluginlib/class_loader.hpp>
40#include <unordered_map>
41#include <memory>
42
43#pragma once
44
45namespace moveit_setup
46{
47MOVEIT_CLASS_FORWARD(DataWarehouse); // Defines DataWarehousePtr, ConstPtr, WeakPtr... etc
48
52class DataWarehouse : public std::enable_shared_from_this<DataWarehouse>
53{
54public:
55 DataWarehouse(const rclcpp::Node::SharedPtr& parent_node);
56
57 void preloadWithURDFPath(const std::filesystem::path& urdf_path);
58 void preloadWithFullConfig(const std::string& package_path_or_name);
59
68 SetupConfigPtr get(const std::string& config_name, std::string config_class = "");
69
81 template <typename T>
82 std::shared_ptr<T> get(const std::string& config_name, const std::string& config_class = "")
83 {
84 return std::static_pointer_cast<T>(get(config_name, config_class));
85 }
86
93 template <typename T>
94 std::unordered_map<std::string, std::shared_ptr<T>> getAll()
95 {
96 std::unordered_map<std::string, std::shared_ptr<T>> matches;
97 for (const auto& pair : registered_types_)
98 {
99 SetupConfigPtr uncast_ptr = get(pair.first);
100 std::shared_ptr<T> ptr = std::dynamic_pointer_cast<T>(uncast_ptr);
101 if (!ptr)
102 {
103 continue;
104 }
105
106 matches[pair.first] = ptr;
107 }
108 return matches;
109 }
110
114 void registerType(const std::string& config_name, const std::string& config_class);
115
119 std::vector<SetupConfigPtr> getConfigured();
120
124 const std::vector<std::string>& getRegisteredNames() const;
125
127 bool debug{ false };
128
129protected:
130 rclcpp::Node::SharedPtr parent_node_;
131 pluginlib::ClassLoader<SetupConfig> config_loader_;
132 std::unordered_map<std::string, SetupConfigPtr> configs_; // mapping from name to config
133 std::unordered_map<std::string, std::string> registered_types_; // mapping from name to config class type
134 std::vector<std::string> registered_names_; // string version of keys for the maps, with ordering
135};
136} // namespace moveit_setup
#define MOVEIT_CLASS_FORWARD(C)
Container for all of the SetupConfig object singletons.
void preloadWithFullConfig(const std::string &package_path_or_name)
SetupConfigPtr get(const std::string &config_name, std::string config_class="")
Get the singleton for a given config name and class.
std::unordered_map< std::string, std::string > registered_types_
std::shared_ptr< T > get(const std::string &config_name, const std::string &config_class="")
Get the specific singleton for a given config name and class.
const std::vector< std::string > & getRegisteredNames() const
Returns a list of config_names that have registered types associated with them.
pluginlib::ClassLoader< SetupConfig > config_loader_
std::vector< std::string > registered_names_
std::unordered_map< std::string, std::shared_ptr< T > > getAll()
Get all of the registered configs that match the given config_class.
std::unordered_map< std::string, SetupConfigPtr > configs_
rclcpp::Node::SharedPtr parent_node_
bool debug
Is this application in debug mode?
std::vector< SetupConfigPtr > getConfigured()
Returns a list of the SetupConfig for which isConfigured is true.
void preloadWithURDFPath(const std::filesystem::path &urdf_path)
void registerType(const std::string &config_name, const std::string &config_class)
Associates a class_name with the given name. Makes calls to get more succinct.