Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00029
00030 #ifndef DRIVER_SVH_SVH_FINGER_MANAGER_H_INCLUDED
00031 #define DRIVER_SVH_SVH_FINGER_MANAGER_H_INCLUDED
00032
00033 #include <driver_svh/ImportExport.h>
00034 #include <driver_svh/SVHController.h>
00035 #include <driver_svh/SVHFeedbackPollingThread.h>
00036 #include <driver_svh/SVHPositionSettings.h>
00037 #include <driver_svh/SVHCurrentSettings.h>
00038 #include <driver_svh/SVHHomeSettings.h>
00039
00040 #include <boost/shared_ptr.hpp>
00041
00042
00043 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
00044 #include <icl_comm_websocket/WsBroadcaster.h>
00045 #else
00046
00047
00048
00049
00050 namespace icl_comm{
00051 namespace websocket{
00052 class WsBroadcaster;
00053 }}
00054 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
00055
00056
00057
00058
00059 namespace driver_svh {
00060
00063 class DRIVER_SVH_IMPORT_EXPORT SVHFingerManager
00064 {
00065 public:
00066
00070 enum MovementState
00071 {
00072 eST_DEACTIVATED,
00073 eST_RESETTING,
00074 eST_RESETTED,
00075 eST_ENABLED,
00076 eST_PARTIALLY_ENABLED,
00077 eST_FAULT,
00078 eST_DIMENSION
00079 };
00080
00084 enum Hints
00085 {
00086 eHT_DEVICE_NOT_FOUND,
00087 eHT_CONNECTION_FAILED,
00088 eHT_NOT_RESETTED,
00089 eHT_NOT_CONNECTED,
00090 eHT_RESET_FAILED,
00091 eHT_CHANNEL_SWITCHED_OF,
00092 eHT_DANGEROUS_CURRENTS,
00093 eHT_DIMENSION
00094 };
00095
00100 SVHFingerManager(const std::vector<bool> &disable_mask = std::vector<bool>(9,false), const uint32_t &reset_timeout = 5);
00101
00102 virtual ~SVHFingerManager();
00103
00110 bool connect(const std::string &dev_name = "/dev/ttyUSB0",const unsigned int &_retry_count = 3);
00111
00115 void disconnect();
00116
00121 bool isConnected() { return m_connected; }
00122
00128 bool resetChannel(const SVHChannel &channel);
00129
00135 bool enableChannel(const SVHChannel &channel);
00136
00141 void disableChannel(const SVHChannel &channel);
00142
00147 bool requestControllerFeedbackAllChannels();
00148
00154 bool requestControllerFeedback(const SVHChannel &channel);
00155
00162 bool getPosition(const SVHChannel &channel, double &position);
00163
00170 bool getCurrent(const SVHChannel &channel, double ¤t);
00171
00172
00178 bool setAllTargetPositions(const std::vector<double>& positions);
00179
00187 bool setTargetPosition(const SVHChannel &channel, double position, double current);
00188
00194 bool isEnabled(const SVHChannel &channel);
00195
00201 bool isHomed(const SVHChannel &channel);
00202
00208 void setMovementState(const MovementState &state);
00209
00210
00213 void requestControllerState();
00214
00221 bool getCurrentSettings(const SVHChannel &channel, SVHCurrentSettings ¤t_settings);
00222
00229 bool getPositionSettings(const SVHChannel &channel, SVHPositionSettings &position_settings);
00230
00231
00238 bool setCurrentSettings(const SVHChannel &channel, const SVHCurrentSettings ¤t_settings);
00239
00246 bool setPositionSettings(const SVHChannel &channel, const SVHPositionSettings &position_settings);
00247
00254 bool setHomeSettings(const SVHChannel &channel,const SVHHomeSettings& home_settings);
00255
00256
00257
00258
00259
00261 std::vector<SVHCurrentSettings> getDefaultCurrentSettings();
00262
00265 std::vector<SVHPositionSettings> getDefaultPositionSettings(const bool& reset = false);
00266
00268 void setDefaultHomeSettings();
00269
00274 void setResetSpeed(const float& speed);
00275
00280 void setResetTimeout(const int& resetTimeout);
00281
00286 SVHFirmwareInfo getFirmwareInfo();
00287
00288
00289 #ifdef _IC_BUILDER_ICL_COMM_WEBSOCKET_
00290
00296 void updateWebSocket();
00297
00302 void receivedHintMessage(const int &hint);
00303
00304 #endif // _IC_BUILDER_ICL_COMM_WEBSOCKET_
00305
00306
00307
00308
00309
00310 private:
00311
00313 boost::shared_ptr<icl_comm::websocket::WsBroadcaster> m_ws_broadcaster;
00314
00316 SVHController *m_controller;
00317
00319 SVHFeedbackPollingThread *m_feedback_thread;
00320
00322 bool m_connected;
00323
00325 bool m_connection_feedback_given;
00326
00328 int8_t m_homing_timeout;
00329
00331 std::vector<double> m_ticks2rad;
00332
00334 std::vector<int32_t> m_position_min;
00335
00337 std::vector<int32_t> m_position_max;
00338
00340 std::vector<int32_t> m_position_home;
00341
00343 std::vector<bool> m_is_homed;
00344
00346 std::vector<bool> m_is_switched_off;
00347
00349 MovementState m_movement_state;
00350
00352 float m_reset_speed_factor;
00353
00355 uint32_t m_reset_timeout;
00356
00358 std::vector<SVHCurrentSettings> m_current_settings;
00360 std::vector<bool> m_current_settings_given;
00361
00363 std::vector<SVHPositionSettings> m_position_settings;
00365 std::vector<bool> m_position_settings_given;
00366
00368 std::vector<SVHHomeSettings> m_home_settings;
00369
00373 std::string m_serial_device;
00374
00376 std::vector<SVHChannel> m_reset_order;
00377
00384 std::vector<double> m_reset_current_factor;
00385
00392 int32_t convertRad2Ticks(const SVHChannel &channel,const double &position);
00393
00400 double convertTicks2Rad(const SVHChannel &channel, const int32_t &ticks);
00401
00408 bool isInsideBounds(const SVHChannel &channel, const int32_t &target_position);
00409
00416 bool currentSettingsAreSafe(const SVHChannel &channel,const SVHCurrentSettings ¤t_settings);
00417
00418
00419 SVHControllerFeedback debug_feedback;
00420
00421
00422 };
00423
00424 }
00425
00426 #endif