Go to the documentation of this file.
32 #ifndef S5FH_WRAPPER_H_INCLUDED
33 #define S5FH_WRAPPER_H_INCLUDED
37 #include <sensor_msgs/JointState.h>
38 #include <std_msgs/Empty.h>
39 #include <std_msgs/Float64MultiArray.h>
40 #include <std_msgs/Int8.h>
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>
70 const uint16_t manual_minor_version);
99 bool homeAllNodes(schunk_svh_msgs::HomeAllRequest& req, schunk_svh_msgs::HomeAllResponse& resp);
102 schunk_svh_msgs::HomeWithChannelsResponse& resp);
105 schunk_svh_msgs::SetAllChannelForceLimits::Response& res);
107 schunk_svh_msgs::SetChannelForceLimit::Response& res);
137 #endif // #ifdef S5FH_WRAPPER_H_INCLUDED
ros::ServiceServer m_setAllForceLimits_srv
std::shared_ptr< SVHDiagnostics > m_svh_diagnostics
Handle to the diagnostics test class creating a test protocol with the web gui package.
int m_firmware_major_version
bool m_channels_enabled
m_channels_enabled enables the ros-control-loop in the hw interface
ros::Subscriber enable_sub
void enableChannelCallback(const std_msgs::Int8ConstPtr &channel)
Callback function to enable channels of SCHUNK five finger hand.
ros::NodeHandle m_priv_nh
private node handle
ros::ServiceServer m_home_service_joint_names
std::shared_ptr< driver_svh::SVHFingerManager > m_finger_manager
Handle to the SVH finger manager for library access.
ros::ServiceServer m_home_service_all
void connectCallback(const std_msgs::Empty &)
Callback function for connecting to SCHUNK five finger hand.
bool homeNodesChannelIds(schunk_svh_msgs::HomeWithChannelsRequest &req, schunk_svh_msgs::HomeWithChannelsResponse &resp)
std::string m_name_prefix
float setChannelForceLimit(size_t channel, float force_limit)
bool setAllForceLimits(schunk_svh_msgs::SetAllChannelForceLimits::Request &req, schunk_svh_msgs::SetAllChannelForceLimits::Response &res)
bool homeAllNodes(schunk_svh_msgs::HomeAllRequest &req, schunk_svh_msgs::HomeAllResponse &resp)
bool setForceLimitById(schunk_svh_msgs::SetChannelForceLimit::Request &req, schunk_svh_msgs::SetChannelForceLimit::Response &res)
void setRosControlEnable(bool enable)
function to set the ros-control-loop enabling flag from the diagnostics class
void initControllerParameters(const uint16_t manual_major_version, const uint16_t manual_minor_version)
std::string m_serial_device_name
Serial device to use for communication with hardware.
std::shared_ptr< driver_svh::SVHFingerManager > getFingerManager() const
std::string getNamePrefix() const
bool connect()
load parameters and try connecting
ros::Subscriber connect_sub
int m_firmware_minor_version
void resetChannelCallback(const std_msgs::Int8ConstPtr &channel)
Callback function to reset/home channels of SCHUNK five finger hand.
SVHWrapper(const ros::NodeHandle &nh)
ros::ServiceServer m_setForceLimitById_srv
int m_connect_retry_count
schunk_svh_driver
Author(s): Georg Heppner
, Felix Exner , Pascal Becker , Johannes Mangler
autogenerated on Sat Apr 15 2023 02:24:55