feature_finder.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 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/capture/feature_finder.h>
00020 #include <robot_calibration/capture/led_finder.h>
00021 #include <robot_calibration/capture/checkerboard_finder.h>
00022 #include <robot_calibration/capture/ground_plane_finder.h>
00023 
00024 namespace robot_calibration
00025 {
00026 
00027 bool loadFeatureFinders(ros::NodeHandle& nh,
00028                         FeatureFinderMap& features)
00029 {
00030   // Empty the mapping
00031   features.clear();
00032 
00033   // Construct finders to detect relevant features
00034   XmlRpc::XmlRpcValue finder_params;
00035   if (!nh.getParam("features", finder_params))
00036   {
00037     ROS_FATAL("Parameter 'features' is not set!");
00038     return false;
00039   }
00040 
00041   // Should be a struct (mapping name -> config)
00042   if (finder_params.getType() != XmlRpc::XmlRpcValue::TypeStruct)
00043   {
00044     ROS_FATAL("Parameter 'features' should be a struct.");
00045     return false;
00046   }
00047 
00048   ROS_INFO("Loading %d feature finders.", (int)finder_params.size());
00049 
00050   // Load each finder
00051   for (XmlRpc::XmlRpcValue::iterator it = finder_params.begin();
00052        it != finder_params.end();
00053        it++)
00054   {
00055     // Get name(space) of this finder
00056     std::string name = static_cast<std::string>(it->first);
00057     ros::NodeHandle finder_handle(nh, "features/"+name);
00058 
00059     // Get finder type
00060     std::string type;
00061     if (!finder_handle.getParam("type", type))
00062     {
00063       ROS_FATAL("Feature finder %s has no type defined", name.c_str());
00064       return false;
00065     }
00066 
00067     // Load correct finder
00068     // TODO: this will probably be plugin-based in the future
00069     FeatureFinderPtr finder;
00070     if (type == "robot_calibration/LedFinder")
00071     {
00072       ROS_INFO("  New robot_calibration/LedFinder: %s", name.c_str());
00073       finder.reset(new robot_calibration::LedFinder(finder_handle));
00074     }
00075     else if (type == "robot_calibration/GroundPlaneFinder")
00076     {
00077       ROS_INFO("  New robot_calibration/GroundPlaneFinder: %s", name.c_str());
00078       finder.reset(new robot_calibration::GroundPlaneFinder(finder_handle));
00079     }
00080     else if (type == "robot_calibration/CheckerboardFinder")
00081     {
00082       ROS_INFO("  New robot_calibration/CheckerboardFinder: %s", name.c_str());
00083       finder.reset(new robot_calibration::CheckerboardFinder(finder_handle));
00084     }
00085     else
00086     {
00087       ROS_FATAL("Unknown finder: %s", type.c_str());
00088       return false;
00089     }
00090 
00091     features[name] = finder;
00092   }
00093 
00094   return true;
00095 }
00096 
00097 }  // namespace robot_calibration


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