generic_tactiles.hpp
Go to the documentation of this file.
00001 
00028 #ifndef GENERIC_TACTILES_HPP_
00029 #define GENERIC_TACTILES_HPP_
00030 
00031 #include <boost/smart_ptr.hpp>
00032 #include <sr_external_dependencies/types_for_external.h>
00033 extern "C"
00034 {
00035   #include <sr_external_dependencies/external/0220_palm_edc/0220_palm_edc_ethercat_protocol.h>
00036   #include <sr_external_dependencies/external/0230_palm_edc_TS/0230_palm_edc_ethercat_protocol.h>
00037   #include <sr_external_dependencies/external/0320_palm_edc_muscle/0320_palm_edc_ethercat_protocol.h>
00038 }
00039 
00040 #include <ros/ros.h>
00041 #include <vector>
00042 #include <std_srvs/Empty.h>
00043 
00044 #include <boost/smart_ptr.hpp>
00045 
00046 #include <diagnostic_msgs/DiagnosticStatus.h>
00047 #include <diagnostic_updater/DiagnosticStatusWrapper.h>
00048 
00049 #include <sr_hardware_interface/tactile_sensors.hpp>
00050 #include "sr_robot_lib/generic_updater.hpp"
00051 #include "sr_robot_lib/sensor_updater.hpp"
00052 
00053 namespace tactiles
00054 {
00055   template <class StatusType, class CommandType>
00056   class GenericTactiles
00057   {
00058   public:
00059     GenericTactiles(std::vector<generic_updater::UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state);
00060     ~GenericTactiles() {};
00061 
00069     virtual void update(StatusType* status_data);
00070 
00075     virtual void publish();
00076 
00081     virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
00082                                  diagnostic_updater::DiagnosticStatusWrapper &d);
00083 
00092     bool reset(std_srvs::Empty::Request& request,
00093                std_srvs::Empty::Response& response);
00094 
00096     static const unsigned int nb_tactiles;
00097 
00098     boost::shared_ptr<generic_updater::SensorUpdater<CommandType> > sensor_updater;
00100     boost::shared_ptr< std::vector<GenericTactileData> > tactiles_vector;
00101 
00102     virtual std::vector<AllTactileData>* get_tactile_data();
00103 
00104   protected:
00105 
00106     void process_received_data_type(int32u data);
00107 
00108     ros::NodeHandle nodehandle_;
00109 
00110     ros::ServiceServer reset_service_client_;
00111 
00113     std::vector<int32u> initialization_received_data_vector;
00114 
00125     std::string sanitise_string( const char* raw_string, const unsigned int str_size );
00126 
00127     boost::shared_ptr<std::vector<AllTactileData> > all_tactile_data;
00128   };//end class
00129 }//end namespace
00130 
00131 /* For the emacs weenies in the crowd.
00132 Local Variables:
00133    c-basic-offset: 2
00134 End:
00135 */
00136 
00137 #endif /* GENERIC_TACTILES_HPP_ */


sr_robot_lib
Author(s): Ugo Cupcic / ugo@shadowrobot.com , software@shadowrobot.com
autogenerated on Mon Oct 6 2014 07:37:50