DynamicParameterClass.h
Go to the documentation of this file.
00001 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
00002 
00003 // -- BEGIN LICENSE BLOCK ----------------------------------------------
00004 // This file is part of the SCHUNK SVH Driver suite.
00005 //
00006 // This program is free software licensed under the LGPL
00007 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
00008 // You can find a copy of this license in LICENSE folder in the top
00009 // directory of the source code.
00010 //
00011 // © Copyright 2017 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
00012 // © Copyright 2017 FZI Forschungszentrum Informatik, Karlsruhe, Germany
00013 //
00014 // -- END LICENSE BLOCK ------------------------------------------------
00015 
00016 //----------------------------------------------------------------------
00026 //----------------------------------------------------------------------
00027 
00028 #ifndef SCHUNK_SVH_DRIVER_DYNAMIC_PARAMETER_CLASS_H_INCLUDED
00029 #define SCHUNK_SVH_DRIVER_DYNAMIC_PARAMETER_CLASS_H_INCLUDED
00030 
00031 #include <XmlRpcException.h>
00032 #include <iostream>
00033 #include <ros/ros.h>
00034 
00035 #include <driver_svh/SVHCurrentSettings.h>
00036 #include <driver_svh/SVHFingerManager.h>
00037 #include <driver_svh/SVHPositionSettings.h>
00038 
00042 class DynamicParameter
00043 {
00044 public:
00051   DynamicParameter( const uint16_t major_version,
00052                     const uint16_t minor_version,
00053                     XmlRpc::XmlRpcValue& parameters);
00054 
00055 
00059   struct Settings
00060   {
00061     Settings()
00062     : position_settings(driver_svh::eSVH_DIMENSION)
00063     , position_settings_given(driver_svh::eSVH_DIMENSION, false)
00064     , current_settings(driver_svh::eSVH_DIMENSION)
00065     , current_settings_given(driver_svh::eSVH_DIMENSION, false)
00066     , home_settings(driver_svh::eSVH_DIMENSION)
00067     , home_settings_given(driver_svh::eSVH_DIMENSION, false)
00068     , major_version(0)
00069     , minor_version(0)
00070     {}
00071 
00072     std::vector<std::vector<float> > position_settings;
00073     std::vector<bool> position_settings_given;
00074 
00075     std::vector<std::vector<float> > current_settings;
00076     std::vector<bool> current_settings_given;
00077 
00078     std::vector<std::vector<float> > home_settings;
00079     std::vector<bool> home_settings_given;
00080 
00081     uint16_t major_version;
00082     uint16_t minor_version;
00083   };
00084 
00085   const Settings& getSettings() const {return m_settings;}
00086 
00087 private:
00094   void parse_parameters(const uint16_t major_version,
00095                         const uint16_t minor_version,
00096                         XmlRpc::XmlRpcValue& parameters);
00097 
00098 
00104   bool xml_rpc_value_to_vector(XmlRpc::XmlRpcValue my_array, std::vector<float>& my_vector);
00105 
00107   Settings m_settings;
00108 
00110   std::map<driver_svh::SVHChannel, std::string> m_name_to_enum;
00111 };
00112 
00113 #endif // #ifdef SCHUNK_SVH_DRIVER_DYNAMIC_PARAMETER_CLASS_H_INCLUDED


schunk_svh_driver
Author(s): Georg Heppner
autogenerated on Thu Jun 6 2019 18:29:08