moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
controllers_config.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
43
44namespace moveit_setup
45{
46namespace controllers
47{
52{
53 std::string name_; // controller name
54 std::string type_; // controller type
55 std::vector<std::string> joints_; // joints controlled by this controller
56 std::map<std::string, std::string> parameters_;
57};
58
63{
64public:
65 bool isConfigured() const override
66 {
67 return !controllers_.empty();
68 }
69
73 std::vector<ControllerInfo>& getControllers()
74 {
75 return controllers_;
76 }
77
85 bool addController(const std::string& name, const std::string& type, const std::vector<std::string>& joint_names);
86
92 bool addController(const ControllerInfo& new_controller);
93
100 ControllerInfo* findControllerByName(const std::string& controller_name);
101
108 bool deleteController(const std::string& controller_name);
109
110 bool hasChangedGroups() const
111 {
112 auto srdf_config = config_data_->get<SRDFConfig>("srdf");
113 return srdf_config->getChangeMask() & GROUPS;
114 }
115
116protected:
118 std::vector<ControllerInfo> controllers_;
120};
121} // namespace controllers
122} // namespace moveit_setup
unsigned long getChangeMask() const
where all the data for each part of the configuration is stored.
Definition config.hpp:58
std::shared_ptr< DataWarehouse > config_data_
Definition config.hpp:161
bool isConfigured() const override
Return true if this part of the configuration is completely set up.
std::vector< ControllerInfo > & getControllers()
Gets controllers_ vector.
ControllerInfo * findControllerByName(const std::string &controller_name)
std::vector< ControllerInfo > controllers_
Controllers config data.
bool deleteController(const std::string &controller_name)
bool addController(const std::string &name, const std::string &type, const std::vector< std::string > &joint_names)
Adds a controller to controllers_ vector.
std::map< std::string, std::string > parameters_