moveit_fake_controllers.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * Copyright (c) 2016, Robert Haschke
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the names of the authors nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan, Robert Haschke */
37 
40 #include <ros/publisher.h>
41 #include <ros/rate.h>
42 #include <boost/thread/thread.hpp>
43 
44 #ifndef MOVEIT_FAKE_CONTROLLERS
45 #define MOVEIT_FAKE_CONTROLLERS
46 
48 {
49 MOVEIT_CLASS_FORWARD(BaseFakeController);
50 
51 // common base class to all fake controllers in this package
53 {
54 public:
55  BaseFakeController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
56 
58  void getJoints(std::vector<std::string>& joints) const;
59 
60 protected:
61  std::vector<std::string> joints_;
63 };
64 
66 {
67 public:
68  LastPointController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
70 
71  virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory& t);
72  virtual bool cancelExecution();
73  virtual bool waitForExecution(const ros::Duration&);
74 };
75 
77 {
78 public:
79  ThreadedController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
81 
82  virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory& t);
83  virtual bool cancelExecution();
84  virtual bool waitForExecution(const ros::Duration&);
86 
87 protected:
88  bool cancelled()
89  {
90  return cancel_;
91  }
92 
93 private:
94  virtual void execTrajectory(const moveit_msgs::RobotTrajectory& t) = 0;
95  virtual void cancelTrajectory();
96 
97 private:
98  boost::thread thread_;
99  bool cancel_;
101 };
102 
104 {
105 public:
106  ViaPointController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
108 
109 protected:
110  virtual void execTrajectory(const moveit_msgs::RobotTrajectory& t);
111 };
112 
114 {
115 public:
116  InterpolatingController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
118 
119 protected:
120  virtual void execTrajectory(const moveit_msgs::RobotTrajectory& t);
121 
122 private:
124 };
125 }
126 
127 #endif
BaseFakeController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
MOVEIT_CLASS_FORWARD(BaseFakeController)
void getJoints(std::vector< std::string > &joints) const
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)=0
virtual bool waitForExecution(const ros::Duration &timeout=ros::Duration(0))=0
moveit_controller_manager::ExecutionStatus status_


moveit_fake_controller_manager
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:17:49