DynamicParameterTest.cpp
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 //----------------------------------------------------------------------
30 //----------------------------------------------------------------------
31 
32 
33 #include <XmlRpcException.h>
34 #include <iostream>
35 #include <ros/ros.h>
36 
37 #include "DynamicParameterClass.h"
41 
42 int main(int argc, char** argv)
43 {
44  ros::init(argc, argv, "DynamicParameterTest");
45  ros::NodeHandle private_node("~");
46 
47 
48  XmlRpc::XmlRpcValue parameters;
49  private_node.getParam("VERSIONS_PARAMETERS", parameters);
50 
51  DynamicParameter dyn_parameters(2, 2, parameters);
52 
53 
54  for (size_t channel = 0; channel < driver_svh::SVH_DIMENSION; ++channel)
55  {
56  ROS_INFO_STREAM("using channel " << channel);
57 
58  if (dyn_parameters.getSettings().position_settings_given[channel])
59  {
60  ROS_INFO("DYN POSITION SETTINGS...");
61  for (size_t j = 0; j < dyn_parameters.getSettings().position_settings[channel].size(); j++)
62  {
63  std::cout << dyn_parameters.getSettings().position_settings[channel][j] << " ";
64  }
65  std::cout << std::endl;
66  }
67 
68  if (dyn_parameters.getSettings().position_settings_given[channel])
69  {
70  ROS_INFO("DYN CURRENT SETTINGS:");
71  for (size_t j = 0; j < dyn_parameters.getSettings().current_settings[channel].size(); j++)
72  {
73  std::cout << dyn_parameters.getSettings().current_settings[channel][j] << " ";
74  }
75  std::cout << std::endl;
76  }
77 
78  if (dyn_parameters.getSettings().home_settings_given[channel])
79  {
80  ROS_INFO("DYN HOME SETTINGS:");
81  for (size_t j = 0; j < dyn_parameters.getSettings().home_settings[channel].size(); j++)
82  {
83  std::cout << dyn_parameters.getSettings().home_settings[channel][j] << " ";
84  }
85  }
86  std::cout << std::endl;
87  }
88  return 0;
89 }
SVHPositionSettings.h
DynamicParameter::Settings::home_settings_given
std::vector< bool > home_settings_given
Definition: DynamicParameterClass.h:87
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
driver_svh::SVH_DIMENSION
SVH_DIMENSION
DynamicParameter::Settings::position_settings_given
std::vector< bool > position_settings_given
Definition: DynamicParameterClass.h:81
DynamicParameter::Settings::home_settings
std::vector< std::vector< float > > home_settings
Definition: DynamicParameterClass.h:86
DynamicParameter::Settings::position_settings
std::vector< std::vector< float > > position_settings
Definition: DynamicParameterClass.h:80
SVHCurrentSettings.h
SVHFingerManager.h
DynamicParameter
Class to read parameter file and set the correct hardware parameters.
Definition: DynamicParameterClass.h:49
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
DynamicParameter::getSettings
const Settings & getSettings() const
Definition: DynamicParameterClass.h:93
DynamicParameterClass.h
DynamicParameter::Settings::current_settings
std::vector< std::vector< float > > current_settings
Definition: DynamicParameterClass.h:83
XmlRpcException.h
ROS_INFO
#define ROS_INFO(...)
XmlRpc::XmlRpcValue
ros::NodeHandle
main
int main(int argc, char **argv)
Definition: DynamicParameterTest.cpp:42


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