calibration_offset_parser.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 Michael Ferguson
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_CALIBRATION_OFFSET_PARSER_H
21 #define ROBOT_CALIBRATION_CALIBRATION_OFFSET_PARSER_H
22 
23 #include <kdl/chain.hpp>
24 
26 {
27 
34 {
35 public:
38 
44  bool add(const std::string name);
45 
50  bool addFrame(const std::string name,
51  bool calibrate_x, bool calibrate_y, bool calibrate_z,
52  bool calibrate_roll, bool calibrate_pitch, bool calibrate_yaw);
53 
58  bool set(const std::string name, double value);
59 
64  bool setFrame(const std::string name,
65  double x, double y, double z,
66  double roll, double pitch, double yaw);
67 
69  bool initialize(double* free_params);
70 
72  bool update(const double* const free_params);
73 
75  double get(const std::string name) const;
76 
83  bool getFrame(const std::string name, KDL::Frame& offset) const;
84 
86  size_t size();
87 
89  bool reset();
90 
92  bool loadOffsetYAML(const std::string& filename);
93 
95  std::string getOffsetYAML();
96 
98  std::string updateURDF(const std::string& urdf);
99 
100 private:
101  // Names of parameters being calibrated. The order of this vector
102  // is the same as the free_param order will be interpreted.
103  std::vector<std::string> parameter_names_;
104 
105  // Names of frames being calibrated.
106  std::vector<std::string> frame_names_;
107 
108  // Values of parameters from last update
109  std::vector<double> parameter_offsets_;
110 
111  // Number of params being calibrated
113 
114  // No copy
117 };
118 
119 } // namespace robot_calibration
120 
121 #endif // ROBOT_CALIBRATION_CALIBRATION_OFFSET_PARSER_H
filename
CalibrationOffsetParser & operator=(const CalibrationOffsetParser &)
bool getFrame(const std::string name, KDL::Frame &offset) const
Get the offset for a frame calibration.
Combined parser and configuration for calibration offsets. Holds the configuration of what is to be c...
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string getOffsetYAML()
Get all the current offsets as a YAML.
bool initialize(double *free_params)
Initialize the free_params.
bool add(const std::string name)
Tell the parser we wish to calibrate an active joint or other single parameter.
bool setFrame(const std::string name, double x, double y, double z, double roll, double pitch, double yaw)
Set the values for a frame.
TFSIMD_FORCE_INLINE const tfScalar & x() const
Calibration code lives under this namespace.
TFSIMD_FORCE_INLINE const tfScalar & z() const
bool addFrame(const std::string name, bool calibrate_x, bool calibrate_y, bool calibrate_z, bool calibrate_roll, bool calibrate_pitch, bool calibrate_yaw)
Tell the parser we wish to calibrate a fixed joint.
std::string updateURDF(const std::string &urdf)
Update the urdf with the new offsets.
bool reset()
Clear free parameters, but retain values for multi-step calirations.
bool loadOffsetYAML(const std::string &filename)
Load all the current offsets from a YAML.
bool update(const double *const free_params)
Update the offsets based on free_params from ceres-solver.


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