SVHNode.h
Go to the documentation of this file.
00001 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
00002 
00003 
00004 // -- BEGIN LICENSE BLOCK ----------------------------------------------
00005 // This file is part of the SCHUNK SVH Driver suite.
00006 //
00007 // This program is free software licensed under the LGPL
00008 // (GNU LESSER GENERAL PUBLIC LICENSE Version 3).
00009 // You can find a copy of this license in LICENSE.txt in the top
00010 // directory of the source code.
00011 //
00012 // © Copyright 2014 SCHUNK Mobile Greifsysteme GmbH, Lauffen/Neckar Germany
00013 // © Copyright 2014 FZI Forschungszentrum Informatik, Karlsruhe, Germany
00014 //
00015 // -- END LICENSE BLOCK ------------------------------------------------
00016 
00017 //----------------------------------------------------------------------
00024 //----------------------------------------------------------------------
00025 
00026 #ifndef S5FH_NODE_H
00027 #define S5FH_NODE_H
00028 
00029 // Messages
00030 #include <std_msgs/Int8.h>
00031 #include <std_msgs/Empty.h>
00032 #include <sensor_msgs/JointState.h>
00033 #include "std_msgs/MultiArrayLayout.h"
00034 #include "std_msgs/MultiArrayDimension.h"
00035 #include "std_msgs/Float64MultiArray.h"
00036 
00037 // Dynamic reconfigure
00038 #include <dynamic_reconfigure/server.h>
00039 #include <schunk_svh_driver/svhConfig.h>
00040 
00041 // Driver Specific things
00042 #include <driver_svh/SVHFingerManager.h>
00043 #include <driver_svh/SVHPositionSettings.h>
00044 #include <driver_svh/SVHCurrentSettings.h>
00045 
00046 #include <boost/shared_ptr.hpp>
00047 
00048 class SVHNode{
00049 
00050 public:
00055   SVHNode(const ros::NodeHandle &nh);
00057   ~SVHNode();
00058 
00060   void dynamic_reconfigure_callback(svh_controller::svhConfig &config, uint32_t level);
00061 
00063   void connectCallback(const std_msgs::Empty&);
00064 
00066   void resetChannelCallback(const std_msgs::Int8ConstPtr& channel);
00067 
00069   void enableChannelCallback(const std_msgs::Int8ConstPtr& channel);
00070 
00072   void jointStateCallback(const sensor_msgs::JointStateConstPtr& input);
00073 
00078   sensor_msgs::JointState getChannelFeedback();
00079 
00084   std_msgs::Float64MultiArray getChannelCurrents();
00085 
00086 
00087 private:
00089   boost::shared_ptr<driver_svh::SVHFingerManager> fm_;
00090 
00092   std::string serial_device_name_;
00093 
00095   int connect_retry_count;
00096 
00098   std::string name_prefix;
00099 
00101   sensor_msgs::JointState channel_pos_;
00102 
00104   std_msgs::Float64MultiArray channel_currents;
00105 };
00106 
00107 #endif // S5FH_CONTROLLER_H


schunk_svh_driver
Author(s): Georg Heppner
autogenerated on Fri Apr 28 2017 02:31:08