moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
config.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
37#pragma once
38
42#include <rclcpp/node.hpp>
43#include <yaml-cpp/yaml.h>
44
45#include <set>
46
47namespace moveit_setup
48{
49class DataWarehouse;
50// NB: We don't use DataWarehousePtr here because it gets complicated with this abstract usage
51
52MOVEIT_CLASS_FORWARD(SetupConfig); // Defines SetupConfigPtr, ConstPtr, WeakPtr... etc
53
58{
59public:
60 SetupConfig() = default;
61 SetupConfig(const SetupConfig&) = default;
63 SetupConfig& operator=(const SetupConfig&) = default;
65 virtual ~SetupConfig() = default;
66
73 void initialize(const std::shared_ptr<DataWarehouse>& config_data, const rclcpp::Node::SharedPtr& parent_node,
74 const std::string& name)
75 {
76 config_data_ = config_data;
77 parent_node_ = parent_node;
78 name_ = name;
79 logger_ = std::make_shared<rclcpp::Logger>(parent_node->get_logger().get_child(name));
80 onInit();
81 }
82
86 virtual void onInit()
87 {
88 }
89
93 const std::string& getName()
94 {
95 return name_;
96 }
97
101 virtual bool isConfigured() const
102 {
103 return false;
104 }
105
118 virtual void loadPrevious(const std::filesystem::path& /*config_package_path*/, const YAML::Node& /*node*/)
119 {
120 }
121
125 virtual YAML::Node saveToYaml() const
126 {
127 return YAML::Node();
128 }
129
137 virtual void collectFiles(const std::filesystem::path& /*package_path*/, const GeneratedTime& /*last_gen_time*/,
138 std::vector<GeneratedFilePtr>& /*files*/)
139 {
140 }
141
147 virtual void collectDependencies(std::set<std::string>& /*packages*/) const
148 {
149 }
150
156 virtual void collectVariables(std::vector<TemplateVariable>& /*variables*/)
157 {
158 }
159
160protected:
161 std::shared_ptr<DataWarehouse> config_data_;
162 rclcpp::Node::SharedPtr parent_node_;
163 std::string name_;
164 std::shared_ptr<rclcpp::Logger> logger_;
165};
166} // namespace moveit_setup
#define MOVEIT_CLASS_FORWARD(C)
where all the data for each part of the configuration is stored.
Definition config.hpp:58
virtual void collectVariables(std::vector< TemplateVariable > &)
Collect key/value pairs for use in templates.
Definition config.hpp:156
rclcpp::Node::SharedPtr parent_node_
Definition config.hpp:162
void initialize(const std::shared_ptr< DataWarehouse > &config_data, const rclcpp::Node::SharedPtr &parent_node, const std::string &name)
Called after construction to initialize the step.
Definition config.hpp:73
std::shared_ptr< DataWarehouse > config_data_
Definition config.hpp:161
SetupConfig(const SetupConfig &)=default
std::shared_ptr< rclcpp::Logger > logger_
Definition config.hpp:164
const std::string & getName()
The name for this part of the configuration.
Definition config.hpp:93
virtual bool isConfigured() const
Return true if this part of the configuration is completely set up.
Definition config.hpp:101
virtual ~SetupConfig()=default
virtual void onInit()
Overridable initialization method.
Definition config.hpp:86
virtual YAML::Node saveToYaml() const
Optionally save "meta" information for saving in the .setup_assistant yaml file.
Definition config.hpp:125
virtual void collectFiles(const std::filesystem::path &, const GeneratedTime &, std::vector< GeneratedFilePtr > &)
Collect the files generated by this configuration and add them to the vector.
Definition config.hpp:137
SetupConfig & operator=(SetupConfig &&)=default
virtual void collectDependencies(std::set< std::string > &) const
Collect the package dependencies generated by this configuration.
Definition config.hpp:147
SetupConfig & operator=(const SetupConfig &)=default
virtual void loadPrevious(const std::filesystem::path &, const YAML::Node &)
Loads the configuration from an existing MoveIt configuration.
Definition config.hpp:118
SetupConfig(SetupConfig &&)=default
std::filesystem::file_time_type GeneratedTime