moveit2
The MoveIt Motion Planning Framework for ROS 2.
controllers.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 #pragma once
37 
41 
42 namespace moveit_setup
43 {
44 namespace controllers
45 {
50 {
51 public:
52  AdditionalControllerField(const std::string& display_name, const std::string& parameter_name)
53  : display_name_(display_name), parameter_name_(parameter_name)
54  {
55  }
56 
62  virtual ~AdditionalControllerField() = default;
63 
67  virtual std::string getDefaultValue(const std::string& /*controller_type*/) const
68  {
69  return "";
70  }
71 
72  std::string display_name_;
73  std::string parameter_name_;
74 };
75 
77 using FieldPointers = std::vector<std::shared_ptr<AdditionalControllerField>>;
78 
79 class Controllers : public SetupStep
80 {
81 public:
82  virtual std::string getInstructions() const = 0;
83 
84  virtual std::string getButtonText() const = 0;
85 
86  virtual std::vector<std::string> getAvailableTypes() const = 0;
87 
88  virtual std::string getDefaultType() const = 0;
89 
94  {
95  return FieldPointers();
96  }
97 
98  bool isReady() const override
99  {
100  return !srdf_config_->getGroups().empty();
101  }
102 
103  const std::vector<std::string>& getJointNames() const
104  {
105  return srdf_config_->getRobotModel()->getJointModelNames();
106  }
107 
108  std::vector<std::string> getGroupNames() const
109  {
110  return srdf_config_->getGroupNames();
111  }
112 
113  std::string getChildOfJoint(const std::string& joint_name) const
114  {
115  return srdf_config_->getChildOfJoint(joint_name);
116  }
117 
118  std::vector<ControllerInfo>& getControllers() const
119  {
120  return controllers_config_->getControllers();
121  }
122 
123  bool addController(const ControllerInfo& new_controller)
124  {
125  return controllers_config_->addController(new_controller);
126  }
127 
128  ControllerInfo* findControllerByName(const std::string& controller_name)
129  {
130  return controllers_config_->findControllerByName(controller_name);
131  }
132 
133  bool deleteController(const std::string& controller_name)
134  {
135  return controllers_config_->deleteController(controller_name);
136  }
137 
138  bool addDefaultControllers();
139 
140  std::vector<std::string> getJointsFromGroups(const std::vector<std::string>& group_names) const;
141 
142 protected:
143  std::shared_ptr<SRDFConfig> srdf_config_;
144  std::shared_ptr<ControllersConfig> controllers_config_;
145 };
146 } // namespace controllers
147 } // namespace moveit_setup
Contains all of the non-GUI code necessary for doing one "screen" worth of setup.
Definition: setup_step.hpp:47
Structure for containing information about types of additional parameters.
Definition: controllers.hpp:50
AdditionalControllerField(AdditionalControllerField &&)=default
AdditionalControllerField & operator=(AdditionalControllerField &&)=default
virtual std::string getDefaultValue(const std::string &) const
Overridable method for changing the default value based on the controller_type.
Definition: controllers.hpp:67
AdditionalControllerField(const std::string &display_name, const std::string &parameter_name)
Definition: controllers.hpp:52
AdditionalControllerField & operator=(const AdditionalControllerField &)=default
AdditionalControllerField(const AdditionalControllerField &)=default
bool isReady() const override
Return true if the data necessary to proceed with this step has been configured.
Definition: controllers.hpp:98
virtual FieldPointers getAdditionalControllerFields() const
Define the types of controller fields for the specific types of controllers.
Definition: controllers.hpp:93
std::vector< std::string > getGroupNames() const
std::vector< ControllerInfo > & getControllers() const
ControllerInfo * findControllerByName(const std::string &controller_name)
virtual std::string getDefaultType() const =0
bool addController(const ControllerInfo &new_controller)
std::shared_ptr< SRDFConfig > srdf_config_
const std::vector< std::string > & getJointNames() const
virtual std::vector< std::string > getAvailableTypes() const =0
std::shared_ptr< ControllersConfig > controllers_config_
bool deleteController(const std::string &controller_name)
std::vector< std::string > getJointsFromGroups(const std::vector< std::string > &group_names) const
Definition: controllers.cpp:71
virtual std::string getButtonText() const =0
std::string getChildOfJoint(const std::string &joint_name) const
virtual std::string getInstructions() const =0
std::vector< std::shared_ptr< AdditionalControllerField > > FieldPointers
Convenience alias.
Definition: controllers.hpp:77