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 
133  KDL::Frame getChainFK(const CalibrationOffsetParser& offsets,
134  const sensor_msgs::JointState& state);
135 
139  virtual std::string getName() const;
140 
144  virtual std::string getType() const;
145 
146 private:
147  KDL::Chain chain_;
148 
149 protected:
150  std::string root_;
151  std::string tip_;
152  std::string name_;
153 };
154 
156 KDL::Rotation rotation_from_axis_magnitude(const double x, const double y, const double z);
157 
159 void axis_magnitude_from_rotation(const KDL::Rotation& r, double& x, double& y, double& z);
160 
161 } // namespace robot_calibration
162 
163 #endif // ROBOT_CALIBRATION_MODELS_CHAIN_H
robot_calibration::ChainModel::name_
std::string name_
Definition: chain.h:152
robot_calibration::ChainModel::ChainModel
ChainModel(const std::string &name, KDL::Tree model, std::string root, std::string tip)
Create a new chain model.
Definition: models.cpp:41
robot_calibration::CalibrationOffsetParser
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
Definition: offset_parser.h:33
offset_parser.h
robot_calibration::ChainModel::root_
std::string root_
Definition: chain.h:150
robot_calibration::ChainModel::tip_
std::string tip_
Definition: chain.h:151
name
std::string name
robot_calibration::ChainModel::chain_
KDL::Chain chain_
Definition: chain.h:147
robot_calibration::ChainModel::~ChainModel
virtual ~ChainModel()
Definition: chain.h:118
robot_calibration::rotation_from_axis_magnitude
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:269
robot_calibration::axis_magnitude_from_rotation
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:282
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::ChainModel::getName
virtual std::string getName() const
Get the name of this model (as provided in the YAML config)
Definition: models.cpp:152
robot_calibration::ChainModel::getType
virtual std::string getType() const
Get the type of this model.
Definition: models.cpp:157
robot_calibration::ChainModel::getChainFK
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:117
robot_calibration::ChainModel::project
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:53
robot_calibration::ChainModel
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 Fri Sep 1 2023 02:52:01