00001 /* 00002 * Copyright (C) 2014-2015 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 #include <robot_calibration/ceres/optimization_params.h> 00020 00021 namespace robot_calibration 00022 { 00023 00024 OptimizationParams::OptimizationParams() : 00025 base_link("base_link") 00026 { 00027 } 00028 00029 bool OptimizationParams::LoadFromROS(ros::NodeHandle& nh) 00030 { 00031 nh.param("base_link", base_link, base_link); 00032 00033 if (nh.hasParam("free_params")) 00034 { 00035 free_params.clear(); 00036 00037 XmlRpc::XmlRpcValue names; 00038 nh.getParam("free_params", names); 00039 ROS_ASSERT(names.getType() == XmlRpc::XmlRpcValue::TypeArray); 00040 00041 for (int i = 0; i < names.size(); ++i) 00042 { 00043 free_params.push_back(static_cast<std::string>(names[i])); 00044 } 00045 } 00046 00047 if (nh.hasParam("free_frames")) 00048 { 00049 free_frames.clear(); 00050 00051 XmlRpc::XmlRpcValue free_frame_params; 00052 nh.getParam("free_frames", free_frame_params); 00053 ROS_ASSERT(free_frame_params.getType() == XmlRpc::XmlRpcValue::TypeArray); 00054 00055 for (int i = 0; i < free_frame_params.size(); ++i) 00056 { 00057 FreeFrameParams params; 00058 params.name = static_cast<std::string>(free_frame_params[i]["name"]); 00059 params.x = static_cast<bool>(free_frame_params[i]["x"]); 00060 params.y = static_cast<bool>(free_frame_params[i]["y"]); 00061 params.z = static_cast<bool>(free_frame_params[i]["z"]); 00062 params.roll = static_cast<bool>(free_frame_params[i]["roll"]); 00063 params.pitch = static_cast<bool>(free_frame_params[i]["pitch"]); 00064 params.yaw = static_cast<bool>(free_frame_params[i]["yaw"]); 00065 free_frames.push_back(params); 00066 } 00067 } 00068 00069 if (nh.hasParam("models")) 00070 { 00071 models.clear(); 00072 00073 XmlRpc::XmlRpcValue model_params; 00074 nh.getParam("models", model_params); 00075 ROS_ASSERT(model_params.getType() == XmlRpc::XmlRpcValue::TypeArray); 00076 00077 for (int i = 0; i < model_params.size(); ++i) 00078 { 00079 Params params; 00080 params.name = static_cast<std::string>(model_params[i]["name"]); 00081 params.type = static_cast<std::string>(model_params[i]["type"]); 00082 params.params = model_params[i]; 00083 models.push_back(params); 00084 } 00085 } 00086 00087 if (nh.hasParam("error_blocks")) 00088 { 00089 error_blocks.clear(); 00090 00091 XmlRpc::XmlRpcValue error_params; 00092 nh.getParam("error_blocks", error_params); 00093 ROS_ASSERT(error_params.getType() == XmlRpc::XmlRpcValue::TypeArray); 00094 00095 for (int i = 0; i < error_params.size(); ++i) 00096 { 00097 Params params; 00098 params.name = static_cast<std::string>(error_params[i]["name"]); 00099 params.type = static_cast<std::string>(error_params[i]["type"]); 00100 params.params = error_params[i]; 00101 error_blocks.push_back(params); 00102 } 00103 } 00104 00105 return true; 00106 } 00107 00108 } // namespace robot_calibration