optimization_params.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2014 Fetch Robotics Inc.
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 // Author: Michael Ferguson
00018 
00019 #ifndef ROBOT_CALIBRATION_CERES_OPTIMIZATION_PARAMS_H
00020 #define ROBOT_CALIBRATION_CERES_OPTIMIZATION_PARAMS_H
00021 
00022 #include <ros/ros.h>
00023 
00024 namespace robot_calibration
00025 {
00026 
00028 struct OptimizationParams
00029 {
00030   struct FreeFrameParams
00031   {
00032     std::string name;
00033     bool x;
00034     bool y;
00035     bool z;
00036     bool roll;
00037     bool pitch;
00038     bool yaw;
00039   };
00040 
00041   struct Params
00042   {
00043     std::string name;
00044     std::string type;
00045     XmlRpc::XmlRpcValue params;
00046   };
00047 
00048   std::string base_link;
00049   std::vector<std::string> free_params;
00050   std::vector<FreeFrameParams> free_frames;
00051   std::vector<Params> models;
00052   std::vector<Params> error_blocks;
00053 
00054   OptimizationParams();
00055   bool LoadFromROS(ros::NodeHandle& nh);
00056 };
00057 
00058 }  // namespace robot_calibration
00059 
00060 #endif  // ROBOT_CALIBRATION_CERES_OPTIMIZATION_PARAMS_H


robot_calibration
Author(s): Michael Ferguson
autogenerated on Sat May 20 2017 02:35:31