chain.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Fetch Robotics Inc.
3  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  */
17 
18 // Author: Michael Ferguson
19 
20 #ifndef ROBOT_CALIBRATION_MODELS_CHAIN_H
21 #define ROBOT_CALIBRATION_MODELS_CHAIN_H
22 
23 #include <string>
24 #include <kdl/chain.hpp>
25 #include <kdl/tree.hpp>
27 
28 #include <geometry_msgs/PointStamped.h>
29 #include <sensor_msgs/JointState.h>
30 #include <robot_calibration_msgs/CalibrationData.h>
31 
33 namespace robot_calibration
34 {
35 
108 {
109 public:
117  ChainModel(const std::string& name, KDL::Tree model, std::string root, std::string tip);
118  virtual ~ChainModel() {}
119 
125  virtual std::vector<geometry_msgs::PointStamped> project(
126  const robot_calibration_msgs::CalibrationData& data,
127  const CalibrationOffsetParser& offsets);
128 
134  const sensor_msgs::JointState& state);
135 
136  std::string name() const;
137 
138 private:
140 
141 protected:
142  std::string root_;
143  std::string tip_;
144  std::string name_;
145 };
146 
148 KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z);
149 
151 void axis_magnitude_from_rotation(const KDL::Rotation& r, double& x, double& y, double& z);
152 
153 inline std::string ChainModel::name() const
154 {
155  return name_;
156 }
157 
158 } // namespace robot_calibration
159 
160 #endif // ROBOT_CALIBRATION_MODELS_CHAIN_H
virtual std::vector< geometry_msgs::PointStamped > project(const robot_calibration_msgs::CalibrationData &data, const CalibrationOffsetParser &offsets)
Compute the position of the estimated points.
Definition: models.cpp:48
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
ChainModel(const std::string &name, KDL::Tree model, std::string root, std::string tip)
Create a new chain model.
Definition: models.cpp:40
KDL::Frame getChainFK(const CalibrationOffsetParser &offsets, const sensor_msgs::JointState &state)
Compute the forward kinematics of the chain, based on the offsets and the joint positions of the stat...
Definition: models.cpp:112
Calibration code lives under this namespace.
void axis_magnitude_from_rotation(const KDL::Rotation &r, double &x, double &y, double &z)
Converts from KDL::Rotation to angle-axis-with-integrated-magnitude.
Definition: models.cpp:261
KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z)
Converts our angle-axis-with-integrated-magnitude representation to a KDL::Rotation.
Definition: models.cpp:248
std::string name() const
Definition: chain.h:153
Model of a kinematic chain. This is the basic instance where we transform the world observations into...
Definition: chain.h:107


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30