DynamicParameterClass.h
Go to the documentation of this file.
1 //
3 // © Copyright 2022 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
4 // © Copyright 2022 FZI Forschungszentrum Informatik, Karlsruhe, Germany
5 //
6 // This file is part of the Schunk SVH Driver.
7 //
8 // The Schunk SVH Driver is free software: you can redistribute it and/or
9 // modify it under the terms of the GNU General Public License as published by
10 // the Free Software Foundation, either version 3 of the License, or (at your
11 // option) any later version.
12 //
13 // The Schunk SVH Driver is distributed in the hope that it will be useful,
14 // but WITHOUT ANY WARRANTY; without even the implied warranty of
15 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
16 // Public License for more details.
17 //
18 // You should have received a copy of the GNU General Public License along with
19 // the Schunk SVH Driver. If not, see <https://www.gnu.org/licenses/>.
20 //
22 
23 //----------------------------------------------------------------------
33 //----------------------------------------------------------------------
34 
35 #ifndef SCHUNK_SVH_DRIVER_DYNAMIC_PARAMETER_CLASS_H_INCLUDED
36 #define SCHUNK_SVH_DRIVER_DYNAMIC_PARAMETER_CLASS_H_INCLUDED
37 
38 #include <XmlRpcException.h>
39 #include <iostream>
40 #include <ros/ros.h>
41 
45 
50 {
51 public:
58  DynamicParameter(const uint16_t major_version,
59  const uint16_t minor_version,
60  XmlRpc::XmlRpcValue& parameters);
61 
62 
66  struct Settings
67  {
75  , major_version(0)
76  , minor_version(0)
77  {
78  }
79 
80  std::vector<std::vector<float> > position_settings;
81  std::vector<bool> position_settings_given;
82 
83  std::vector<std::vector<float> > current_settings;
84  std::vector<bool> current_settings_given;
85 
86  std::vector<std::vector<float> > home_settings;
87  std::vector<bool> home_settings_given;
88 
89  uint16_t major_version;
90  uint16_t minor_version;
91  };
92 
93  const Settings& getSettings() const { return m_settings; }
94 
95 private:
102  void parse_parameters(const uint16_t major_version,
103  const uint16_t minor_version,
104  XmlRpc::XmlRpcValue& parameters);
105 
106 
112  bool xml_rpc_value_to_vector(XmlRpc::XmlRpcValue my_array, std::vector<float>& my_vector);
113 
116 
118  std::map<driver_svh::SVHChannel, std::string> m_name_to_enum;
119 };
120 
121 #endif // #ifdef SCHUNK_SVH_DRIVER_DYNAMIC_PARAMETER_CLASS_H_INCLUDED
SVHPositionSettings.h
DynamicParameter::Settings::home_settings_given
std::vector< bool > home_settings_given
Definition: DynamicParameterClass.h:87
DynamicParameter::m_settings
Settings m_settings
Stores the settings received by the firmware.
Definition: DynamicParameterClass.h:115
ros.h
SVH_DIMENSION
SVH_DIMENSION
DynamicParameter::Settings::position_settings_given
std::vector< bool > position_settings_given
Definition: DynamicParameterClass.h:81
driver_svh
DynamicParameter::parse_parameters
void parse_parameters(const uint16_t major_version, const uint16_t minor_version, XmlRpc::XmlRpcValue &parameters)
This method parses the given XmlRpcValue array and sets the corresponding parameters.
Definition: DynamicParameterClass.cpp:104
DynamicParameter::Settings::home_settings
std::vector< std::vector< float > > home_settings
Definition: DynamicParameterClass.h:86
DynamicParameter::Settings::Settings
Settings()
Definition: DynamicParameterClass.h:68
DynamicParameter::Settings::current_settings_given
std::vector< bool > current_settings_given
Definition: DynamicParameterClass.h:84
DynamicParameter::Settings::position_settings
std::vector< std::vector< float > > position_settings
Definition: DynamicParameterClass.h:80
DynamicParameter::xml_rpc_value_to_vector
bool xml_rpc_value_to_vector(XmlRpc::XmlRpcValue my_array, std::vector< float > &my_vector)
Converts the given XmlRpcValue array to a std:vector /param my_array XmlRpcValue array created by rea...
Definition: DynamicParameterClass.cpp:76
SVHCurrentSettings.h
SVHFingerManager.h
DynamicParameter::Settings
Inline struct to store the settings.
Definition: DynamicParameterClass.h:66
DynamicParameter
Class to read parameter file and set the correct hardware parameters.
Definition: DynamicParameterClass.h:49
DynamicParameter::getSettings
const Settings & getSettings() const
Definition: DynamicParameterClass.h:93
DynamicParameter::Settings::major_version
uint16_t major_version
Definition: DynamicParameterClass.h:89
DynamicParameter::Settings::minor_version
uint16_t minor_version
Definition: DynamicParameterClass.h:90
DynamicParameter::Settings::current_settings
std::vector< std::vector< float > > current_settings
Definition: DynamicParameterClass.h:83
XmlRpcException.h
DynamicParameter::m_name_to_enum
std::map< driver_svh::SVHChannel, std::string > m_name_to_enum
Stores an enum-string matching map.
Definition: DynamicParameterClass.h:118
DynamicParameter::DynamicParameter
DynamicParameter(const uint16_t major_version, const uint16_t minor_version, XmlRpc::XmlRpcValue &parameters)
DynamicParameter constructs a new dynamic parameter handler.
Definition: DynamicParameterClass.cpp:40
XmlRpc::XmlRpcValue


schunk_svh_driver
Author(s): Georg Heppner , Felix Exner , Pascal Becker , Johannes Mangler
autogenerated on Sat Apr 15 2023 02:24:55