moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
configuration_files.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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#pragma once
38
39namespace moveit_setup
40{
41namespace core
42{
44{
45public:
46 std::string getName() const override
47 {
48 return "Configuration Files";
49 }
50
51 void onInit() override;
52
53 const std::filesystem::path& getPackagePath()
54 {
55 return package_settings_->getPackagePath();
56 }
57
58 void setPackagePath(const std::filesystem::path& package_path)
59 {
60 package_settings_->setPackagePath(package_path);
61 }
62
63 void setPackageName(const std::string& package_name)
64 {
65 package_settings_->setPackageName(package_name);
66 }
67
69 void loadFiles();
70
71 const std::vector<GeneratedFilePtr> getGeneratedFiles() const
72 {
73 return gen_files_;
74 }
75
76 unsigned int getNumFiles() const
77 {
78 return gen_files_.size();
79 }
80
81 bool shouldGenerate(const GeneratedFilePtr& file) const
82 {
83 std::string rel_path = file->getRelativePath();
84 auto it = should_generate_.find(rel_path);
85 if (it == should_generate_.end())
86 {
87 return true;
88 }
89 return it->second;
90 }
91
96
101
102 void setShouldGenerate(const std::string& rel_path, bool should_generate);
103
104 bool isExistingConfig();
106
108
109 std::vector<std::string> getIncompleteWarnings() const;
110
111 std::string getInvalidGroupName() const;
112
114 {
115 package_settings_->setGenerationTime();
116 }
117
118protected:
119 bool hasMatchingFileStatus(FileStatus status) const;
120
121 // ******************************************************************************************
122 // Variables
123 // ******************************************************************************************
125 std::vector<GeneratedFilePtr> gen_files_;
126
127 std::unordered_map<std::string, bool> should_generate_;
128
129 std::shared_ptr<PackageSettingsConfig> package_settings_;
130};
131} // namespace core
132} // namespace moveit_setup
Contains all of the non-GUI code necessary for doing one "screen" worth of setup.
void loadFiles()
Populate the 'Files to be generated' list.
void setShouldGenerate(const std::string &rel_path, bool should_generate)
const std::filesystem::path & getPackagePath()
void onInit() override
Overridable initialization method.
std::vector< std::string > getIncompleteWarnings() const
std::unordered_map< std::string, bool > should_generate_
std::vector< GeneratedFilePtr > gen_files_
Vector of all files to be generated.
void setPackagePath(const std::filesystem::path &package_path)
bool hasMatchingFileStatus(FileStatus status) const
bool shouldGenerate(const GeneratedFilePtr &file) const
std::shared_ptr< PackageSettingsConfig > package_settings_
std::string getName() const override
Returns the name of the setup step.
void setPackageName(const std::string &package_name)
const std::vector< GeneratedFilePtr > getGeneratedFiles() const
FileStatus
Status associated with each GeneratedFile.