PTUDriverMock.h
Go to the documentation of this file.
00001 #ifndef PTUDRIVERMOCK_H
00002 #define PTUDRIVERMOCK_H
00003 #include "driver/PTUDriver.h"
00004 
00005 namespace asr_flir_ptu_driver {
00006 
00007 class PTUDriverMock : public PTUDriver{
00008     public:
00009         PTUDriverMock(const char* port, int baud, bool speed_control);
00010         ~PTUDriverMock();
00011 
00012         bool isConnected();
00013 
00014         void virtual setSettings(int pan_base, int tilt_base,
00015                                  int pan_speed, int tilt_speed,
00016                                  int pan_upper, int tilt_upper,
00017                                  int pan_accel, int tilt_accel,
00018                                  int pan_hold, int tilt_hold,
00019                                  int pan_move, int tilt_move);
00020 
00021         void virtual setLimitAngles(double pan_min, double pan_max, double tilt_min, double tilt_max);
00022 
00023         //dynamic settings
00024         void virtual setAbsoluteAngleSpeeds(double pan_speed, double tilt_speed); //in deg/s
00025 
00031         void virtual setAbsoluteAngleSpeeds(signed short pan_speed, signed short tilt_speed); //in angle seconds
00032         bool virtual setAbsoluteAngles(double pan_angle, double tilt_angle, bool no_forbidden_area_check); //in deg
00033 
00034         void virtual setSpeedControlMode(bool speed_control_mode);
00035         bool virtual isInSpeedControlMode();
00036 
00037         double virtual getCurrentAngle(char type);
00038         double virtual getDesiredAngle(char type);
00039         double virtual getAngleSpeed(char type);
00040 
00041         bool virtual hasHalted();
00042         bool virtual reachedGoal();
00043         bool virtual hasHaltedAndReachedGoal();
00044         bool virtual isWithinPanTiltLimits(double pan, double tilt);
00045 
00046         void virtual setLimitAnglesToHardwareConstraints();
00047 
00054         std::vector<double> virtual determineLegitEndPoint(double end_point_pan_candidate, double end_point_tilt_candidate);
00055 
00056         bool virtual setValuesOutOfLimitsButWithinMarginToLimit(double * pan, double * tilt, double margin);
00057         long virtual getLimitAngle(char pan_or_tilt, char upper_or_lower);
00058 
00059    private:
00060         int is_stopped_count;
00061         double pan_angle;
00062         double tilt_angle;
00063         double pan_speed;
00064         double tilt_speed;
00065         double current_pan_speed;
00066         double current_tilt_speed;
00067         double pan_base;
00068         double tilt_base;
00069         double pan_acceleration;
00070         double tilt_acceleration;
00071         double pan_max_limit;
00072         double pan_min_limit;
00073         double tilt_max_limit;
00074         double tilt_min_limit;
00075 
00076         double pan_distance;
00077         double tilt_distance;
00078 };
00079 
00080 }
00081 #endif // PTUDRIVERMOCK_H


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