SVHWrapper.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 //----------------------------------------------------------------------
30 //----------------------------------------------------------------------
31 
32 #ifndef S5FH_WRAPPER_H_INCLUDED
33 #define S5FH_WRAPPER_H_INCLUDED
34 
35 #include <ros/ros.h>
36 
37 #include <sensor_msgs/JointState.h>
38 #include <std_msgs/Empty.h>
39 #include <std_msgs/Float64MultiArray.h>
40 #include <std_msgs/Int8.h>
41 
42 #include <memory>
43 #include <schunk_svh_msgs/HomeAll.h>
44 #include <schunk_svh_msgs/HomeWithChannels.h>
45 #include <schunk_svh_msgs/SetAllChannelForceLimits.h>
46 #include <schunk_svh_msgs/SetChannelForceLimit.h>
47 
48 // Driver Specific things
50 
51 #include <SVHDiagnostics.h>
52 
54 {
55 public:
56  SVHWrapper(const ros::NodeHandle& nh);
57  ~SVHWrapper();
58 
59  std::shared_ptr<driver_svh::SVHFingerManager> getFingerManager() const
60  {
61  return m_finger_manager;
62  }
63 
64  std::string getNamePrefix() const { return m_name_prefix; }
65 
66  bool channelsEnabled() { return m_channels_enabled; };
67 
68 private:
69  void initControllerParameters(const uint16_t manual_major_version,
70  const uint16_t manual_minor_version);
71 
73  bool connect();
74 
76  void connectCallback(const std_msgs::Empty&);
77 
79  void setRosControlEnable(bool enable);
80 
83 
85  std::shared_ptr<driver_svh::SVHFingerManager> m_finger_manager;
86 
88  std::shared_ptr<SVHDiagnostics> m_svh_diagnostics;
89 
91  std::string m_serial_device_name;
92 
94  void resetChannelCallback(const std_msgs::Int8ConstPtr& channel);
95 
97  void enableChannelCallback(const std_msgs::Int8ConstPtr& channel);
98 
99  bool homeAllNodes(schunk_svh_msgs::HomeAllRequest& req, schunk_svh_msgs::HomeAllResponse& resp);
100 
101  bool homeNodesChannelIds(schunk_svh_msgs::HomeWithChannelsRequest& req,
102  schunk_svh_msgs::HomeWithChannelsResponse& resp);
103 
104  bool setAllForceLimits(schunk_svh_msgs::SetAllChannelForceLimits::Request& req,
105  schunk_svh_msgs::SetAllChannelForceLimits::Response& res);
106  bool setForceLimitById(schunk_svh_msgs::SetChannelForceLimit::Request& req,
107  schunk_svh_msgs::SetChannelForceLimit::Response& res);
108 
109  float setChannelForceLimit(size_t channel, float force_limit);
110 
111 
115 
118  std::string m_name_prefix;
119 
124 
127 
130 
135 };
136 
137 #endif // #ifdef S5FH_WRAPPER_H_INCLUDED
SVHWrapper::m_setAllForceLimits_srv
ros::ServiceServer m_setAllForceLimits_srv
Definition: SVHWrapper.h:133
SVHWrapper::m_svh_diagnostics
std::shared_ptr< SVHDiagnostics > m_svh_diagnostics
Handle to the diagnostics test class creating a test protocol with the web gui package.
Definition: SVHWrapper.h:88
SVHWrapper::m_firmware_major_version
int m_firmware_major_version
Definition: SVHWrapper.h:122
SVHWrapper::m_channels_enabled
bool m_channels_enabled
m_channels_enabled enables the ros-control-loop in the hw interface
Definition: SVHWrapper.h:126
ros.h
SVHWrapper::enable_sub
ros::Subscriber enable_sub
Definition: SVHWrapper.h:129
SVHWrapper::enableChannelCallback
void enableChannelCallback(const std_msgs::Int8ConstPtr &channel)
Callback function to enable channels of SCHUNK five finger hand.
Definition: SVHWrapper.cpp:263
SVHWrapper::m_priv_nh
ros::NodeHandle m_priv_nh
private node handle
Definition: SVHWrapper.h:82
SVHWrapper::m_home_service_joint_names
ros::ServiceServer m_home_service_joint_names
Definition: SVHWrapper.h:132
SVHWrapper::m_finger_manager
std::shared_ptr< driver_svh::SVHFingerManager > m_finger_manager
Handle to the SVH finger manager for library access.
Definition: SVHWrapper.h:85
SVHWrapper::m_home_service_all
ros::ServiceServer m_home_service_all
Definition: SVHWrapper.h:131
ros::ServiceServer
SVHWrapper::connectCallback
void connectCallback(const std_msgs::Empty &)
Callback function for connecting to SCHUNK five finger hand.
Definition: SVHWrapper.cpp:256
SVHWrapper::homeNodesChannelIds
bool homeNodesChannelIds(schunk_svh_msgs::HomeWithChannelsRequest &req, schunk_svh_msgs::HomeWithChannelsResponse &resp)
Definition: SVHWrapper.cpp:286
SVHWrapper::m_name_prefix
std::string m_name_prefix
Definition: SVHWrapper.h:118
SVHWrapper::setChannelForceLimit
float setChannelForceLimit(size_t channel, float force_limit)
Definition: SVHWrapper.cpp:341
SVHWrapper::setAllForceLimits
bool setAllForceLimits(schunk_svh_msgs::SetAllChannelForceLimits::Request &req, schunk_svh_msgs::SetAllChannelForceLimits::Response &res)
Definition: SVHWrapper.cpp:323
SVHWrapper::homeAllNodes
bool homeAllNodes(schunk_svh_msgs::HomeAllRequest &req, schunk_svh_msgs::HomeAllResponse &resp)
Definition: SVHWrapper.cpp:268
SVHFingerManager.h
SVHWrapper::setForceLimitById
bool setForceLimitById(schunk_svh_msgs::SetChannelForceLimit::Request &req, schunk_svh_msgs::SetChannelForceLimit::Response &res)
Definition: SVHWrapper.cpp:333
SVHWrapper::channelsEnabled
bool channelsEnabled()
Definition: SVHWrapper.h:66
SVHWrapper::setRosControlEnable
void setRosControlEnable(bool enable)
function to set the ros-control-loop enabling flag from the diagnostics class
Definition: SVHWrapper.cpp:136
SVHWrapper::initControllerParameters
void initControllerParameters(const uint16_t manual_major_version, const uint16_t manual_minor_version)
Definition: SVHWrapper.cpp:141
SVHWrapper::~SVHWrapper
~SVHWrapper()
Definition: SVHWrapper.cpp:201
SVHWrapper::m_serial_device_name
std::string m_serial_device_name
Serial device to use for communication with hardware.
Definition: SVHWrapper.h:91
SVHWrapper::getFingerManager
std::shared_ptr< driver_svh::SVHFingerManager > getFingerManager() const
Definition: SVHWrapper.h:59
SVHWrapper::getNamePrefix
std::string getNamePrefix() const
Definition: SVHWrapper.h:64
SVHDiagnostics.h
SVHWrapper
Definition: SVHWrapper.h:53
SVHWrapper::connect
bool connect()
load parameters and try connecting
Definition: SVHWrapper.cpp:207
SVHWrapper::connect_sub
ros::Subscriber connect_sub
Definition: SVHWrapper.h:128
SVHWrapper::m_firmware_minor_version
int m_firmware_minor_version
Definition: SVHWrapper.h:123
SVHWrapper::resetChannelCallback
void resetChannelCallback(const std_msgs::Int8ConstPtr &channel)
Callback function to reset/home channels of SCHUNK five finger hand.
SVHWrapper::SVHWrapper
SVHWrapper(const ros::NodeHandle &nh)
Definition: SVHWrapper.cpp:39
SVHWrapper::m_setForceLimitById_srv
ros::ServiceServer m_setForceLimitById_srv
Definition: SVHWrapper.h:134
SVHWrapper::m_connect_retry_count
int m_connect_retry_count
Definition: SVHWrapper.h:114
ros::NodeHandle
ros::Subscriber


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