moveit_controller_manager_example.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
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 Ioan A. Sucan 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 #include <ros/ros.h>
39 #include <sensor_msgs/JointState.h>
41 #include <map>
42 
44 {
46 {
47 public:
49  {
50  }
51 
52  virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory& t)
53  {
54  // do whatever is needed to actually execute this trajectory
55  return true;
56  }
57 
58  virtual bool cancelExecution()
59  {
60  // do whatever is needed to cancel execution
61  return true;
62  }
63 
64  virtual bool waitForExecution(const ros::Duration&)
65  {
66  // wait for the current execution to finish
67  return true;
68  }
69 
71  {
73  }
74 };
75 
77 {
78 public:
80  {
81  }
82 
84  {
85  }
86 
87  virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
88  {
89  return moveit_controller_manager::MoveItControllerHandlePtr(new ExampleControllerHandle(name));
90  }
91 
92  /*
93  * Get the list of controller names.
94  */
95  virtual void getControllersList(std::vector<std::string>& names)
96  {
97  names.resize(1);
98  names[0] = "my_example_controller";
99  }
100 
101  /*
102  * This plugin assumes that all controllers are already active -- and if they are not, well, it has no way to deal
103  * with it anyways!
104  */
105  virtual void getActiveControllers(std::vector<std::string>& names)
106  {
107  getControllersList(names);
108  }
109 
110  /*
111  * Controller must be loaded to be active, see comment above about active controllers...
112  */
113  virtual void getLoadedControllers(std::vector<std::string>& names)
114  {
115  getControllersList(names);
116  }
117 
118  /*
119  * Get the list of joints that a controller can control.
120  */
121  virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
122  {
123  joints.clear();
124  if (name == "my_example_controller")
125  {
126  // declare which joints this controller actuates
127  joints.push_back("joint1");
128  joints.push_back("joint2");
129  joints.push_back("joint3");
130  joints.push_back("joint4");
131  // ...
132  }
133  }
134 
135  /*
136  * Controllers are all active and default.
137  */
139  getControllerState(const std::string& name)
140  {
142  state.active_ = true;
143  state.default_ = true;
144  return state;
145  }
146 
147  /* Cannot switch our controllers */
148  virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
149  {
150  return false;
151  }
152 
153 protected:
155  std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> controllers_;
156 };
157 
158 } // end namespace moveit_controller_manager_example
159 
PLUGINLIB_EXPORT_CLASS(moveit_controller_manager_example::MoveItControllerManagerExample, moveit_controller_manager::MoveItControllerManager)
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &t)
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
std::map< std::string, moveit_controller_manager::MoveItControllerHandlePtr > controllers_


moveit_controller_manager_example
Author(s): Ioan Sucan
autogenerated on Wed Jul 10 2019 04:03:25