moveit2
The MoveIt Motion Planning Framework for ROS 2.
controller_manager.h
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 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
39 #include <vector>
40 #include <string>
41 #include <moveit_msgs/msg/robot_trajectory.hpp>
43 #include <rclcpp/rclcpp.hpp>
44 
47 {
50 {
51  enum Value
52  {
59  FAILED
60  };
61 
62  ExecutionStatus(Value value = UNKNOWN) : status_(value)
63  {
64  }
65 
66  operator Value() const
67  {
68  return status_;
69  }
70 
71  explicit operator bool() const
72  {
73  return status_ == SUCCEEDED;
74  }
75 
77  std::string asString() const
78  {
79  switch (status_)
80  {
81  case RUNNING:
82  return "RUNNING";
83  case SUCCEEDED:
84  return "SUCCEEDED";
85  case PREEMPTED:
86  return "PREEMPTED";
87  case TIMED_OUT:
88  return "TIMED_OUT";
89  case ABORTED:
90  return "ABORTED";
91  case FAILED:
92  return "FAILED";
93  default:
94  return "UNKNOWN";
95  }
96  }
97 
98 private:
99  Value status_;
100 };
101 
102 MOVEIT_CLASS_FORWARD(MoveItControllerHandle); // Defines MoveItControllerHandlePtr, ConstPtr, WeakPtr... etc
103 
106 {
107 public:
109  MoveItControllerHandle(const std::string& name) : name_(name)
110  {
111  }
112 
114  {
115  }
116 
118  const std::string& getName() const
119  {
120  return name_;
121  }
122 
128  virtual bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory& trajectory) = 0;
129 
134  virtual bool cancelExecution() = 0;
135 
141  virtual bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration::from_nanoseconds(-1)) = 0;
142 
145 
146 protected:
147  std::string name_;
148 };
149 
150 MOVEIT_CLASS_FORWARD(MoveItControllerManager); // Defines MoveItControllerManagerPtr, ConstPtr, WeakPtr... etc
151 
158 {
159 public:
163  {
164  ControllerState() : active_(false), default_(false)
165  {
166  }
167 
170  bool active_;
171 
174  bool default_;
175  };
176 
179  {
180  }
181 
183  {
184  }
185 
186  virtual void initialize(const rclcpp::Node::SharedPtr& node) = 0;
187 
189  virtual MoveItControllerHandlePtr getControllerHandle(const std::string& name) = 0;
190 
192  virtual void getControllersList(std::vector<std::string>& names) = 0;
193 
198  virtual void getActiveControllers(std::vector<std::string>& names) = 0;
199 
204  virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints) = 0;
205 
207  virtual ControllerState getControllerState(const std::string& name) = 0;
208 
210  virtual bool switchControllers(const std::vector<std::string>& activate,
211  const std::vector<std::string>& deactivate) = 0;
212 };
213 } // namespace moveit_controller_manager
MoveIt sends commands to a controller via a handle that satisfies this interface.
virtual ExecutionStatus getLastExecutionStatus()=0
Return the execution status of the last trajectory sent to the controller.
const std::string & getName() const
Get the name of the controller this handle can send commands to.
virtual bool waitForExecution(const rclcpp::Duration &timeout=rclcpp::Duration::from_nanoseconds(-1))=0
Wait for the current execution to complete, or until the timeout is reached.
virtual bool cancelExecution()=0
Cancel the execution of any motion using this controller.
virtual bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &trajectory)=0
Send a trajectory to the controller.
MoveItControllerHandle(const std::string &name)
Each controller has a name. The handle is initialized with that name.
MoveIt does not enforce how controllers are implemented. To make your controllers usable by MoveIt,...
virtual void getActiveControllers(std::vector< std::string > &names)=0
Get the list of active controllers.
virtual void getControllersList(std::vector< std::string > &names)=0
Get the list of known controller names.
virtual MoveItControllerHandlePtr getControllerHandle(const std::string &name)=0
Return a given named controller.
virtual ControllerState getControllerState(const std::string &name)=0
Report the state of a controller, given its name.
MoveItControllerManager()
Default constructor. This needs to have no arguments so that the plugin system can construct the obje...
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)=0
Activate and deactivate controllers.
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)=0
Report the joints a controller operates on, given the controller name.
virtual void initialize(const rclcpp::Node::SharedPtr &node)=0
Namespace for the base class of a MoveIt controller manager.
MOVEIT_CLASS_FORWARD(MoveItControllerHandle)
name
Definition: setup.py:7
std::string asString() const
Convert the execution status to a string.
Each controller known to MoveIt has a state. This structure describes that controller's state.
bool default_
It is often the case that multiple controllers could be used to execute a motion. Marking a controlle...
bool active_
A controller can be active or inactive. This means that MoveIt could activate the controller when nee...