Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
asr_flir_ptu_driver::PTUDriver Class Reference

#include <PTUDriver.h>

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

Public Member Functions

virtual std::vector< double > determineLegitEndPoint (double end_point_pan_candidate, double end_point_tilt_candidate)
 determineLegitEndPoint Method to determine an end point which is not inside a forbidden area using path prediction to get the point where the path would hit the first forbidden area. ASSUMES that the point is within pan-tilt-limits. 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...
 
virtual bool isConnected ()
 isConnected Method to check if ptu is connected. More...
 
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...
 
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...
 
 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 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)
 setAbsoluteAngleSpeeds Method to set desired speed for pan/tilt movement absolute in position/s 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...
 
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...
 
 ~PTUDriver ()
 ~PTUDriver Do not use, necessary because of some compiler issues. More...
 

Protected Member Functions

virtual std::string getErrorString (char status_code)
 

Protected Attributes

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
 

Private Member Functions

std::vector< double > calculateCoordinateForm (std::vector< double > start_point, std::vector< double > end_point)
 
double calculateCoveredDistance (double acceleration_time, double slew_speed_time, double decceleration_time, bool is_pan)
 
std::vector< double > calculateIntersectionPoint (std::vector< double > first_line_coordiante_form, std::vector< double > second_line_coordiante_form)
 
std::vector< double > calculatePointOfIntersectionWithForbiddenAreas (std::vector< double > start_point, std::vector< double > end_point)
 
std::vector< double > checkForPossibleKollision (double new_pan_angle, double new_tilt_angle)
 
bool checkReturnCode (char return_code)
 
long convertPanFromAngleToPosition (double angle)
 
double convertPanFromPositionToAngle (long position)
 
long convertTiltFromAngleToPosition (double angle)
 
double convertTiltFromPositionToAngle (long position)
 
void createSettingsBackup ()
 
long get_current (char pan_or_tilt, char what)
 
long get_desired (char pan_or_tilt, char what)
 
std::vector< double > getAccelerationTimeAndSlewSpeedTime (double distance_in_steps, double base_speed, double acceleration, double slew_speed)
 
double getVectorLength (std::vector< double > input_vector)
 
double getVectorLength (std::vector< double > start_point, std::vector< double > end_point)
 
bool isOnLineSegmentBetweenTwoPoints (std::vector< double > start_point, std::vector< double > end_point, std::vector< double > line_coordinate_form, std::vector< double > point_to_check, double tolerance)
 
void precalculateForbiddenAreaCoodinateForms ()
 
std::vector< double > predictPositionInTime (std::vector< double > start_point, std::vector< double > end_point, double point_in_time)
 
void prefetchValues ()
 
void restoreSettingsFromBackup ()
 
char set_desired (char pan_or_tilt, char what, short int *value, char type)
 
char set_mode (char mode_type, char mode)
 
void setValuesToBackupValues (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)
 
std::vector< double > solveSecondDegreePolynomial (double a, double b, double c)
 

Private Attributes

long backup_pan_accel
 
long backup_pan_base
 
long backup_pan_hold
 
long backup_pan_move
 
long backup_pan_speed
 
long backup_pan_upper
 
std::map< std::string, int > backup_settings
 
long backup_tilt_accel
 
long backup_tilt_base
 
long backup_tilt_hold
 
long backup_tilt_move
 
long backup_tilt_speed
 
long backup_tilt_upper
 
double distance_factor
 
double double_computation_tolerance
 
std::vector< std::vector< double > > forbidden_area_first_line_coordinate_forms
 
std::vector< std::vector< double > > forbidden_area_fourth_line_coordinate_forms
 
std::vector< std::vector< double > > forbidden_area_second_line_coordinate_forms
 
std::vector< std::vector< double > > forbidden_area_third_line_coordinate_forms
 
ptu_free::PTUFree free_ptu
 
std::vector< std::vector< double > > max_pan_max_tilt_points
 
std::vector< std::vector< double > > max_pan_min_tilt_points
 
std::vector< std::vector< double > > min_pan_max_tilt_points
 
std::vector< std::vector< double > > min_pan_min_tilt_points
 
double pan_acceleration_time
 
double pan_slew_speed_time
 
bool speed_control
 
double tilt_acceleration_time
 
double tilt_slew_speed_time
 

Static Private Attributes

static short int POW_VAL_HOLD [3] = {PTU_OFF_POWER, PTU_LOW_POWER, PTU_REG_POWER}
 
static short int POW_VAL_MOVE [3] = {PTU_LOW_POWER, PTU_REG_POWER, PTU_HI_POWER}
 

Detailed Description

Definition at line 58 of file PTUDriver.h.

Constructor & Destructor Documentation

◆ PTUDriver() [1/2]

asr_flir_ptu_driver::PTUDriver::PTUDriver ( const char *  port,
int  baud,
bool  speed_control 
)

PTUDriver Constructor for PTUDriver class.

Parameters
portidentifing string for port where ptu is plugged in
baudbaud rate for port
speed_controlTrue if PTUDriver shall be launched in pure speed control mode

Definition at line 15 of file PTUDriver.cpp.

◆ PTUDriver() [2/2]

asr_flir_ptu_driver::PTUDriver::PTUDriver ( )

PTUDriver Do not use, needed for mock.

Definition at line 60 of file PTUDriver.cpp.

◆ ~PTUDriver()

asr_flir_ptu_driver::PTUDriver::~PTUDriver ( )

~PTUDriver Do not use, necessary because of some compiler issues.

Definition at line 64 of file PTUDriver.cpp.

Member Function Documentation

◆ calculateCoordinateForm()

std::vector< double > asr_flir_ptu_driver::PTUDriver::calculateCoordinateForm ( std::vector< double >  start_point,
std::vector< double >  end_point 
)
private

Definition at line 992 of file PTUDriver.cpp.

◆ calculateCoveredDistance()

double asr_flir_ptu_driver::PTUDriver::calculateCoveredDistance ( double  acceleration_time,
double  slew_speed_time,
double  decceleration_time,
bool  is_pan 
)
private

Definition at line 840 of file PTUDriver.cpp.

◆ calculateIntersectionPoint()

std::vector< double > asr_flir_ptu_driver::PTUDriver::calculateIntersectionPoint ( std::vector< double >  first_line_coordiante_form,
std::vector< double >  second_line_coordiante_form 
)
private

Definition at line 934 of file PTUDriver.cpp.

◆ calculatePointOfIntersectionWithForbiddenAreas()

std::vector< double > asr_flir_ptu_driver::PTUDriver::calculatePointOfIntersectionWithForbiddenAreas ( std::vector< double >  start_point,
std::vector< double >  end_point 
)
private

Definition at line 875 of file PTUDriver.cpp.

◆ checkForPossibleKollision()

std::vector< double > asr_flir_ptu_driver::PTUDriver::checkForPossibleKollision ( double  new_pan_angle,
double  new_tilt_angle 
)
private

Definition at line 1053 of file PTUDriver.cpp.

◆ checkReturnCode()

bool asr_flir_ptu_driver::PTUDriver::checkReturnCode ( char  return_code)
private

Definition at line 257 of file PTUDriver.cpp.

◆ convertPanFromAngleToPosition()

long asr_flir_ptu_driver::PTUDriver::convertPanFromAngleToPosition ( double  angle)
private

Definition at line 573 of file PTUDriver.cpp.

◆ convertPanFromPositionToAngle()

double asr_flir_ptu_driver::PTUDriver::convertPanFromPositionToAngle ( long  position)
private

Definition at line 577 of file PTUDriver.cpp.

◆ convertTiltFromAngleToPosition()

long asr_flir_ptu_driver::PTUDriver::convertTiltFromAngleToPosition ( double  angle)
private

Definition at line 581 of file PTUDriver.cpp.

◆ convertTiltFromPositionToAngle()

double asr_flir_ptu_driver::PTUDriver::convertTiltFromPositionToAngle ( long  position)
private

Definition at line 585 of file PTUDriver.cpp.

◆ createSettingsBackup()

void asr_flir_ptu_driver::PTUDriver::createSettingsBackup ( )
private

Definition at line 240 of file PTUDriver.cpp.

◆ determineLegitEndPoint()

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

determineLegitEndPoint Method to determine an end point which is not inside a forbidden area using path prediction to get the point where the path would hit the first forbidden area. ASSUMES that the point is within pan-tilt-limits.

Parameters
end_point_pan_candidatePan value of desired end point
end_point_tilt_candidateTilt value of desired end point
Returns
Vector with nearest legit end point on the path to the desired end point. Pan at [0], Tilt at [1].

Reimplemented in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 1026 of file PTUDriver.cpp.

◆ get_current()

long asr_flir_ptu_driver::PTUDriver::get_current ( char  pan_or_tilt,
char  what 
)
private

◆ get_desired()

long asr_flir_ptu_driver::PTUDriver::get_desired ( char  pan_or_tilt,
char  what 
)
private

◆ getAccelerationTimeAndSlewSpeedTime()

std::vector< double > asr_flir_ptu_driver::PTUDriver::getAccelerationTimeAndSlewSpeedTime ( double  distance_in_steps,
double  base_speed,
double  acceleration,
double  slew_speed 
)
private

Definition at line 687 of file PTUDriver.cpp.

◆ getAngleSpeed()

double asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 561 of file PTUDriver.cpp.

◆ getCurrentAngle()

double asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 536 of file PTUDriver.cpp.

◆ getDesiredAngle()

double asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 549 of file PTUDriver.cpp.

◆ getErrorString()

std::string asr_flir_ptu_driver::PTUDriver::getErrorString ( char  status_code)
protectedvirtual

Definition at line 589 of file PTUDriver.cpp.

◆ getLimitAngle()

long asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 278 of file PTUDriver.cpp.

◆ getVectorLength() [1/2]

double asr_flir_ptu_driver::PTUDriver::getVectorLength ( std::vector< double >  input_vector)
private

Definition at line 1007 of file PTUDriver.cpp.

◆ getVectorLength() [2/2]

double asr_flir_ptu_driver::PTUDriver::getVectorLength ( std::vector< double >  start_point,
std::vector< double >  end_point 
)
private

Definition at line 1015 of file PTUDriver.cpp.

◆ hasHalted()

bool asr_flir_ptu_driver::PTUDriver::hasHalted ( )
virtual

hasHalted Method to determine if PTU movement has stopped

Returns
True if halted

Reimplemented in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 646 of file PTUDriver.cpp.

◆ hasHaltedAndReachedGoal()

bool asr_flir_ptu_driver::PTUDriver::hasHaltedAndReachedGoal ( )
virtual

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

Returns
True if halted and reached goal

Reimplemented in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 642 of file PTUDriver.cpp.

◆ isConnected()

bool asr_flir_ptu_driver::PTUDriver::isConnected ( )
virtual

isConnected Method to check if ptu is connected.

Returns
True if connected

Reimplemented in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 69 of file PTUDriver.cpp.

◆ isInForbiddenArea()

bool asr_flir_ptu_driver::PTUDriver::isInForbiddenArea ( double  pan_angle,
double  tilt_angle 
)
virtual

isInForbiddenArea method to determine if a pan + tilt value pair lies within a forbidden area.

Parameters
pan_anglePan angle to check
tilt_angleTilt angle to check
Returns
True if pan + tilt position lies in forbidden area

Definition at line 362 of file PTUDriver.cpp.

◆ isInSpeedControlMode()

bool asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 532 of file PTUDriver.cpp.

◆ isOnLineSegmentBetweenTwoPoints()

bool asr_flir_ptu_driver::PTUDriver::isOnLineSegmentBetweenTwoPoints ( std::vector< double >  start_point,
std::vector< double >  end_point,
std::vector< double >  line_coordinate_form,
std::vector< double >  point_to_check,
double  tolerance 
)
private

!!!!!!!!!!!!!Problem: x or y is zero -> this value is freely changeable!!!!!!!!!!!!!!!!!!!!!!!!!!!!

Definition at line 950 of file PTUDriver.cpp.

◆ isWithinPanTiltLimits()

bool asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 385 of file PTUDriver.cpp.

◆ precalculateForbiddenAreaCoodinateForms()

void asr_flir_ptu_driver::PTUDriver::precalculateForbiddenAreaCoodinateForms ( )
private

Definition at line 1095 of file PTUDriver.cpp.

◆ predictPositionInTime()

std::vector< double > asr_flir_ptu_driver::PTUDriver::predictPositionInTime ( std::vector< double >  start_point,
std::vector< double >  end_point,
double  point_in_time 
)
private

Definition at line 736 of file PTUDriver.cpp.

◆ prefetchValues()

void asr_flir_ptu_driver::PTUDriver::prefetchValues ( )
private

Definition at line 1120 of file PTUDriver.cpp.

◆ reachedGoal()

bool asr_flir_ptu_driver::PTUDriver::reachedGoal ( )
virtual

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

Returns
True if halted

Reimplemented in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 653 of file PTUDriver.cpp.

◆ restoreSettingsFromBackup()

void asr_flir_ptu_driver::PTUDriver::restoreSettingsFromBackup ( )
private

Definition at line 263 of file PTUDriver.cpp.

◆ set_desired()

char asr_flir_ptu_driver::PTUDriver::set_desired ( char  pan_or_tilt,
char  what,
short int *  value,
char  type 
)
private

◆ set_mode()

char asr_flir_ptu_driver::PTUDriver::set_mode ( char  mode_type,
char  mode 
)
private

◆ setAbsoluteAngles()

bool asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 453 of file PTUDriver.cpp.

◆ setAbsoluteAngleSpeeds() [1/2]

void asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 331 of file PTUDriver.cpp.

◆ setAbsoluteAngleSpeeds() [2/2]

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

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

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

Reimplemented in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 350 of file PTUDriver.cpp.

◆ setComputationTolerance()

void asr_flir_ptu_driver::PTUDriver::setComputationTolerance ( double  computation_tolerance)
virtual

setComputationTolerance Sets the tolerance value for errors due to the imprecise nature of float, double, sqrt, ... computations (default is 0.00005 on startup)

Parameters
computation_toleranceTolerance for calculation errors on floating-point numbers

Definition at line 78 of file PTUDriver.cpp.

◆ setDistanceFactor()

void asr_flir_ptu_driver::PTUDriver::setDistanceFactor ( long  distance_factor)
virtual

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.

Parameters
distance_factorFactor for scaling the time period between two samples of the path prediction. Default 5. Higher Value -> Less Samples. Decrease to boost precision, Increase to boost performance.

Definition at line 82 of file PTUDriver.cpp.

◆ setForbiddenAreas()

void asr_flir_ptu_driver::PTUDriver::setForbiddenAreas ( std::vector< std::map< std::string, double > >  forbidden_areas)
virtual

setForbiddenAreas Method to set all forbidden areas for the PTU. Former forbidden areas will be discarded when invoking this method

Parameters
forbidden_areasVector of std::map. Each map needs to contain 4 entries specified by the strings "pan_min", "pan_max", "tilt_min" and "tilt_max" with the corresponding values for the forbidden area

Definition at line 308 of file PTUDriver.cpp.

◆ setLimitAngles()

void asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 487 of file PTUDriver.cpp.

◆ setLimitAnglesToHardwareConstraints()

void asr_flir_ptu_driver::PTUDriver::setLimitAnglesToHardwareConstraints ( )
virtual

setLimitAnglesToHardwareConstraints Method that sets the pan and tilt limits to the maximum values that the hardware can provide.

Reimplemented in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 443 of file PTUDriver.cpp.

◆ setSettings()

void asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 87 of file PTUDriver.cpp.

◆ setSpeedControlMode()

void asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 523 of file PTUDriver.cpp.

◆ setValuesOutOfLimitsButWithinMarginToLimit()

bool asr_flir_ptu_driver::PTUDriver::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 in asr_flir_ptu_driver::PTUDriverMock.

Definition at line 400 of file PTUDriver.cpp.

◆ setValuesToBackupValues()

void asr_flir_ptu_driver::PTUDriver::setValuesToBackupValues ( 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 
)
private

Definition at line 187 of file PTUDriver.cpp.

◆ solveSecondDegreePolynomial()

std::vector< double > asr_flir_ptu_driver::PTUDriver::solveSecondDegreePolynomial ( double  a,
double  b,
double  c 
)
private

Definition at line 666 of file PTUDriver.cpp.

Member Data Documentation

◆ backup_pan_accel

long asr_flir_ptu_driver::PTUDriver::backup_pan_accel
private

Definition at line 309 of file PTUDriver.h.

◆ backup_pan_base

long asr_flir_ptu_driver::PTUDriver::backup_pan_base
private

Definition at line 306 of file PTUDriver.h.

◆ backup_pan_hold

long asr_flir_ptu_driver::PTUDriver::backup_pan_hold
private

Definition at line 310 of file PTUDriver.h.

◆ backup_pan_move

long asr_flir_ptu_driver::PTUDriver::backup_pan_move
private

Definition at line 311 of file PTUDriver.h.

◆ backup_pan_speed

long asr_flir_ptu_driver::PTUDriver::backup_pan_speed
private

Definition at line 308 of file PTUDriver.h.

◆ backup_pan_upper

long asr_flir_ptu_driver::PTUDriver::backup_pan_upper
private

Definition at line 307 of file PTUDriver.h.

◆ backup_settings

std::map<std::string,int> asr_flir_ptu_driver::PTUDriver::backup_settings
private

Definition at line 287 of file PTUDriver.h.

◆ backup_tilt_accel

long asr_flir_ptu_driver::PTUDriver::backup_tilt_accel
private

Definition at line 315 of file PTUDriver.h.

◆ backup_tilt_base

long asr_flir_ptu_driver::PTUDriver::backup_tilt_base
private

Definition at line 312 of file PTUDriver.h.

◆ backup_tilt_hold

long asr_flir_ptu_driver::PTUDriver::backup_tilt_hold
private

Definition at line 316 of file PTUDriver.h.

◆ backup_tilt_move

long asr_flir_ptu_driver::PTUDriver::backup_tilt_move
private

Definition at line 317 of file PTUDriver.h.

◆ backup_tilt_speed

long asr_flir_ptu_driver::PTUDriver::backup_tilt_speed
private

Definition at line 314 of file PTUDriver.h.

◆ backup_tilt_upper

long asr_flir_ptu_driver::PTUDriver::backup_tilt_upper
private

Definition at line 313 of file PTUDriver.h.

◆ distance_factor

double asr_flir_ptu_driver::PTUDriver::distance_factor
private

Definition at line 331 of file PTUDriver.h.

◆ double_computation_tolerance

double asr_flir_ptu_driver::PTUDriver::double_computation_tolerance
private

Definition at line 283 of file PTUDriver.h.

◆ forbidden_area_first_line_coordinate_forms

std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::forbidden_area_first_line_coordinate_forms
private

Definition at line 296 of file PTUDriver.h.

◆ forbidden_area_fourth_line_coordinate_forms

std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::forbidden_area_fourth_line_coordinate_forms
private

Definition at line 299 of file PTUDriver.h.

◆ forbidden_area_second_line_coordinate_forms

std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::forbidden_area_second_line_coordinate_forms
private

Definition at line 297 of file PTUDriver.h.

◆ forbidden_area_third_line_coordinate_forms

std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::forbidden_area_third_line_coordinate_forms
private

Definition at line 298 of file PTUDriver.h.

◆ forbidden_areas

std::vector< std::map< std::string, double> > asr_flir_ptu_driver::PTUDriver::forbidden_areas
protected

Definition at line 261 of file PTUDriver.h.

◆ free_ptu

ptu_free::PTUFree asr_flir_ptu_driver::PTUDriver::free_ptu
private

Definition at line 343 of file PTUDriver.h.

◆ max_pan_max_tilt_points

std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::max_pan_max_tilt_points
private

Definition at line 301 of file PTUDriver.h.

◆ max_pan_min_tilt_points

std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::max_pan_min_tilt_points
private

Definition at line 302 of file PTUDriver.h.

◆ min_pan_max_tilt_points

std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::min_pan_max_tilt_points
private

Definition at line 303 of file PTUDriver.h.

◆ min_pan_min_tilt_points

std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::min_pan_min_tilt_points
private

Definition at line 304 of file PTUDriver.h.

◆ pan_acceleration_time

double asr_flir_ptu_driver::PTUDriver::pan_acceleration_time
private

Definition at line 292 of file PTUDriver.h.

◆ pan_max

long asr_flir_ptu_driver::PTUDriver::pan_max
protected

Definition at line 262 of file PTUDriver.h.

◆ pan_min

long asr_flir_ptu_driver::PTUDriver::pan_min
protected

Definition at line 262 of file PTUDriver.h.

◆ pan_resolution

double asr_flir_ptu_driver::PTUDriver::pan_resolution
protected

Definition at line 273 of file PTUDriver.h.

◆ pan_slew_speed_time

double asr_flir_ptu_driver::PTUDriver::pan_slew_speed_time
private

Definition at line 293 of file PTUDriver.h.

◆ POW_VAL_HOLD

short int asr_flir_ptu_driver::PTUDriver::POW_VAL_HOLD = {PTU_OFF_POWER, PTU_LOW_POWER, PTU_REG_POWER}
staticprivate

Definition at line 286 of file PTUDriver.h.

◆ POW_VAL_MOVE

short int asr_flir_ptu_driver::PTUDriver::POW_VAL_MOVE = {PTU_LOW_POWER, PTU_REG_POWER, PTU_HI_POWER}
staticprivate

Definition at line 285 of file PTUDriver.h.

◆ prefetched_pan_current_base

long asr_flir_ptu_driver::PTUDriver::prefetched_pan_current_base
protected

Definition at line 265 of file PTUDriver.h.

◆ prefetched_pan_current_position

long asr_flir_ptu_driver::PTUDriver::prefetched_pan_current_position
protected

Definition at line 271 of file PTUDriver.h.

◆ prefetched_pan_desired_acceleration

long asr_flir_ptu_driver::PTUDriver::prefetched_pan_desired_acceleration
protected

Definition at line 266 of file PTUDriver.h.

◆ prefetched_pan_desired_speed

long asr_flir_ptu_driver::PTUDriver::prefetched_pan_desired_speed
protected

Definition at line 267 of file PTUDriver.h.

◆ prefetched_tilt_current_base

long asr_flir_ptu_driver::PTUDriver::prefetched_tilt_current_base
protected

Definition at line 268 of file PTUDriver.h.

◆ prefetched_tilt_current_position

long asr_flir_ptu_driver::PTUDriver::prefetched_tilt_current_position
protected

Definition at line 272 of file PTUDriver.h.

◆ prefetched_tilt_desired_acceleration

long asr_flir_ptu_driver::PTUDriver::prefetched_tilt_desired_acceleration
protected

Definition at line 269 of file PTUDriver.h.

◆ prefetched_tilt_desired_speed

long asr_flir_ptu_driver::PTUDriver::prefetched_tilt_desired_speed
protected

Definition at line 270 of file PTUDriver.h.

◆ speed_control

bool asr_flir_ptu_driver::PTUDriver::speed_control
private

Definition at line 284 of file PTUDriver.h.

◆ tilt_acceleration_time

double asr_flir_ptu_driver::PTUDriver::tilt_acceleration_time
private

Definition at line 294 of file PTUDriver.h.

◆ tilt_max

long asr_flir_ptu_driver::PTUDriver::tilt_max
protected

Definition at line 263 of file PTUDriver.h.

◆ tilt_min

long asr_flir_ptu_driver::PTUDriver::tilt_min
protected

Definition at line 263 of file PTUDriver.h.

◆ tilt_resolution

double asr_flir_ptu_driver::PTUDriver::tilt_resolution
protected

Definition at line 273 of file PTUDriver.h.

◆ tilt_slew_speed_time

double asr_flir_ptu_driver::PTUDriver::tilt_slew_speed_time
private

Definition at line 295 of file PTUDriver.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 Feb 28 2022 21:41:05