PTUDriverMock.h
Go to the documentation of this file.
1 #ifndef PTUDRIVERMOCK_H
2 #define PTUDRIVERMOCK_H
3 #include "driver/PTUDriver.h"
4 
5 namespace asr_flir_ptu_driver {
6 
7 class PTUDriverMock : public PTUDriver{
8  public:
9  PTUDriverMock(const char* port, int baud, bool speed_control);
11 
12  bool isConnected();
13 
14  void virtual setSettings(int pan_base, int tilt_base,
15  int pan_speed, int tilt_speed,
16  int pan_upper, int tilt_upper,
17  int pan_accel, int tilt_accel,
18  int pan_hold, int tilt_hold,
19  int pan_move, int tilt_move);
20 
21  void virtual setLimitAngles(double pan_min, double pan_max, double tilt_min, double tilt_max);
22 
23  //dynamic settings
24  void virtual setAbsoluteAngleSpeeds(double pan_speed, double tilt_speed); //in deg/s
25 
31  void virtual setAbsoluteAngleSpeeds(signed short pan_speed, signed short tilt_speed); //in angle seconds
32  bool virtual setAbsoluteAngles(double pan_angle, double tilt_angle, bool no_forbidden_area_check); //in deg
33 
34  void virtual setSpeedControlMode(bool speed_control_mode);
35  bool virtual isInSpeedControlMode();
36 
37  double virtual getCurrentAngle(char type);
38  double virtual getDesiredAngle(char type);
39  double virtual getAngleSpeed(char type);
40 
41  bool virtual hasHalted();
42  bool virtual reachedGoal();
43  bool virtual hasHaltedAndReachedGoal();
44  bool virtual isWithinPanTiltLimits(double pan, double tilt);
45 
47 
54  std::vector<double> virtual determineLegitEndPoint(double end_point_pan_candidate, double end_point_tilt_candidate);
55 
56  bool virtual setValuesOutOfLimitsButWithinMarginToLimit(double * pan, double * tilt, double margin);
57  long virtual getLimitAngle(char pan_or_tilt, char upper_or_lower);
58 
59  private:
61  double pan_angle;
62  double tilt_angle;
63  double pan_speed;
64  double tilt_speed;
67  double pan_base;
68  double tilt_base;
71  double pan_max_limit;
72  double pan_min_limit;
75 
76  double pan_distance;
77  double tilt_distance;
78 };
79 
80 }
81 #endif // PTUDRIVERMOCK_H
virtual double getAngleSpeed(char type)
getAngleSpeed Method to get the current angle speed of an axisa (deg/s)
virtual bool hasHaltedAndReachedGoal()
hasHaltedAndReachedGoal Method to determine if the PTU has halted and reached its goal ...
virtual void setAbsoluteAngleSpeeds(double pan_speed, double tilt_speed)
setAbsoluteAngleSpeeds Method to set desired speed for pan/tilt movement absolute in deg/s ...
virtual void setSettings(int pan_base, int tilt_base, int pan_speed, int tilt_speed, int pan_upper, int tilt_upper, int pan_accel, int tilt_accel, int pan_hold, int tilt_hold, int pan_move, int tilt_move)
setSettings Method to configure various settings of the ptu
virtual void setSpeedControlMode(bool speed_control_mode)
setSpeedControlMode Method to set and disable pure speed control mode
PTUDriverMock(const char *port, int baud, bool speed_control)
bool isConnected()
isConnected Method to check if ptu is connected.
virtual bool isWithinPanTiltLimits(double pan, double tilt)
isWithinPanTiltLimits Method that checks if pan and tilt value are within the chosen pan and tilt lim...
virtual bool hasHalted()
hasHalted Method to determine if PTU movement has stopped
virtual bool setAbsoluteAngles(double pan_angle, double tilt_angle, bool no_forbidden_area_check)
setAbsoluteAngles Method to set pan and tilt angle for the PTU
virtual bool reachedGoal()
reachedGoal Method to determine if the PTU has reached its goal.
virtual double getDesiredAngle(char type)
getDesiredAngle Method to get the desired pan/tilt angle (where the ptu moves to) ...
virtual void setLimitAngles(double pan_min, double pan_max, double tilt_min, double tilt_max)
setSettings Method to configure limits for pan and tilt
virtual void setLimitAnglesToHardwareConstraints()
setLimitAnglesToHardwareConstraints Method that sets the pan and tilt limits to the maximum values th...
virtual bool setValuesOutOfLimitsButWithinMarginToLimit(double *pan, double *tilt, double margin)
setValuesOutOfLimitsButWithinMarginToLimit This method is used to set pan/tilt values that are slighl...
virtual long getLimitAngle(char pan_or_tilt, char upper_or_lower)
!!!!!!!!!Müssen nachfolgende public sein? Nach erstellen von mock überprüfen!!!!!!!!!!! ...
virtual bool isInSpeedControlMode()
isInSpeedControlMode Method to determine if ptu is in pure speed control mode
virtual double getCurrentAngle(char type)
getCurrentAngle Method to get the current pan/tilt angle
virtual std::vector< double > determineLegitEndPoint(double end_point_pan_candidate, double end_point_tilt_candidate)
determineLegitEndPoint DO NOT USE, NOT SUPPORTED IN MOCK


asr_flir_ptu_driver
Author(s): Valerij Wittenbeck, Joachim Gehrung, Pascal Meißner, Patrick Schlosser
autogenerated on Mon Dec 2 2019 03:15:17