moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
data_warehouse.cpp
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
41
42namespace moveit_setup
43{
44DataWarehouse::DataWarehouse(const rclcpp::Node::SharedPtr& parent_node)
45 : parent_node_(parent_node), config_loader_("moveit_setup_framework", "moveit_setup::SetupConfig")
46{
47 registerType("urdf", "moveit_setup::URDFConfig");
48 registerType("srdf", "moveit_setup::SRDFConfig");
49 registerType("package_settings", "moveit_setup::PackageSettingsConfig");
50}
51
52void DataWarehouse::preloadWithURDFPath(const std::filesystem::path& urdf_path)
53{
54 get<URDFConfig>("urdf")->loadFromPath(urdf_path);
55}
56
57void DataWarehouse::preloadWithFullConfig(const std::string& package_path_or_name)
58{
59 get<PackageSettingsConfig>("package_settings")->loadExisting(package_path_or_name);
60}
61
62SetupConfigPtr DataWarehouse::get(const std::string& config_name, std::string config_class)
63{
64 if (config_class.empty())
65 {
66 auto it = registered_types_.find(config_name);
67 if (it == registered_types_.end())
68 {
69 throw std::runtime_error(config_name + " does not have a registered type in the data warehouse");
70 }
71 config_class = it->second;
72 }
73 auto it = configs_.find(config_name);
74 if (it != configs_.end())
75 {
76 return it->second;
77 }
78 auto config = config_loader_.createSharedInstance(config_class);
79 config->initialize(shared_from_this(), parent_node_, config_name);
80 configs_[config_name] = config;
81 return config;
82}
83
84void DataWarehouse::registerType(const std::string& config_name, const std::string& config_class)
85{
86 registered_types_[config_name] = config_class;
87 registered_names_.push_back(config_name);
88}
89
90std::vector<SetupConfigPtr> DataWarehouse::getConfigured()
91{
92 std::vector<SetupConfigPtr> configs;
93 for (const std::string& config_name : registered_names_)
94 {
95 auto it = configs_.find(config_name);
96 if (it == configs_.end())
97 {
98 continue;
99 }
100 SetupConfigPtr ptr = it->second;
101 if (ptr->isConfigured())
102 {
103 configs.push_back(ptr);
104 }
105 }
106 return configs;
107}
108
109const std::vector<std::string>& DataWarehouse::getRegisteredNames() const
110{
111 return registered_names_;
112}
113} // namespace moveit_setup
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_
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_
DataWarehouse(const rclcpp::Node::SharedPtr &parent_node)
std::unordered_map< std::string, SetupConfigPtr > configs_
rclcpp::Node::SharedPtr parent_node_
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.