DynamicParameterClass.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 // -- BEGIN LICENSE BLOCK ----------------------------------------------
4 // This file is part of the SCHUNK SVH Driver suite.
5 //
6 // This program is free software licensed under the LGPL
7 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
8 // You can find a copy of this license in LICENSE folder in the top
9 // directory of the source code.
10 //
11 // © Copyright 2017 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
12 // © Copyright 2017 FZI Forschungszentrum Informatik, Karlsruhe, Germany
13 //
14 // -- END LICENSE BLOCK ------------------------------------------------
15 
16 //----------------------------------------------------------------------
26 //----------------------------------------------------------------------
27 
28 #ifndef SCHUNK_SVH_DRIVER_DYNAMIC_PARAMETER_CLASS_H_INCLUDED
29 #define SCHUNK_SVH_DRIVER_DYNAMIC_PARAMETER_CLASS_H_INCLUDED
30 
31 #include <XmlRpcException.h>
32 #include <iostream>
33 #include <ros/ros.h>
34 
38 
43 {
44 public:
51  DynamicParameter( const uint16_t major_version,
52  const uint16_t minor_version,
53  XmlRpc::XmlRpcValue& parameters);
54 
55 
59  struct Settings
60  {
68  , major_version(0)
69  , minor_version(0)
70  {}
71 
72  std::vector<std::vector<float> > position_settings;
73  std::vector<bool> position_settings_given;
74 
75  std::vector<std::vector<float> > current_settings;
76  std::vector<bool> current_settings_given;
77 
78  std::vector<std::vector<float> > home_settings;
79  std::vector<bool> home_settings_given;
80 
83  };
84 
85  const Settings& getSettings() const {return m_settings;}
86 
87 private:
94  void parse_parameters(const uint16_t major_version,
95  const uint16_t minor_version,
96  XmlRpc::XmlRpcValue& parameters);
97 
98 
104  bool xml_rpc_value_to_vector(XmlRpc::XmlRpcValue my_array, std::vector<float>& my_vector);
105 
108 
110  std::map<driver_svh::SVHChannel, std::string> m_name_to_enum;
111 };
112 
113 #endif // #ifdef SCHUNK_SVH_DRIVER_DYNAMIC_PARAMETER_CLASS_H_INCLUDED
DynamicParameter(const uint16_t major_version, const uint16_t minor_version, XmlRpc::XmlRpcValue &parameters)
DynamicParameter constructs a new dynamic parameter handler.
std::vector< bool > home_settings_given
Settings m_settings
Stores the settings received by the firmware.
std::map< driver_svh::SVHChannel, std::string > m_name_to_enum
Stores an enum-string matching map.
std::vector< bool > position_settings_given
std::vector< std::vector< float > > position_settings
std::vector< std::vector< float > > home_settings
std::vector< bool > current_settings_given
Class to read parameter file and set the correct hardware parameters.
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...
const Settings & getSettings() const
unsigned short uint16_t
Inline struct to store the settings.
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.
std::vector< std::vector< float > > current_settings


schunk_svh_driver
Author(s): Georg Heppner
autogenerated on Mon Jun 10 2019 15:04:59