chain.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2015 Fetch Robotics Inc.
00003  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
00004  *
00005  * Licensed under the Apache License, Version 2.0 (the "License");
00006  * you may not use this file except in compliance with the License.
00007  * You may obtain a copy of the License at
00008  *
00009  *     http://www.apache.org/licenses/LICENSE-2.0
00010  *
00011  * Unless required by applicable law or agreed to in writing, software
00012  * distributed under the License is distributed on an "AS IS" BASIS,
00013  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014  * See the License for the specific language governing permissions and
00015  * limitations under the License.
00016  */
00017 
00018 // Author: Michael Ferguson
00019 
00020 #ifndef ROBOT_CALIBRATION_MODELS_CHAIN_H
00021 #define ROBOT_CALIBRATION_MODELS_CHAIN_H
00022 
00023 #include <string>
00024 #include <kdl/chain.hpp>
00025 #include <kdl/tree.hpp>
00026 #include <robot_calibration/calibration_offset_parser.h>
00027 
00028 #include <geometry_msgs/PointStamped.h>
00029 #include <sensor_msgs/JointState.h>
00030 #include <robot_calibration_msgs/CalibrationData.h>
00031 
00033 namespace robot_calibration
00034 {
00035 
00107 class ChainModel
00108 {
00109 public:
00117   ChainModel(const std::string& name, KDL::Tree model, std::string root, std::string tip);
00118   virtual ~ChainModel() {}
00119 
00125   virtual std::vector<geometry_msgs::PointStamped> project(
00126     const robot_calibration_msgs::CalibrationData& data,
00127     const CalibrationOffsetParser& offsets);
00128 
00133   KDL::Frame getChainFK(const CalibrationOffsetParser& offsets,
00134                         const sensor_msgs::JointState& state);
00135 
00136   std::string name() const;
00137 
00138 private:
00139   KDL::Chain chain_;
00140 
00141 protected:
00142   std::string root_;
00143   std::string tip_;
00144   std::string name_;
00145 };
00146 
00148 KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z);
00149 
00151 void axis_magnitude_from_rotation(const KDL::Rotation& r, double& x, double& y, double& z);
00152 
00153 inline std::string ChainModel::name() const
00154 {
00155   return name_;
00156 }
00157 
00158 }  // namespace robot_calibration
00159 
00160 #endif  // ROBOT_CALIBRATION_MODELS_CHAIN_H


robot_calibration
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 21:54:10