SVHNode.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2 
3 
4 // -- BEGIN LICENSE BLOCK ----------------------------------------------
5 // This file is part of the SCHUNK SVH Driver suite.
6 //
7 // This program is free software licensed under the LGPL
8 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
9 // You can find a copy of this license in LICENSE.txt in the top
10 // directory of the source code.
11 //
12 // © Copyright 2014 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
13 // © Copyright 2014 FZI Forschungszentrum Informatik, Karlsruhe, Germany
14 //
15 // -- END LICENSE BLOCK ------------------------------------------------
16 
17 //----------------------------------------------------------------------
24 //----------------------------------------------------------------------
25 
26 #ifndef S5FH_NODE_H
27 #define S5FH_NODE_H
28 
29 // Messages
30 #include <std_msgs/Int8.h>
31 #include <std_msgs/Empty.h>
32 #include <sensor_msgs/JointState.h>
33 #include "std_msgs/MultiArrayLayout.h"
34 #include "std_msgs/MultiArrayDimension.h"
35 #include "std_msgs/Float64MultiArray.h"
36 
37 // Dynamic reconfigure
38 #include <dynamic_reconfigure/server.h>
39 #include <schunk_svh_driver/svhConfig.h>
40 
41 // Driver Specific things
45 
46 #include <boost/shared_ptr.hpp>
47 
48 class SVHNode{
49 
50 public:
55  SVHNode(const ros::NodeHandle &nh);
57  ~SVHNode();
58 
60  void dynamic_reconfigure_callback(svh_controller::svhConfig &config, uint32_t level);
61 
63  void connectCallback(const std_msgs::Empty&);
64 
66  void resetChannelCallback(const std_msgs::Int8ConstPtr& channel);
67 
69  void enableChannelCallback(const std_msgs::Int8ConstPtr& channel);
70 
72  void jointStateCallback(const sensor_msgs::JointStateConstPtr& input);
73 
78  sensor_msgs::JointState getChannelFeedback();
79 
84  std_msgs::Float64MultiArray getChannelCurrents();
85 
86 
87 private:
90 
92  std::string serial_device_name_;
93 
96 
98  std::string name_prefix;
99 
101  sensor_msgs::JointState channel_pos_;
102 
104  std_msgs::Float64MultiArray channel_currents;
105 };
106 
107 #endif // S5FH_CONTROLLER_H
std_msgs::Float64MultiArray getChannelCurrents()
getChannelCurrents Returns the current values of the channels as raw output
Definition: SVHNode.cpp:366
SVHNode(const ros::NodeHandle &nh)
SVHNode constructs a new node object that handles most of the functionality.
Definition: SVHNode.cpp:39
unsigned int uint32_t
std::string serial_device_name_
Serial device to use for communication with hardware.
Definition: SVHNode.h:92
void enableChannelCallback(const std_msgs::Int8ConstPtr &channel)
Callback function to enable channels of SCHUNK five finger hand.
Definition: SVHNode.cpp:262
config
void jointStateCallback(const sensor_msgs::JointStateConstPtr &input)
Callback function for setting channel target positions to SCHUNK five finger hand.
Definition: SVHNode.cpp:268
void dynamic_reconfigure_callback(svh_controller::svhConfig &config, uint32_t level)
Dynamic reconfigure callback to update changing parameters.
Definition: SVHNode.cpp:220
void resetChannelCallback(const std_msgs::Int8ConstPtr &channel)
Callback function to reset/home channels of SCHUNK five finger hand.
Definition: SVHNode.cpp:246
std_msgs::Float64MultiArray channel_currents
Current Value message template.
Definition: SVHNode.h:104
std::string name_prefix
Prefix for the driver to identify joint names if the Driver should expext "left_hand_Pinky" than the ...
Definition: SVHNode.h:98
int connect_retry_count
Number of times the connect routine tries to connect in case that we receive at least one package...
Definition: SVHNode.h:95
sensor_msgs::JointState getChannelFeedback()
SVHNode::getChannelFeedback Gets the latest received positions and efforts from the driver...
Definition: SVHNode.cpp:341
sensor_msgs::JointState channel_pos_
joint state message template
Definition: SVHNode.h:101
void connectCallback(const std_msgs::Empty &)
Callback function for connecting to SCHUNK five finger hand.
Definition: SVHNode.cpp:229
boost::shared_ptr< driver_svh::SVHFingerManager > fm_
Handle to the SVH finger manager for library access.
Definition: SVHNode.h:89
~SVHNode()
Default DTOR.
Definition: SVHNode.cpp:213


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