advanced_chainfksolver_recursive.hpp
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 ADVANCED_CHAINFKSOLVERPOS_RECURSIVE_H_
00019 #define ADVANCED_CHAINFKSOLVERPOS_RECURSIVE_H_
00020 
00021 #include <kdl/chainfksolver.hpp>
00022 #include <vector>
00023 #include <stdint.h>
00024 
00025 typedef std::vector<KDL::Frame> FrameVector_t;
00026 typedef std::vector<KDL::FrameVel> FrameVelVector_t;
00027 
00035 class AdvancedChainFkSolverPos_recursive : public KDL::ChainFkSolverPos
00036 {
00037     public:
00038         AdvancedChainFkSolverPos_recursive(const KDL::Chain& chain);
00039         ~AdvancedChainFkSolverPos_recursive();
00040 
00047         virtual int JntToCart(const KDL::JntArray& q_in, KDL::Frame& p_out, int seg_nr = -1);
00048 
00053         KDL::Frame getFrameAtSegment(uint16_t seg_idx) const;
00054 
00055         void dumpAllSegmentPostures() const;
00056 
00057     private:
00058         const KDL::Chain& chain_;
00059         FrameVector_t segment_pos_;
00060 
00061 };
00062 
00063 
00071 class AdvancedChainFkSolverVel_recursive : public KDL::ChainFkSolverVel
00072 {
00073     public:
00074         AdvancedChainFkSolverVel_recursive(const KDL::Chain& chain);
00075         ~AdvancedChainFkSolverVel_recursive();
00076 
00083         virtual int JntToCart(const KDL::JntArrayVel& q_in, KDL::FrameVel& out, int seg_nr = -1);
00084 
00089         KDL::FrameVel getFrameVelAtSegment(uint16_t seg_idx) const;
00090 
00091 
00092     private:
00093         const KDL::Chain& chain_;
00094         FrameVelVector_t segment_vel_;
00095 
00096 };
00097 
00098 
00099 #endif /* ADVANCED_CHAINFKSOLVERPOS_RECURSIVE_H_ */


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Jun 6 2019 21:19:14