Public Member Functions | Private Attributes | List of all members
asr_flir_ptu_driver::PTUDriverMock Class Reference

#include <PTUDriverMock.h>

Inheritance diagram for asr_flir_ptu_driver::PTUDriverMock:
Inheritance graph
[legend]

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
 

Detailed Description

Definition at line 7 of file PTUDriverMock.h.

Constructor & Destructor Documentation

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 ( )

Member Function Documentation

std::vector< double > asr_flir_ptu_driver::PTUDriverMock::determineLegitEndPoint ( double  end_point_pan_candidate,
double  end_point_tilt_candidate 
)
virtual

determineLegitEndPoint DO NOT USE, NOT SUPPORTED IN MOCK

Parameters
end_point_pan_candidate-
end_point_tilt_candidate-
Returns
-

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 194 of file PTUDriverMock.cpp.

double asr_flir_ptu_driver::PTUDriverMock::getAngleSpeed ( char  type)
virtual

getAngleSpeed Method to get the current angle speed of an axisa (deg/s)

Parameters
typeAxis to get the current angle speed from. PAN or TILT as value allowed.
Returns
Current angle speed of the axis (deg/s)

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 156 of file PTUDriverMock.cpp.

double asr_flir_ptu_driver::PTUDriverMock::getCurrentAngle ( char  type)
virtual

getCurrentAngle Method to get the current pan/tilt angle

Parameters
typeAxis to get the current angle from. PAN or TILT as value allowed.
Returns
The current angle of the chosen axis

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 140 of file PTUDriverMock.cpp.

double asr_flir_ptu_driver::PTUDriverMock::getDesiredAngle ( char  type)
virtual

getDesiredAngle Method to get the desired pan/tilt angle (where the ptu moves to)

Parameters
typeAxis to get the desired angle from. PAN or TILT as value allowed.
Returns
The desired angle of the chosen axis

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 147 of file PTUDriverMock.cpp.

long asr_flir_ptu_driver::PTUDriverMock::getLimitAngle ( char  pan_or_tilt,
char  upper_or_lower 
)
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

Parameters
pan_or_tiltValue to specify the axes from which you want the limit angle. Can be 'p' for pan or 't' for tilt
upper_or_lowerValue to specifie if you want the upper or lower limit on specified axis. Can be 'l' for lower and 'u' for upper limit.
Returns
Desired limit angle; in error case (none legit input) maximum value for double is returned

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 239 of file PTUDriverMock.cpp.

bool asr_flir_ptu_driver::PTUDriverMock::hasHalted ( )
virtual

hasHalted Method to determine if PTU movement has stopped

Returns
True if halted

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 113 of file PTUDriverMock.cpp.

bool asr_flir_ptu_driver::PTUDriverMock::hasHaltedAndReachedGoal ( )
virtual

hasHaltedAndReachedGoal Method to determine if the PTU has halted and reached its goal

Returns
True if halted and reached goal

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 135 of file PTUDriverMock.cpp.

bool asr_flir_ptu_driver::PTUDriverMock::isConnected ( )
virtual

isConnected Method to check if ptu is connected.

Returns
True if connected

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 19 of file PTUDriverMock.cpp.

bool asr_flir_ptu_driver::PTUDriverMock::isInSpeedControlMode ( )
virtual

isInSpeedControlMode Method to determine if ptu is in pure speed control mode

Returns
True if ptu is in pure speed control mode

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 86 of file PTUDriverMock.cpp.

bool asr_flir_ptu_driver::PTUDriverMock::isWithinPanTiltLimits ( double  pan,
double  tilt 
)
virtual

isWithinPanTiltLimits Method that checks if pan and tilt value are within the chosen pan and tilt limits

Parameters
panValue for pan to be checked to be within limits
tiltValue for tilt to be checke to be within limits
Returns
True if pan and tilt are within the limits

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 101 of file PTUDriverMock.cpp.

bool asr_flir_ptu_driver::PTUDriverMock::reachedGoal ( )
virtual

reachedGoal Method to determine if the PTU has reached its goal.

Returns
True if halted

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 126 of file PTUDriverMock.cpp.

bool asr_flir_ptu_driver::PTUDriverMock::setAbsoluteAngles ( double  pan_angle,
double  tilt_angle,
bool  no_forbidden_area_check 
)
virtual

setAbsoluteAngles Method to set pan and tilt angle for the PTU

Parameters
pan_angleAngle to move the pan axis to
tilt_angleAngle to move the tilt axis to
no_forbidden_area_checkTrue 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)
Returns
True if successfull, false otherwise (especially if no_forbidden_are_check is true and point is in forbidden area)

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 63 of file PTUDriverMock.cpp.

void asr_flir_ptu_driver::PTUDriverMock::setAbsoluteAngleSpeeds ( double  pan_speed,
double  tilt_speed 
)
virtual

setAbsoluteAngleSpeeds Method to set desired speed for pan/tilt movement absolute in deg/s

Parameters
pan_speedAbsolute desired speed for pan axis
tilt_speedAbsolute desired speed for tilt axis

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 51 of file PTUDriverMock.cpp.

void asr_flir_ptu_driver::PTUDriverMock::setAbsoluteAngleSpeeds ( signed short  pan_speed,
signed short  tilt_speed 
)
virtual

determineLegitEndPoint DO NOT USE, NOT SUPPORTED IN MOCK

Parameters
end_point_pan_candidate-
end_point_tilt_candidate-

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 59 of file PTUDriverMock.cpp.

void asr_flir_ptu_driver::PTUDriverMock::setLimitAngles ( double  pan_min,
double  pan_max,
double  tilt_min,
double  tilt_max 
)
virtual

setSettings Method to configure limits for pan and tilt

Parameters
pan_minMinimum pan value in degree
pan_maxMaxiumum pan value in degree
tilt_minMinimum tilt value in degree
tilt_maxMaximum tilt value in degree

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 41 of file PTUDriverMock.cpp.

void asr_flir_ptu_driver::PTUDriverMock::setLimitAnglesToHardwareConstraints ( )
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.

void asr_flir_ptu_driver::PTUDriverMock::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 
)
virtual

setSettings Method to configure various settings of the ptu

Parameters
pan_baseBase speed of pan axis
tilt_baseBase speed of tilt axis
pan_speedDesired speed on pan axis
tilt_speedDesired speed on tilt axis
pan_upperUpper speed limit on pan axis
tilt_upperUpper speed limit on tilt axis
pan_accelAcceleration on pan axis
tilt_accelAcceleration on tilt axis
pan_holdPowerlevel of pan axis when not moving
tilt_holdPowerlevel of tilt axis when not moving
pan_movePowerlevel of pan axis when moving
tilt_movePowerlevel of tilt axis when moving

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 24 of file PTUDriverMock.cpp.

void asr_flir_ptu_driver::PTUDriverMock::setSpeedControlMode ( bool  speed_control_mode)
virtual

setSpeedControlMode Method to set and disable pure speed control mode

Parameters
speed_control_modeTrue 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.

bool asr_flir_ptu_driver::PTUDriverMock::setValuesOutOfLimitsButWithinMarginToLimit ( double *  pan,
double *  tilt,
double  margin 
)
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

Parameters
panPan value to check if it is within pan limits and to set to limit if it is outside but within margin
tiltTilt value to check if it is within tilt limits and to set to limit if it is outside but within margin
marginMargin for values outside pan/tilt limits
Returns
True if successfull, false if values are more out of pan/tilt limits than margin

Reimplemented from asr_flir_ptu_driver::PTUDriver.

Definition at line 203 of file PTUDriverMock.cpp.

Member Data Documentation

double asr_flir_ptu_driver::PTUDriverMock::current_pan_speed
private

Definition at line 65 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::current_tilt_speed
private

Definition at line 66 of file PTUDriverMock.h.

int asr_flir_ptu_driver::PTUDriverMock::is_stopped_count
private

Definition at line 60 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::pan_acceleration
private

Definition at line 69 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::pan_angle
private

Definition at line 61 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::pan_base
private

Definition at line 67 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::pan_distance
private

Definition at line 76 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::pan_max_limit
private

Definition at line 71 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::pan_min_limit
private

Definition at line 72 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::pan_speed
private

Definition at line 63 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::tilt_acceleration
private

Definition at line 70 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::tilt_angle
private

Definition at line 62 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::tilt_base
private

Definition at line 68 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::tilt_distance
private

Definition at line 77 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::tilt_max_limit
private

Definition at line 73 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::tilt_min_limit
private

Definition at line 74 of file PTUDriverMock.h.

double asr_flir_ptu_driver::PTUDriverMock::tilt_speed
private

Definition at line 64 of file PTUDriverMock.h.


The documentation for this class was generated from the following files:


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