controller_interface.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #ifndef COB_TWIST_CONTROLLER_CONTROLLER_INTERFACES_CONTROLLER_INTERFACE_H
00019 #define COB_TWIST_CONTROLLER_CONTROLLER_INTERFACES_CONTROLLER_INTERFACE_H
00020 
00021 #include <sensor_msgs/JointState.h>
00022 #include <std_msgs/Float64MultiArray.h>
00023 #include <trajectory_msgs/JointTrajectory.h>
00024 
00025 #include <boost/thread/mutex.hpp>
00026 
00027 #include "cob_twist_controller/cob_twist_controller_data_types.h"
00028 #include "cob_twist_controller/utils/moving_average.h"
00029 
00030 #include "cob_twist_controller/controller_interfaces/controller_interface_base.h"
00031 
00032 
00033 namespace cob_twist_controller
00034 {
00035 
00036 /* BEGIN ControllerInterfaceVelocity ****************************************************************************************/
00038 class ControllerInterfaceVelocity : public ControllerInterfaceBase
00039 {
00040     public:
00041         ControllerInterfaceVelocity() {}
00042         ~ControllerInterfaceVelocity() {}
00043 
00044         virtual void initialize(ros::NodeHandle& nh,
00045                                 const TwistControllerParams& params);
00046         virtual void processResult(const KDL::JntArray& q_dot_ik,
00047                                    const KDL::JntArray& current_q);
00048 };
00049 /* END ControllerInterfaceVelocity **********************************************************************************************/
00050 
00051 
00052 /* BEGIN ControllerInterfacePosition ****************************************************************************************/
00054 class ControllerInterfacePosition : public ControllerInterfacePositionBase
00055 {
00056     public:
00057         ControllerInterfacePosition() {}
00058         ~ControllerInterfacePosition() {}
00059 
00060         virtual void initialize(ros::NodeHandle& nh,
00061                                 const TwistControllerParams& params);
00062         virtual void processResult(const KDL::JntArray& q_dot_ik,
00063                                    const KDL::JntArray& current_q);
00064 };
00065 /* END ControllerInterfacePosition **********************************************************************************************/
00066 
00067 
00068 /* BEGIN ControllerInterfaceTrajectory ****************************************************************************************/
00070 class ControllerInterfaceTrajectory : public ControllerInterfacePositionBase
00071 {
00072     public:
00073         ControllerInterfaceTrajectory() {}
00074         ~ControllerInterfaceTrajectory() {}
00075 
00076         virtual void initialize(ros::NodeHandle& nh,
00077                                 const TwistControllerParams& params);
00078         virtual void processResult(const KDL::JntArray& q_dot_ik,
00079                                    const KDL::JntArray& current_q);
00080 };
00081 /* END ControllerInterfaceTrajectory **********************************************************************************************/
00082 
00083 /* BEGIN ControllerInterfaceJointStates ****************************************************************************************/
00085 class ControllerInterfaceJointStates : public ControllerInterfacePositionBase
00086 {
00087     public:
00088         ControllerInterfaceJointStates() {}
00089         ~ControllerInterfaceJointStates() {}
00090 
00091         virtual void initialize(ros::NodeHandle& nh,
00092                                 const TwistControllerParams& params);
00093         virtual void processResult(const KDL::JntArray& q_dot_ik,
00094                                    const KDL::JntArray& current_q);
00095 
00096     private:
00097         boost::mutex mutex_;
00098         sensor_msgs::JointState js_msg_;
00099 
00100         ros::Timer js_timer_;
00101         void publishJointState(const ros::TimerEvent& event);
00102 };
00103 /* END ControllerInterfaceJointStates **********************************************************************************************/
00104 
00105 }
00106 
00107 #endif  // COB_TWIST_CONTROLLER_CONTROLLER_INTERFACES_CONTROLLER_INTERFACE_H


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Jun 6 2019 21:19:26