controller_interface.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef COB_TWIST_CONTROLLER_CONTROLLER_INTERFACES_CONTROLLER_INTERFACE_H
19 #define COB_TWIST_CONTROLLER_CONTROLLER_INTERFACES_CONTROLLER_INTERFACE_H
20 
21 #include <sensor_msgs/JointState.h>
22 #include <std_msgs/Float64MultiArray.h>
23 #include <trajectory_msgs/JointTrajectory.h>
24 
25 #include <boost/thread/mutex.hpp>
26 
29 
31 
32 
34 {
35 
36 /* BEGIN ControllerInterfaceVelocity ****************************************************************************************/
39 {
40  public:
43 
44  virtual void initialize(ros::NodeHandle& nh,
45  const TwistControllerParams& params);
46  virtual void processResult(const KDL::JntArray& q_dot_ik,
47  const KDL::JntArray& current_q);
48 };
49 /* END ControllerInterfaceVelocity **********************************************************************************************/
50 
51 
52 /* BEGIN ControllerInterfacePosition ****************************************************************************************/
55 {
56  public:
59 
60  virtual void initialize(ros::NodeHandle& nh,
61  const TwistControllerParams& params);
62  virtual void processResult(const KDL::JntArray& q_dot_ik,
63  const KDL::JntArray& current_q);
64 };
65 /* END ControllerInterfacePosition **********************************************************************************************/
66 
67 
68 /* BEGIN ControllerInterfaceTrajectory ****************************************************************************************/
71 {
72  public:
75 
76  virtual void initialize(ros::NodeHandle& nh,
77  const TwistControllerParams& params);
78  virtual void processResult(const KDL::JntArray& q_dot_ik,
79  const KDL::JntArray& current_q);
80 };
81 /* END ControllerInterfaceTrajectory **********************************************************************************************/
82 
83 /* BEGIN ControllerInterfaceJointStates ****************************************************************************************/
86 {
87  public:
90 
91  virtual void initialize(ros::NodeHandle& nh,
92  const TwistControllerParams& params);
93  virtual void processResult(const KDL::JntArray& q_dot_ik,
94  const KDL::JntArray& current_q);
95 
96  private:
97  boost::mutex mutex_;
98  sensor_msgs::JointState js_msg_;
99 
101  void publishJointState(const ros::TimerEvent& event);
102 };
103 /* END ControllerInterfaceJointStates **********************************************************************************************/
104 
105 }
106 
107 #endif // COB_TWIST_CONTROLLER_CONTROLLER_INTERFACES_CONTROLLER_INTERFACE_H
Base class for controller interfaces using position integration.
Class providing a ControllerInterface publishing JointStates.
virtual void processResult(const KDL::JntArray &q_dot_ik, const KDL::JntArray &current_q)
virtual void initialize(ros::NodeHandle &nh, const TwistControllerParams &params)
Base class for controller interfaces.
Class providing a ControllerInterface publishing JointGroupPositionCommands.
Class providing a ControllerInterface publishing velocities.
Class providing a ControllerInterface publishing a JointTrajectory.


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:00