1 #ifndef __PTU_FREE_INCLUDED__ 2 #define __PTU_FREE_INCLUDED__ 7 #include <boost/asio.hpp> 8 #include <boost/lexical_cast.hpp> 12 #define ERROR LONG_MIN 13 #define DISABLED ( LONG_MIN + 1 ) 14 #define ENABELED ( LONG_MIN + 2 ) 15 #define FACTORY_LIMITS_ENABLED ( LONG_MIN + 3 ) 16 #define USER_DEFINED_LIMITS_ENABLED ( LONG_MIN + 4 ) 17 #define LIMITS_DISABLED ( LONG_MIN + 5 ) 18 #define USER_DEFINED_PAN_LIMIT_ENABLED ( LONG_MIN + 6 ) 19 #define IMMEDIATE_POSITION_EXECUTION_MODE ( LONG_MIN + 7 ) 20 #define SLAVED_POSITION_EXECUTION_MODE ( LONG_MIN + 8 ) 21 #define HALT_PAN_ONLY ( LONG_MIN + 9 ) 22 #define HALT_TILT_ONLY ( LONG_MIN + 10 ) 23 #define HALT_BOTH ( LONG_MIN + 11 ) 24 #define INDEPENDENT_SPEED_MODE ( LONG_MIN + 12 ) 25 #define PURE_VELOCITY_CONTROL_MODE ( LONG_MIN + 13 ) 26 #define NO_RESET_MODE ( LONG_MIN + 14 ) 27 #define PAN_ONLY_RESET_MODE ( LONG_MIN + 15 ) 28 #define TILT_ONLY_RESET_MODE ( LONG_MIN + 16 ) 29 #define BOTH_RESET_MODE ( LONG_MIN + 17 ) 30 #define REGULAR_HOLD_POWER_MODE ( LONG_MIN + 18 ) 31 #define LOW_HOLD_POWER_MODE ( LONG_MIN + 19 ) 32 #define OFF_HOLD_POWER_MODE ( LONG_MIN + 20 ) 33 #define HIGH_MOVE_POWER_MODE ( LONG_MIN + 21 ) 34 #define REGULAR_MOVE_POWER_MODE ( LONG_MIN + 22 ) 35 #define LOW_MOVE_POWER_MODE ( LONG_MIN + 23 ) 37 #define ERROR_CODES_BELOW ( LONG_MIN + 24) 58 PTUFree(boost::asio::io_service& io);
432 bool halt(
long axis);
449 bool setPreset(
int preset_index,
short int pan,
short int tilt);
long getFactoryMaximumPanPositionLimit()
getFactoryMaximumPanPositionLimit Method to get the factory defined maximum pan position.
void test()
test Method to test the methods of this program, for DEBUG/DEVELOPMENT purpose, changes PTU settings ...
long getCurrentPanSpeed()
getCurrentPanSpeed Method that queries the current pan speed
bool setDesiredTiltUpperSpeedLimit(short int upper_speed_limit)
setDesiredTiltUpperSpeedLimit Method that sets the upper speed limit for tilt (position/second). WARNING: Takes extremly long or does not work on every ptu
bool setDesiredPanSpeedAbsolute(short int speed)
setDesiredPanSpeedAbsolute Method that sets absolute pan speed (position/second)
bool setDesiredTiltPositionRelative(short int position_offset)
setDesiredTiltPositionRelative Method that sets current tilt position by offset (current pos + offset...
long getUserMinimumTiltPositionLimit()
getUserMinimumTiltPositionLimit Method to get the user defined minimum tilt position. WARNING: Does not work on older PTUs and is not tested.
long getCurrentUsedMaximumTiltPositionLimit()
getCurrentUsedMaximumTiltPositionLimit Method to get the currently used maximum tilt position...
long getSpeedControlMode()
getSpeedControlMode Method to get the currently used sped control mode of the ptu.
long getDesiredTiltSpeed()
getDesiredTiltSpeed Method that queries the desired tilt speed
bool setResetMode(long mode)
setResetMode Method to set the reset mode of the ptu. Saved to EEPROM, do not use too often...
double getTiltResolution()
getTiltResolution Method that queries the tilt resolution (seconds/arc per position). Divide by 3600 to get Degree.
bool setDesiredTiltPositionAbsolute(short int position)
setDesiredTiltPositionAbsolute Method that sets absolute tilt position
bool setDesiredPanLowerSpeedLimit(short int lower_speed_limit)
setDesiredPanLowerSpeedLimit Method that sets the lower speed limit for pan (position/second). WARNING: Takes extremly long or does not work on every ptu
long getCurrentUsedMinimumPanPositionLimit()
getCurrentUsedMinimumPanPositionLimit Method to get the currently used minimum pan position...
std::string readPTUResponse()
readPTUResponse Method that reads from the PTU until delimitor (' ') appears. Then the read data is r...
long getFactoryMaximumTiltPositionLimit()
getFactoryMaximumTiltPositionLimit Method to get the factory defined maximum tilt position...
long getTiltAcceleartion()
getTiltAcceleartion Method that queries the tilt acceleration (no current or desired here) ...
long getPanInMotionPowerMode()
getPanInMotionPowerMode Method to get the move power mode for pan axis.
void closeSerialConnection()
closeSerialConnection Closes currently used serial port
bool isOpen()
isOpen Method to determine if used port is open or closed.
long getCurrentTiltSpeed()
getCurrentTiltSpeed Method that queries the current tilt speed
bool setTiltBaseSpeed(short int base_speed)
setTiltBaseSpeed Method that sets the base speed for tilt (position/second)
long getTiltUpperSpeedLimit()
getTiltUpperSpeedLimit Method that queries the tilt upper speed limit WARNING: This Method consumes e...
long getUserMaximumTiltPositionLimit()
getUserMaximumTiltPositionLimit Method to get the user defined maximum tilt position. WARNING: Does not work on older PTUs and is not tested.
std::string getErrorString(boost::system::error_code error)
long getCurrentUsedMinimumTiltPositionLimit()
getCurrentUsedMinimumTiltPositionLimit Method to get the currently used minimum tilt position...
long getDesiredPanSpeed()
getDesiredPanSpeed Method that queries the desired pan speed
long getUserMaximumPanPositionLimit()
getUserMaximumPanPositionLimit Method to get the user defined maximum pan position. WARNING: Does not work on older PTUs and is not tested.
bool setDesiredPanUpperSpeedLimit(short int upper_speed_limit)
setDesiredPanUpperSpeedLimit Method that sets the upper speed limit for pan (position/second). WARNING: Takes extremly long or does not work on every ptu
bool setNewSerialConnection(std::string port, int baud)
setNewSerialConnection Establishes a new connection via serial port specified by 'port' to a target d...
bool setPanStationaryPowerMode(long mode)
setPanStationaryPowerMode Method to set the stationary power mode for pan axis.
PTUFree()
PTUFree Constructor for PTUFree object. Not connected to any port.
long getTiltStationaryPowerMode()
getTiltStationaryPowerMode Method to get the stationary power mode for tilt axis. ...
bool setDesiredPanAccelerationAbsolute(short int acceleration)
setDesiredPanAccelerationAbsolute Method that sets the absolute pan acceleration (position/second^2) ...
long getFactoryMinimumTiltPositionLimit()
getFactoryMinimumTiltPositionLimit Method to get the factory defined minimum tilt position...
long getPositionLimitEnforcementMode()
getPositionLimitEnforcementMode Method to get the currently used position limit enforcement mode...
bool setMaximumPanPositionLimit(short int position)
setMaximumPanPositionLimit Method that is used to set a user defined maximum pan position limit...
std::vector< std::string > evaluateResponse(std::string response)
evaluateResponse Method that preprocesses the answer of the PTU. Splits the PTU to a maximum of 3 par...
std::string communicate(std::string request)
communicate Method to send a command 'request' to the serial port (and the device) and recieve the an...
bool clearPreset()
clearPreset Method to delete all existing presets. WARNING: Does not work on older PTUs and is not te...
bool setDesiredTiltSpeedRelative(short int speed_offset)
setDesiredTiltSpeedRelative Method that sets the desired tilt speed relative to the CURRENT (not the ...
bool setDesiredTiltAccelerationAbsolute(short int acceleration)
setDesiredTiltAccelerationAbsolute Method that sets the absolute tilt acceleration (position/second^2...
bool setPreset(int preset_index, short int pan, short int tilt)
setPreset Method that allows to associate a pan and tilt position with a preset index. Moves to the pan and tilt position and saves the position as a preset. WARNING: Does not work on older PTUs and is not tested.
bool setDesiredPanPositionRelative(short int position_offset)
setDesiredPanPositionRelative Method that sets current pan position by offset (current pos + offset =...
bool setPanBaseSpeed(short int base_speed)
setPanBaseSpeed Method that sets the base speed for pan (position/second)
bool setPositionExecutionMode(long mode)
setPositionExecutionMode Method to set the position execution mode.
long getTiltInMotionPowerMode()
getTiltInMotionPowerMode Method to get the move power mode for tilt axis.
long getPanLowerSpeedLimit()
getPanLowerSpeedLimit Method that queries the pan lower speed limit. WARNING: This Method consumes ei...
bool setSpeedControlMode(long mode)
setSpeedControlMode Method to set the sped control mode of the ptu.
long getPanAcceleartion()
getPanAcceleartion Method that queries the pan acceleration (no current or desired here) ...
bool setMinimumPanPositionLimit(short int position)
setMinimumPanPositionLimit Method that is used to set a user defined minimum pan position limit...
bool gotoPreset(int preset_index)
gotoPreset Method that moves the ptu to a existing preset of pan and tilt corrdiantes. WARNING: Does not work on older PTUs and is not tested.
long getPanUpperSpeedLimit()
getPanUpperSpeedLimit Method that queries the pan upper speed limit WARNING: This Method consumes eit...
long position_execution_mode
long getTiltBaseSpeed()
getTiltBaseSpeed Returns the current tilt base speed
long getDesiredPanPosition()
getDesiredPanPosition Method that queries the desired pan position
boost::asio::io_service timer_io_service
long getCurrentPanPosition()
getCurrentPanPosition Method that queries the current pan position
bool setDesiredPanSpeedRelative(short int speed_offset)
setDesiredPanSpeedRelative Method that sets the desired pan speed relative to the CURRENT (not the de...
bool halt(long axis)
halt Method that halts movement on specified axis.
bool restoreFactoryDefault()
restoreFactoryDefault Method to set default settings to factory defaults. Saved to EEPROM...
double getPanResolution()
getPanResolution Method that queries the pan resolution (seconds/arc per position). Divide by 3600 to get Degree.
long getPanBaseSpeed()
getPanBaseSpeed Returns the current pan base speed
bool awaitPositionCommandCompletion()
awaitPositionCommandCompletion Method to wait for the completion of the last issued pan and tilt posi...
bool restoreDefault()
restoreDefault Method to restore default settings. WARNING: Not tested.
long getPanStationaryPowerMode()
getPanStationaryPowerMode Method to get the stationary power mode for pan axis.
long getTiltLowerSpeedLimit()
getTiltLowerSpeedLimit Method that queries the tilt lower speed limit. WARNING: This Method consumes ...
bool setDesiredPanTiltPositionAbsoluteSlaved(short int pan, short int tilt)
setDesiredPanTiltPositionAbsoluteSlaved Method that allows a movement of pan and tilt axis to specifi...
long getFactoryMinimumPanPositionLimit()
getFactoryMinimumPanPositionLimit Method to get the factory defined minimum pan position.
bool setBaudRate(int baud)
setBaudRate Sets the baud rate for the serial port that is used. Only use of serial connection is est...
long getCurrentUsedMaximumPanPositionLimit()
getCurrentUsedMaximumPanPositionLimit Method to get the currently used maximum pan position...
bool setMinimumTiltPositionLimit(short int position)
setMinimumTiltPositionLimit Method that is used to set a user defined minimum tilt position limit...
boost::asio::io_service ptu_io_service
bool setPositionLimitEnforcementMode(long enable)
setPositionLimitEnforcementMode Method to set the position limit enforcement mode. Warning: USER_DEFINED_LIMITS_ENABLED does not work on older PTUs and setting of this value is not tested.
bool setDesiredPanPositionAbsolute(short int position)
setDesiredPanPositionAbsolute Method that sets absolute pan position
bool saveDefault()
saveDefault Method to save the current axis settings as default at power up. Note: This class sets th...
bool setDesiredTiltLowerSpeedLimit(short int lower_speed_limit)
setDesiredTiltLowerSpeedLimit Method that sets the lower speed limit for tilt (position/second). WARNING: Takes extremly long or does not work on every ptu
boost::asio::serial_port ptu_port
bool setTiltStationaryPowerMode(long mode)
setTiltStationaryPowerMode Method to set the stationary power mode for tilt axis. ...
bool setMaximumTiltPositionLimit(short int position)
setMaximumTiltPositionLimit Method that is used to set a user defined maximum tilt position limit...
bool setTiltInMotionPowerMode(long mode)
setTiltInMotionPowerMode Method to set the move power mode for tilt axis.
bool reset()
reset Method to reset the ptu (pan and/or tilt axis depending on reset mode)
long getCurrentTiltPosition()
getCurrentTiltPosition Method that queries the current tilt position
long getUserMinimumPanPositionLimit()
getUserMinimumPanPositionLimit Method to get the user defined minimum pan position. WARNING: Does not work on older PTUs and is not tested.
bool setDesiredTiltSpeedAbsolute(short int speed)
setDesiredTiltSpeedAbsolute Method that sets absolute tilt speed (position/second) ...
bool setPanInMotionPowerMode(long mode)
setPanInMotionPowerMode Method to set the move power mode for pan axis.
long getDesiredTiltPosition()
getDesiredTiltPosition Method that queries the desired tilt position
long getPositionExecutionMode()
getPositionExecutionMode Method to get the currently used position execution mode. Can return IMMEDIATE_POSITION_EXECUTION_MODE or SLAVED_POSITION_EXECUTION_MODE.