PTUFree.h
Go to the documentation of this file.
00001 #ifndef __PTU_FREE_INCLUDED__
00002 #define __PTU_FREE_INCLUDED__
00003 //#include <serial/serial.h>
00004 //#include "ros/ros.h"
00005 //#include <boost/asio/io_service.hpp>
00006 //#include <boost/asio/serial_port.hpp>
00007 #include <boost/asio.hpp>
00008 #include <boost/lexical_cast.hpp>
00009 #include <vector>
00010 #include "limits.h"
00011 
00012 #define ERROR LONG_MIN
00013 #define DISABLED ( LONG_MIN + 1 )
00014 #define ENABELED ( LONG_MIN + 2 )
00015 #define FACTORY_LIMITS_ENABLED ( LONG_MIN + 3 )
00016 #define USER_DEFINED_LIMITS_ENABLED ( LONG_MIN + 4 )
00017 #define LIMITS_DISABLED ( LONG_MIN + 5 )
00018 #define USER_DEFINED_PAN_LIMIT_ENABLED ( LONG_MIN + 6 )
00019 #define IMMEDIATE_POSITION_EXECUTION_MODE ( LONG_MIN + 7 )
00020 #define SLAVED_POSITION_EXECUTION_MODE ( LONG_MIN + 8 )
00021 #define HALT_PAN_ONLY ( LONG_MIN + 9 )
00022 #define HALT_TILT_ONLY ( LONG_MIN + 10 )
00023 #define HALT_BOTH ( LONG_MIN + 11 )
00024 #define INDEPENDENT_SPEED_MODE ( LONG_MIN + 12 )
00025 #define PURE_VELOCITY_CONTROL_MODE ( LONG_MIN + 13 )
00026 #define NO_RESET_MODE ( LONG_MIN + 14 )
00027 #define PAN_ONLY_RESET_MODE ( LONG_MIN + 15 )
00028 #define TILT_ONLY_RESET_MODE ( LONG_MIN + 16 )
00029 #define BOTH_RESET_MODE ( LONG_MIN + 17 )
00030 #define REGULAR_HOLD_POWER_MODE ( LONG_MIN + 18 )
00031 #define LOW_HOLD_POWER_MODE ( LONG_MIN + 19 )
00032 #define OFF_HOLD_POWER_MODE ( LONG_MIN + 20 )
00033 #define HIGH_MOVE_POWER_MODE ( LONG_MIN + 21 )
00034 #define REGULAR_MOVE_POWER_MODE ( LONG_MIN + 22 )
00035 #define LOW_MOVE_POWER_MODE ( LONG_MIN + 23 )
00036 
00037 #define ERROR_CODES_BELOW ( LONG_MIN + 24)
00038 
00039 
00040 
00041 
00042 namespace ptu_free {
00046     class PTUFree {
00047         public:
00048 
00052             PTUFree();
00053 
00058             PTUFree(boost::asio::io_service& io);
00059 
00065             bool setBaudRate(int baud);
00066 
00073             bool setNewSerialConnection(std::string port, int baud);
00074 
00078             void closeSerialConnection();
00079 
00085             std::string communicate(std::string request);
00086 
00091             std::string readPTUResponse();
00092 
00100             std::vector<std::string> evaluateResponse(std::string response);
00101 
00107             bool setDesiredPanPositionAbsolute(short int position);
00108 
00114             bool setDesiredPanPositionRelative(short int position_offset);
00115 
00121             bool setDesiredPanSpeedAbsolute(short int speed);
00122 
00128             bool setDesiredPanSpeedRelative(short int speed_offset);
00134             bool setDesiredPanAccelerationAbsolute(short int acceleration);
00140             bool setDesiredPanUpperSpeedLimit(short int upper_speed_limit);
00146             bool setDesiredPanLowerSpeedLimit(short int lower_speed_limit);
00152             bool setPanBaseSpeed(short int base_speed);
00157             long getCurrentPanPosition();
00162             long getCurrentPanSpeed();
00167             long getPanUpperSpeedLimit();
00172             long getPanLowerSpeedLimit();
00177             double getPanResolution();
00182             long getDesiredPanPosition();
00187             long getDesiredPanSpeed();
00192             long getPanAcceleartion();
00197             long getPanBaseSpeed();
00203             bool setDesiredTiltPositionAbsolute(short int position);
00204 
00210             bool setDesiredTiltPositionRelative(short int position_offset);
00211 
00217             bool setDesiredTiltSpeedAbsolute(short int speed);
00218 
00224             bool setDesiredTiltSpeedRelative(short int speed_offset);
00230             bool setDesiredTiltAccelerationAbsolute(short int acceleration);
00236             bool setDesiredTiltUpperSpeedLimit(short int upper_speed_limit);
00242             bool setDesiredTiltLowerSpeedLimit(short int lower_speed_limit);
00248             bool setTiltBaseSpeed(short int base_speed);
00253             long getCurrentTiltPosition();
00258             long getCurrentTiltSpeed();
00263             long getTiltUpperSpeedLimit();
00268             long getTiltLowerSpeedLimit();
00273             double getTiltResolution();
00278             long getDesiredTiltPosition();
00283             long getDesiredTiltSpeed();
00288             long getTiltAcceleartion();
00293             long getTiltBaseSpeed();
00294 
00300             bool setPositionLimitEnforcementMode(long enable);
00301 
00307             bool setMinimumPanPositionLimit(short int position);
00308 
00314             bool setMaximumPanPositionLimit(short int position);
00315 
00321             bool setMinimumTiltPositionLimit(short int position);
00322 
00328             bool setMaximumTiltPositionLimit(short int position);
00329 
00334             long getUserMinimumPanPositionLimit();
00335 
00340             long getUserMaximumPanPositionLimit();
00341 
00346             long getUserMinimumTiltPositionLimit();
00347 
00352             long getUserMaximumTiltPositionLimit();
00353 
00358             long getFactoryMinimumPanPositionLimit();
00359 
00364             long getFactoryMaximumPanPositionLimit();
00365 
00370             long getFactoryMinimumTiltPositionLimit();
00371 
00376             long getFactoryMaximumTiltPositionLimit();
00377 
00382             long getCurrentUsedMinimumPanPositionLimit();
00383 
00388             long getCurrentUsedMaximumPanPositionLimit();
00389 
00394             long getCurrentUsedMinimumTiltPositionLimit();
00395 
00400             long getCurrentUsedMaximumTiltPositionLimit();
00401 
00406             long getPositionLimitEnforcementMode();
00407 
00413             bool setPositionExecutionMode(long mode);
00414 
00419             long getPositionExecutionMode();
00420 
00425             bool awaitPositionCommandCompletion();
00426 
00432             bool halt(long axis);
00433 
00440             bool setDesiredPanTiltPositionAbsoluteSlaved(short int pan, short int tilt);
00441 
00449             bool setPreset(int preset_index, short int pan, short int tilt);
00450 
00456             bool setPreset(int preset_index);
00457 
00463             bool gotoPreset(int preset_index);
00464 
00469             bool clearPreset();
00470 
00476             bool setSpeedControlMode(long mode);
00477 
00482             long getSpeedControlMode();
00483 
00488             bool reset();
00489 
00495             bool setResetMode(long mode);
00496 
00502             bool saveDefault();
00503 
00508             bool restoreDefault();
00509 
00514             bool restoreFactoryDefault();
00515 
00521             bool setPanStationaryPowerMode(long mode);
00522 
00528             bool setTiltStationaryPowerMode(long mode);
00529 
00534             long getPanStationaryPowerMode();
00535 
00540             long getTiltStationaryPowerMode();
00541 
00547             bool setPanInMotionPowerMode(long mode);
00548 
00554             bool setTiltInMotionPowerMode(long mode);
00555 
00560             long getPanInMotionPowerMode();
00561 
00566             long getTiltInMotionPowerMode();
00567 
00571             void test();
00572 
00577             bool isOpen();
00578 
00579         private:
00580             boost::asio::io_service ptu_io_service;
00581             boost::asio::io_service timer_io_service;
00582             boost::asio::serial_port ptu_port;
00583             bool timeout_occured;
00584             long factory_pan_min;
00585             long factory_pan_max;
00586             long factory_tilt_min;
00587             long factory_tilt_max;
00588             long position_execution_mode;
00589             std::string getErrorString(boost::system::error_code error);
00590         };
00591 }
00592 #endif


asr_flir_ptu_driver
Author(s): Valerij Wittenbeck, Joachim Gehrung, Pascal Meißner, Patrick Schlosser
autogenerated on Thu Jun 6 2019 21:16:45