00001 //================================================================================================= 00002 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt 00003 // All rights reserved. 00004 00005 // Redistribution and use in source and binary forms, with or without 00006 // modification, are permitted provided that the following conditions are met: 00007 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Flight Systems and Automatic Control group, 00013 // TU Darmstadt, nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 00029 #include "services.h" 00030 00031 namespace hector_pose_estimation { 00032 00033 SystemService::SystemService(RTT::TaskContext *owner, const SystemPtr& system, const std::string& name) 00034 : RTT::Service(name.empty() ? system->getName() : name, owner) 00035 { 00036 system->parameters().registerParams(boost::bind(®isterParamAsProperty, _1, this->properties())); 00037 } 00038 00039 SystemService::~SystemService() 00040 {} 00041 00042 MeasurementService::MeasurementService(RTT::TaskContext *owner, const MeasurementPtr& measurement, const std::string& name) 00043 : RTT::Service(name.empty() ? measurement->getName() : name, owner) 00044 { 00045 measurement->parameters().registerParams(boost::bind(®isterParamAsProperty, _1, this->properties())); 00046 } 00047 00048 MeasurementService::~MeasurementService() 00049 {} 00050 00051 void registerParamAsProperty(ParameterPtr ¶meter, RTT::PropertyBag *bag) { 00052 bag->removeProperty(bag->getProperty(parameter->key)); 00053 if (parameter->hasType<std::string>()) bag->addProperty(parameter->key, parameter->as<std::string>()); 00054 if (parameter->hasType<double>()) bag->addProperty(parameter->key, parameter->as<double>()); 00055 if (parameter->hasType<int>()) bag->addProperty(parameter->key, parameter->as<int>()); 00056 if (parameter->hasType<bool>()) bag->addProperty(parameter->key, parameter->as<bool>()); 00057 } 00058 00059 } // namespace hector_pose_estimation