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); // Defines BaseFakeControllerPtr, ConstPtr, WeakPtr... etc
50 
51 // common base class to all fake controllers in this package
52 class BaseFakeController : public moveit_controller_manager::MoveItControllerHandle
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_;
62  const ros::Publisher& pub_;
63 };
64 
65 class LastPointController : public BaseFakeController
66 {
67 public:
68  LastPointController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
69  ~LastPointController() override;
70 
71  bool sendTrajectory(const moveit_msgs::RobotTrajectory& t) override;
72  bool cancelExecution() override;
73  bool waitForExecution(const ros::Duration& /*timeout*/) override;
74 };
75 
76 class ThreadedController : public BaseFakeController
77 {
78 public:
79  ThreadedController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
80  ~ThreadedController() override;
81 
82  bool sendTrajectory(const moveit_msgs::RobotTrajectory& t) override;
83  bool cancelExecution() override;
84  bool waitForExecution(const ros::Duration& /*timeout*/) override;
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);
107  ~ViaPointController() override;
108 
109 protected:
110  void execTrajectory(const moveit_msgs::RobotTrajectory& t) override;
111 };
112 
114 {
115 public:
116  InterpolatingController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
117  ~InterpolatingController() override;
118 
119 protected:
120  void execTrajectory(const moveit_msgs::RobotTrajectory& t) override;
121 
122 private:
124 };
125 } // namespace moveit_fake_controller_manager
126 
127 #endif
moveit_fake_controller_manager::LastPointController::sendTrajectory
bool sendTrajectory(const moveit_msgs::RobotTrajectory &t) override
Definition: moveit_fake_controllers.cpp:108
ros::Publisher
moveit_fake_controller_manager::InterpolatingController::rate_
ros::WallRate rate_
Definition: moveit_fake_controllers.h:156
moveit_fake_controller_manager::LastPointController::cancelExecution
bool cancelExecution() override
Definition: moveit_fake_controllers.cpp:127
moveit_fake_controller_manager::LastPointController::LastPointController
LastPointController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:100
moveit_fake_controller_manager::BaseFakeController::joints_
std::vector< std::string > joints_
Definition: moveit_fake_controllers.h:94
moveit_fake_controller_manager::ViaPointController::~ViaPointController
~ViaPointController() override
moveit_fake_controller_manager::LastPointController::~LastPointController
~LastPointController() override
moveit_fake_controller_manager::ThreadedController::execTrajectory
virtual void execTrajectory(const moveit_msgs::RobotTrajectory &t)=0
moveit_fake_controller_manager::InterpolatingController::execTrajectory
void execTrajectory(const moveit_msgs::RobotTrajectory &t) override
Definition: moveit_fake_controllers.cpp:251
moveit_fake_controller_manager::ViaPointController
Definition: moveit_fake_controllers.h:136
moveit_fake_controller_manager::ThreadedController::waitForExecution
bool waitForExecution(const ros::Duration &) override
Definition: moveit_fake_controllers.cpp:172
moveit_fake_controller_manager::InterpolatingController::~InterpolatingController
~InterpolatingController() override
moveit_fake_controller_manager::BaseFakeController::BaseFakeController
BaseFakeController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:79
moveit_fake_controller_manager::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(BaseFakeController)
controller_manager.h
publisher.h
moveit_fake_controller_manager::ThreadedController::getLastExecutionStatus
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
Definition: moveit_fake_controllers.cpp:179
moveit_fake_controller_manager::BaseFakeController::getLastExecutionStatus
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
Definition: moveit_fake_controllers.cpp:95
name
std::string name
ros::WallRate
moveit_fake_controller_manager::ThreadedController::cancelTrajectory
virtual void cancelTrajectory()
Definition: moveit_fake_controllers.cpp:149
moveit_fake_controller_manager::ThreadedController
Definition: moveit_fake_controllers.h:109
rate.h
moveit_fake_controller_manager::ViaPointController::ViaPointController
ViaPointController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:184
moveit_fake_controller_manager
Definition: moveit_fake_controller_manager.cpp:46
moveit_fake_controller_manager::ThreadedController::~ThreadedController
~ThreadedController() override
Definition: moveit_fake_controllers.cpp:144
moveit_fake_controller_manager::ThreadedController::sendTrajectory
bool sendTrajectory(const moveit_msgs::RobotTrajectory &t) override
Definition: moveit_fake_controllers.cpp:155
moveit_fake_controller_manager::ThreadedController::cancelled
bool cancelled()
Definition: moveit_fake_controllers.h:121
moveit_fake_controller_manager::ThreadedController::status_
moveit_controller_manager::ExecutionStatus status_
Definition: moveit_fake_controllers.h:133
moveit_fake_controller_manager::ThreadedController::cancel_
bool cancel_
Definition: moveit_fake_controllers.h:132
moveit_fake_controller_manager::BaseFakeController::pub_
const ros::Publisher & pub_
Definition: moveit_fake_controllers.h:95
moveit_fake_controller_manager::BaseFakeController::getJoints
void getJoints(std::vector< std::string > &joints) const
Definition: moveit_fake_controllers.cpp:90
moveit_fake_controller_manager::ThreadedController::cancelExecution
bool cancelExecution() override
Definition: moveit_fake_controllers.cpp:164
class_forward.h
moveit_fake_controller_manager::InterpolatingController::InterpolatingController
InterpolatingController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:222
moveit_fake_controller_manager::ThreadedController::thread_
boost::thread thread_
Definition: moveit_fake_controllers.h:131
moveit_fake_controller_manager::ThreadedController::ThreadedController
ThreadedController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:138
ros::Duration
moveit_controller_manager::ExecutionStatus
moveit_fake_controller_manager::ViaPointController::execTrajectory
void execTrajectory(const moveit_msgs::RobotTrajectory &t) override
Definition: moveit_fake_controllers.cpp:192
moveit_fake_controller_manager::InterpolatingController
Definition: moveit_fake_controllers.h:146
moveit_fake_controller_manager::LastPointController::waitForExecution
bool waitForExecution(const ros::Duration &) override
Definition: moveit_fake_controllers.cpp:132
moveit_controller_manager::MoveItControllerHandle


moveit_fake_controller_manager
Author(s): Ioan Sucan
autogenerated on Sat May 3 2025 02:26:28