#include <PTUDriverMock.h>
Public Member Functions | |
virtual std::vector< double > | determineLegitEndPoint (double end_point_pan_candidate, double end_point_tilt_candidate) |
determineLegitEndPoint DO NOT USE, NOT SUPPORTED IN MOCK More... | |
virtual double | getAngleSpeed (char type) |
getAngleSpeed Method to get the current angle speed of an axisa (deg/s) More... | |
virtual double | getCurrentAngle (char type) |
getCurrentAngle Method to get the current pan/tilt angle More... | |
virtual double | getDesiredAngle (char type) |
getDesiredAngle Method to get the desired pan/tilt angle (where the ptu moves to) More... | |
virtual long | getLimitAngle (char pan_or_tilt, char upper_or_lower) |
!!!!!!!!!Müssen nachfolgende public sein? Nach erstellen von mock überprüfen!!!!!!!!!!! More... | |
virtual bool | hasHalted () |
hasHalted Method to determine if PTU movement has stopped More... | |
virtual bool | hasHaltedAndReachedGoal () |
hasHaltedAndReachedGoal Method to determine if the PTU has halted and reached its goal More... | |
bool | isConnected () |
isConnected Method to check if ptu is connected. More... | |
virtual bool | isInSpeedControlMode () |
isInSpeedControlMode Method to determine if ptu is in pure speed control mode More... | |
virtual bool | isWithinPanTiltLimits (double pan, double tilt) |
isWithinPanTiltLimits Method that checks if pan and tilt value are within the chosen pan and tilt limits More... | |
PTUDriverMock (const char *port, int baud, bool speed_control) | |
virtual bool | reachedGoal () |
reachedGoal Method to determine if the PTU has reached its goal. More... | |
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 More... | |
virtual void | setAbsoluteAngleSpeeds (double pan_speed, double tilt_speed) |
setAbsoluteAngleSpeeds Method to set desired speed for pan/tilt movement absolute in deg/s More... | |
virtual void | setAbsoluteAngleSpeeds (signed short pan_speed, signed short tilt_speed) |
determineLegitEndPoint DO NOT USE, NOT SUPPORTED IN MOCK More... | |
virtual void | setLimitAngles (double pan_min, double pan_max, double tilt_min, double tilt_max) |
setSettings Method to configure limits for pan and tilt More... | |
virtual void | setLimitAnglesToHardwareConstraints () |
setLimitAnglesToHardwareConstraints Method that sets the pan and tilt limits to the maximum values that the hardware can provide. More... | |
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 More... | |
virtual void | setSpeedControlMode (bool speed_control_mode) |
setSpeedControlMode Method to set and disable pure speed control mode More... | |
virtual bool | setValuesOutOfLimitsButWithinMarginToLimit (double *pan, double *tilt, double margin) |
setValuesOutOfLimitsButWithinMarginToLimit This method is used to set pan/tilt values that are slighly out of pan/tilt limits (but within a margin) to these limits More... | |
~PTUDriverMock () | |
Public Member Functions inherited from asr_flir_ptu_driver::PTUDriver | |
virtual bool | isInForbiddenArea (double pan_angle, double tilt_angle) |
isInForbiddenArea method to determine if a pan + tilt value pair lies within a forbidden area. More... | |
PTUDriver (const char *port, int baud, bool speed_control) | |
PTUDriver Constructor for PTUDriver class. More... | |
PTUDriver () | |
PTUDriver Do not use, needed for mock. More... | |
virtual void | setComputationTolerance (double computation_tolerance) |
setComputationTolerance Sets the tolerance value for errors due to the imprecise nature of float, double, sqrt, ... computations (default is 0.00005 on startup) More... | |
virtual void | setDistanceFactor (long distance_factor) |
setDistanceFactor Method to set the factor which determines how much samples are going to be taken for path prediction. The higher the distance factor is the less samples get taken (the maximum time for changing a single position (step on step motor) is taken and scaled by distance factor. This is the time between two samples). Default is 5. More... | |
virtual void | setForbiddenAreas (std::vector< std::map< std::string, double > > forbidden_areas) |
setForbiddenAreas Method to set all forbidden areas for the PTU. Former forbidden areas will be discarded when invoking this method More... | |
~PTUDriver () | |
~PTUDriver Do not use, necessary because of some compiler issues. More... | |
Private Attributes | |
double | current_pan_speed |
double | current_tilt_speed |
int | is_stopped_count |
double | pan_acceleration |
double | pan_angle |
double | pan_base |
double | pan_distance |
double | pan_max_limit |
double | pan_min_limit |
double | pan_speed |
double | tilt_acceleration |
double | tilt_angle |
double | tilt_base |
double | tilt_distance |
double | tilt_max_limit |
double | tilt_min_limit |
double | tilt_speed |
Additional Inherited Members | |
Protected Member Functions inherited from asr_flir_ptu_driver::PTUDriver | |
virtual std::string | getErrorString (char status_code) |
Protected Attributes inherited from asr_flir_ptu_driver::PTUDriver | |
std::vector< std::map< std::string, double > > | forbidden_areas |
long | pan_max |
long | pan_min |
double | pan_resolution |
long | prefetched_pan_current_base |
long | prefetched_pan_current_position |
long | prefetched_pan_desired_acceleration |
long | prefetched_pan_desired_speed |
long | prefetched_tilt_current_base |
long | prefetched_tilt_current_position |
long | prefetched_tilt_desired_acceleration |
long | prefetched_tilt_desired_speed |
long | tilt_max |
long | tilt_min |
double | tilt_resolution |
Definition at line 7 of file PTUDriverMock.h.
asr_flir_ptu_driver::PTUDriverMock::PTUDriverMock | ( | const char * | port, |
int | baud, | ||
bool | speed_control | ||
) |
Definition at line 7 of file PTUDriverMock.cpp.
asr_flir_ptu_driver::PTUDriverMock::~PTUDriverMock | ( | ) |
|
virtual |
determineLegitEndPoint DO NOT USE, NOT SUPPORTED IN MOCK
end_point_pan_candidate | - |
end_point_tilt_candidate | - |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 194 of file PTUDriverMock.cpp.
|
virtual |
getAngleSpeed Method to get the current angle speed of an axisa (deg/s)
type | Axis to get the current angle speed from. PAN or TILT as value allowed. |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 156 of file PTUDriverMock.cpp.
|
virtual |
getCurrentAngle Method to get the current pan/tilt angle
type | Axis to get the current angle from. PAN or TILT as value allowed. |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 140 of file PTUDriverMock.cpp.
|
virtual |
getDesiredAngle Method to get the desired pan/tilt angle (where the ptu moves to)
type | Axis to get the desired angle from. PAN or TILT as value allowed. |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 147 of file PTUDriverMock.cpp.
|
virtual |
!!!!!!!!!Müssen nachfolgende public sein? Nach erstellen von mock überprüfen!!!!!!!!!!!
getLimitAngle Method to get one of the limit angles for pan/tilt movement
pan_or_tilt | Value to specify the axes from which you want the limit angle. Can be 'p' for pan or 't' for tilt |
upper_or_lower | Value to specifie if you want the upper or lower limit on specified axis. Can be 'l' for lower and 'u' for upper limit. |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 239 of file PTUDriverMock.cpp.
|
virtual |
hasHalted Method to determine if PTU movement has stopped
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 113 of file PTUDriverMock.cpp.
|
virtual |
hasHaltedAndReachedGoal Method to determine if the PTU has halted and reached its goal
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 135 of file PTUDriverMock.cpp.
|
virtual |
isConnected Method to check if ptu is connected.
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 19 of file PTUDriverMock.cpp.
|
virtual |
isInSpeedControlMode Method to determine if ptu is in pure speed control mode
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 86 of file PTUDriverMock.cpp.
|
virtual |
isWithinPanTiltLimits Method that checks if pan and tilt value are within the chosen pan and tilt limits
pan | Value for pan to be checked to be within limits |
tilt | Value for tilt to be checke to be within limits |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 101 of file PTUDriverMock.cpp.
|
virtual |
reachedGoal Method to determine if the PTU has reached its goal.
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 126 of file PTUDriverMock.cpp.
|
virtual |
setAbsoluteAngles Method to set pan and tilt angle for the PTU
pan_angle | Angle to move the pan axis to |
tilt_angle | Angle to move the tilt axis to |
no_forbidden_area_check | True if path prediction shall be used (nearest point on path outside orbidden areas is used) or False if it shall be checked if point is inside forbidden area (rejected then) |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 63 of file PTUDriverMock.cpp.
|
virtual |
setAbsoluteAngleSpeeds Method to set desired speed for pan/tilt movement absolute in deg/s
pan_speed | Absolute desired speed for pan axis |
tilt_speed | Absolute desired speed for tilt axis |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 51 of file PTUDriverMock.cpp.
|
virtual |
determineLegitEndPoint DO NOT USE, NOT SUPPORTED IN MOCK
end_point_pan_candidate | - |
end_point_tilt_candidate | - |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 59 of file PTUDriverMock.cpp.
|
virtual |
setSettings Method to configure limits for pan and tilt
pan_min | Minimum pan value in degree |
pan_max | Maxiumum pan value in degree |
tilt_min | Minimum tilt value in degree |
tilt_max | Maximum tilt value in degree |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 41 of file PTUDriverMock.cpp.
|
virtual |
setLimitAnglesToHardwareConstraints Method that sets the pan and tilt limits to the maximum values that the hardware can provide.
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 176 of file PTUDriverMock.cpp.
|
virtual |
setSettings Method to configure various settings of the ptu
pan_base | Base speed of pan axis |
tilt_base | Base speed of tilt axis |
pan_speed | Desired speed on pan axis |
tilt_speed | Desired speed on tilt axis |
pan_upper | Upper speed limit on pan axis |
tilt_upper | Upper speed limit on tilt axis |
pan_accel | Acceleration on pan axis |
tilt_accel | Acceleration on tilt axis |
pan_hold | Powerlevel of pan axis when not moving |
tilt_hold | Powerlevel of tilt axis when not moving |
pan_move | Powerlevel of pan axis when moving |
tilt_move | Powerlevel of tilt axis when moving |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 24 of file PTUDriverMock.cpp.
|
virtual |
setSpeedControlMode Method to set and disable pure speed control mode
speed_control_mode | True to make the PTU controllable by speed values only (no angles, only speed), false for hybrid mode (movement via angles by specified speed) |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 83 of file PTUDriverMock.cpp.
|
virtual |
setValuesOutOfLimitsButWithinMarginToLimit This method is used to set pan/tilt values that are slighly out of pan/tilt limits (but within a margin) to these limits
pan | Pan value to check if it is within pan limits and to set to limit if it is outside but within margin |
tilt | Tilt value to check if it is within tilt limits and to set to limit if it is outside but within margin |
margin | Margin for values outside pan/tilt limits |
Reimplemented from asr_flir_ptu_driver::PTUDriver.
Definition at line 203 of file PTUDriverMock.cpp.
|
private |
Definition at line 65 of file PTUDriverMock.h.
|
private |
Definition at line 66 of file PTUDriverMock.h.
|
private |
Definition at line 60 of file PTUDriverMock.h.
|
private |
Definition at line 69 of file PTUDriverMock.h.
|
private |
Definition at line 61 of file PTUDriverMock.h.
|
private |
Definition at line 67 of file PTUDriverMock.h.
|
private |
Definition at line 76 of file PTUDriverMock.h.
|
private |
Definition at line 71 of file PTUDriverMock.h.
|
private |
Definition at line 72 of file PTUDriverMock.h.
|
private |
Definition at line 63 of file PTUDriverMock.h.
|
private |
Definition at line 70 of file PTUDriverMock.h.
|
private |
Definition at line 62 of file PTUDriverMock.h.
|
private |
Definition at line 68 of file PTUDriverMock.h.
|
private |
Definition at line 77 of file PTUDriverMock.h.
|
private |
Definition at line 73 of file PTUDriverMock.h.
|
private |
Definition at line 74 of file PTUDriverMock.h.
|
private |
Definition at line 64 of file PTUDriverMock.h.