moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
srdf_step.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2022, Metro Robots
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 Metro Robots 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#pragma once
37
40
41namespace moveit_setup
42{
43namespace srdf_setup
44{
48class SRDFStep : public SetupStep
49{
50public:
51 void onInit() override
52 {
53 srdf_config_ = config_data_->get<SRDFConfig>("srdf");
54 }
55
56 bool isReady() const override
57 {
58 return srdf_config_->isConfigured();
59 }
60
61 bool hasGroups() const
62 {
63 return !srdf_config_->getGroups().empty();
64 }
65
66protected:
67 std::shared_ptr<SRDFConfig> srdf_config_;
68};
69
81template <typename T>
82class SuperSRDFStep : public SRDFStep
83{
84public:
88 virtual std::vector<T>& getContainer() = 0;
89
93 virtual InformationFields getInfoField() const = 0;
94
98 T* find(const std::string& name)
99 {
100 // Note: method is not const because otherwise we cannot return a non-const pointer
101 for (T& item : getContainer())
102 {
103 if (item.name_ == name)
104 {
105 return &item;
106 }
107 }
108 return nullptr;
109 }
110
115 T* create(const std::string& name)
116 {
117 T new_item;
118 new_item.name_ = name;
119 getContainer().push_back(new_item);
120 srdf_config_->updateRobotModel(getInfoField());
121 return &getContainer().back();
122 }
123
128 T* rename(const std::string& old_name, const std::string& new_name)
129 {
130 T* item = find(old_name);
131 T* existing_item = find(new_name);
132 if (existing_item)
133 {
134 throw std::runtime_error("An item already exists with that name!");
135 }
136 item->name_ = new_name;
137 srdf_config_->updateRobotModel(getInfoField());
138 return item;
139 }
140
145 bool remove(const std::string& name)
146 {
147 auto& container = getContainer();
148 for (auto it = container.begin(); it != container.end(); ++it)
149 {
150 if (it->name_ == name) // string match
151 {
152 container.erase(it);
153 srdf_config_->updateRobotModel(getInfoField());
154 return true;
155 }
156 }
157 return false;
158 }
159
164 T* get(const std::string& name, const std::string& old_name = "")
165 {
166 if (name == old_name)
167 {
168 return find(name);
169 }
170 else if (old_name.empty())
171 {
172 return create(name);
173 }
174 else
175 {
176 return rename(old_name, name);
177 }
178 }
179};
180} // namespace srdf_setup
181} // namespace moveit_setup
Contains all of the non-GUI code necessary for doing one "screen" worth of setup.
DataWarehousePtr config_data_
Setup Step that contains the SRDFConfig.
Definition srdf_step.hpp:49
bool isReady() const override
Return true if the data necessary to proceed with this step has been configured.
Definition srdf_step.hpp:56
void onInit() override
Overridable initialization method.
Definition srdf_step.hpp:51
std::shared_ptr< SRDFConfig > srdf_config_
Definition srdf_step.hpp:67
This class provides a number of standard operations based on srdf's vector members.
Definition srdf_step.hpp:83
T * get(const std::string &name, const std::string &old_name="")
Get a pointer to an item with the given name, creating if necessary. If old_name is provided (and is ...
T * find(const std::string &name)
Return a pointer to an item with the given name if it exists, otherwise null.
Definition srdf_step.hpp:98
T * create(const std::string &name)
Create an item with the given name and return the pointer.
T * rename(const std::string &old_name, const std::string &new_name)
Renames an item and returns a pointer to the item.
virtual InformationFields getInfoField() const =0
Returns the info field associated with this part of the SRDF.
virtual std::vector< T > & getContainer()=0
Returns the reference to the vector in the SRDF.
bool remove(const std::string &name)
Delete an item with the given name from the list.