#include <PTUDriver.h>
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. | |
virtual double | getAngleSpeed (char type) |
getAngleSpeed Method to get the current angle speed of an axisa (deg/s) | |
virtual double | getCurrentAngle (char type) |
getCurrentAngle Method to get the current pan/tilt angle | |
virtual double | getDesiredAngle (char type) |
getDesiredAngle Method to get the desired pan/tilt angle (where the ptu moves to) | |
virtual long | getLimitAngle (char pan_or_tilt, char upper_or_lower) |
!!!!!!!!!Müssen nachfolgende public sein? Nach erstellen von mock überprüfen!!!!!!!!!!! | |
virtual bool | hasHalted () |
hasHalted Method to determine if PTU movement has stopped | |
virtual bool | hasHaltedAndReachedGoal () |
hasHaltedAndReachedGoal Method to determine if the PTU has halted and reached its goal | |
virtual bool | isConnected () |
isConnected Method to check if ptu is connected. | |
virtual bool | isInForbiddenArea (double pan_angle, double tilt_angle) |
isInForbiddenArea method to determine if a pan + tilt value pair lies within a forbidden area. | |
virtual bool | isInSpeedControlMode () |
isInSpeedControlMode Method to determine if ptu is in pure speed control mode | |
virtual bool | isWithinPanTiltLimits (double pan, double tilt) |
isWithinPanTiltLimits Method that checks if pan and tilt value are within the chosen pan and tilt limits | |
PTUDriver (const char *port, int baud, bool speed_control) | |
PTUDriver Constructor for PTUDriver class. | |
PTUDriver () | |
PTUDriver Do not use, needed for mock. | |
virtual bool | reachedGoal () |
reachedGoal Method to determine if the PTU has reached its goal. | |
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 void | setAbsoluteAngleSpeeds (double pan_speed, double tilt_speed) |
setAbsoluteAngleSpeeds Method to set desired speed for pan/tilt movement absolute in deg/s | |
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 | |
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) | |
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. | |
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 | |
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 that the hardware can provide. | |
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 | |
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 | |
~PTUDriver () | |
~PTUDriver Do not use, necessary because of some compiler issues. | |
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} |
Definition at line 58 of file PTUDriver.h.
asr_flir_ptu_driver::PTUDriver::PTUDriver | ( | const char * | port, |
int | baud, | ||
bool | speed_control | ||
) |
PTUDriver Constructor for PTUDriver class.
port | identifing string for port where ptu is plugged in |
baud | baud rate for port |
speed_control | True if PTUDriver shall be launched in pure speed control mode |
Definition at line 15 of file PTUDriver.cpp.
PTUDriver Do not use, needed for mock.
Definition at line 60 of file PTUDriver.cpp.
~PTUDriver Do not use, necessary because of some compiler issues.
Definition at line 64 of file PTUDriver.cpp.
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.
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.
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.
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.
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.
bool asr_flir_ptu_driver::PTUDriver::checkReturnCode | ( | char | return_code | ) | [private] |
Definition at line 257 of file PTUDriver.cpp.
long asr_flir_ptu_driver::PTUDriver::convertPanFromAngleToPosition | ( | double | angle | ) | [private] |
Definition at line 573 of file PTUDriver.cpp.
double asr_flir_ptu_driver::PTUDriver::convertPanFromPositionToAngle | ( | long | position | ) | [private] |
Definition at line 577 of file PTUDriver.cpp.
long asr_flir_ptu_driver::PTUDriver::convertTiltFromAngleToPosition | ( | double | angle | ) | [private] |
Definition at line 581 of file PTUDriver.cpp.
double asr_flir_ptu_driver::PTUDriver::convertTiltFromPositionToAngle | ( | long | position | ) | [private] |
Definition at line 585 of file PTUDriver.cpp.
void asr_flir_ptu_driver::PTUDriver::createSettingsBackup | ( | ) | [private] |
Definition at line 240 of file PTUDriver.cpp.
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.
end_point_pan_candidate | Pan value of desired end point |
end_point_tilt_candidate | Tilt value of desired end point |
Reimplemented in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 1026 of file PTUDriver.cpp.
long asr_flir_ptu_driver::PTUDriver::get_current | ( | char | pan_or_tilt, |
char | what | ||
) | [private] |
long asr_flir_ptu_driver::PTUDriver::get_desired | ( | char | pan_or_tilt, |
char | what | ||
) | [private] |
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.
double asr_flir_ptu_driver::PTUDriver::getAngleSpeed | ( | char | type | ) | [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 in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 561 of file PTUDriver.cpp.
double asr_flir_ptu_driver::PTUDriver::getCurrentAngle | ( | char | type | ) | [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 in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 536 of file PTUDriver.cpp.
double asr_flir_ptu_driver::PTUDriver::getDesiredAngle | ( | char | type | ) | [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 in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 549 of file PTUDriver.cpp.
std::string asr_flir_ptu_driver::PTUDriver::getErrorString | ( | char | status_code | ) | [protected, virtual] |
Definition at line 589 of file PTUDriver.cpp.
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
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 in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 278 of file PTUDriver.cpp.
double asr_flir_ptu_driver::PTUDriver::getVectorLength | ( | std::vector< double > | input_vector | ) | [private] |
Definition at line 1007 of file PTUDriver.cpp.
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.
bool asr_flir_ptu_driver::PTUDriver::hasHalted | ( | ) | [virtual] |
hasHalted Method to determine if PTU movement has stopped
Reimplemented in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 646 of file PTUDriver.cpp.
bool asr_flir_ptu_driver::PTUDriver::hasHaltedAndReachedGoal | ( | ) | [virtual] |
hasHaltedAndReachedGoal Method to determine if the PTU has halted and reached its goal
Reimplemented in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 642 of file PTUDriver.cpp.
bool asr_flir_ptu_driver::PTUDriver::isConnected | ( | ) | [virtual] |
isConnected Method to check if ptu is connected.
Reimplemented in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 69 of file PTUDriver.cpp.
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.
pan_angle | Pan angle to check |
tilt_angle | Tilt angle to check |
Definition at line 362 of file PTUDriver.cpp.
bool asr_flir_ptu_driver::PTUDriver::isInSpeedControlMode | ( | ) | [virtual] |
isInSpeedControlMode Method to determine if ptu is in pure speed control mode
Reimplemented in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 532 of file PTUDriver.cpp.
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.
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
pan | Value for pan to be checked to be within limits |
tilt | Value for tilt to be checke to be within limits |
Reimplemented in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 385 of file PTUDriver.cpp.
void asr_flir_ptu_driver::PTUDriver::precalculateForbiddenAreaCoodinateForms | ( | ) | [private] |
Definition at line 1095 of file PTUDriver.cpp.
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.
void asr_flir_ptu_driver::PTUDriver::prefetchValues | ( | ) | [private] |
Definition at line 1120 of file PTUDriver.cpp.
bool asr_flir_ptu_driver::PTUDriver::reachedGoal | ( | ) | [virtual] |
reachedGoal Method to determine if the PTU has reached its goal.
Reimplemented in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 653 of file PTUDriver.cpp.
void asr_flir_ptu_driver::PTUDriver::restoreSettingsFromBackup | ( | ) | [private] |
Definition at line 263 of file PTUDriver.cpp.
char asr_flir_ptu_driver::PTUDriver::set_desired | ( | char | pan_or_tilt, |
char | what, | ||
short int * | value, | ||
char | type | ||
) | [private] |
char asr_flir_ptu_driver::PTUDriver::set_mode | ( | char | mode_type, |
char | mode | ||
) | [private] |
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
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 in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 453 of file PTUDriver.cpp.
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
pan_speed | Absolute desired speed for pan axis |
tilt_speed | Absolute desired speed for tilt axis |
Reimplemented in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 331 of file PTUDriver.cpp.
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
pan_speed | Absolute desired speed for pan axis |
tilt_speed | Absolute desired speed for pan axis |
Reimplemented in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 350 of file PTUDriver.cpp.
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)
computation_tolerance | Tolerance for calculation errors on floating-point numbers |
Definition at line 78 of file PTUDriver.cpp.
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.
distance_factor | Factor 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.
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
forbidden_areas | Vector 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.
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
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 in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 487 of file PTUDriver.cpp.
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.
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
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 in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 87 of file PTUDriver.cpp.
void asr_flir_ptu_driver::PTUDriver::setSpeedControlMode | ( | bool | speed_control_mode | ) | [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 in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 523 of file PTUDriver.cpp.
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
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 in asr_flir_ptu_driver::PTUDriverMock.
Definition at line 400 of file PTUDriver.cpp.
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.
std::vector< double > asr_flir_ptu_driver::PTUDriver::solveSecondDegreePolynomial | ( | double | a, |
double | b, | ||
double | c | ||
) | [private] |
Definition at line 666 of file PTUDriver.cpp.
long asr_flir_ptu_driver::PTUDriver::backup_pan_accel [private] |
Definition at line 309 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_pan_base [private] |
Definition at line 306 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_pan_hold [private] |
Definition at line 310 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_pan_move [private] |
Definition at line 311 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_pan_speed [private] |
Definition at line 308 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_pan_upper [private] |
Definition at line 307 of file PTUDriver.h.
std::map<std::string,int> asr_flir_ptu_driver::PTUDriver::backup_settings [private] |
Definition at line 287 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_tilt_accel [private] |
Definition at line 315 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_tilt_base [private] |
Definition at line 312 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_tilt_hold [private] |
Definition at line 316 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_tilt_move [private] |
Definition at line 317 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_tilt_speed [private] |
Definition at line 314 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::backup_tilt_upper [private] |
Definition at line 313 of file PTUDriver.h.
double asr_flir_ptu_driver::PTUDriver::distance_factor [private] |
Definition at line 331 of file PTUDriver.h.
double asr_flir_ptu_driver::PTUDriver::double_computation_tolerance [private] |
Definition at line 283 of file PTUDriver.h.
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.
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.
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.
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.
std::vector< std::map< std::string, double> > asr_flir_ptu_driver::PTUDriver::forbidden_areas [protected] |
Definition at line 261 of file PTUDriver.h.
Definition at line 343 of file PTUDriver.h.
std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::max_pan_max_tilt_points [private] |
Definition at line 301 of file PTUDriver.h.
std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::max_pan_min_tilt_points [private] |
Definition at line 302 of file PTUDriver.h.
std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::min_pan_max_tilt_points [private] |
Definition at line 303 of file PTUDriver.h.
std::vector<std::vector<double> > asr_flir_ptu_driver::PTUDriver::min_pan_min_tilt_points [private] |
Definition at line 304 of file PTUDriver.h.
double asr_flir_ptu_driver::PTUDriver::pan_acceleration_time [private] |
Definition at line 292 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::pan_max [protected] |
Definition at line 262 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::pan_min [protected] |
Definition at line 262 of file PTUDriver.h.
double asr_flir_ptu_driver::PTUDriver::pan_resolution [protected] |
Definition at line 273 of file PTUDriver.h.
double asr_flir_ptu_driver::PTUDriver::pan_slew_speed_time [private] |
Definition at line 293 of file PTUDriver.h.
short int asr_flir_ptu_driver::PTUDriver::POW_VAL_HOLD = {PTU_OFF_POWER, PTU_LOW_POWER, PTU_REG_POWER} [static, private] |
Definition at line 286 of file PTUDriver.h.
short int asr_flir_ptu_driver::PTUDriver::POW_VAL_MOVE = {PTU_LOW_POWER, PTU_REG_POWER, PTU_HI_POWER} [static, private] |
Definition at line 285 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::prefetched_pan_current_base [protected] |
Definition at line 265 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::prefetched_pan_current_position [protected] |
Definition at line 271 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::prefetched_pan_desired_acceleration [protected] |
Definition at line 266 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::prefetched_pan_desired_speed [protected] |
Definition at line 267 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::prefetched_tilt_current_base [protected] |
Definition at line 268 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::prefetched_tilt_current_position [protected] |
Definition at line 272 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::prefetched_tilt_desired_acceleration [protected] |
Definition at line 269 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::prefetched_tilt_desired_speed [protected] |
Definition at line 270 of file PTUDriver.h.
bool asr_flir_ptu_driver::PTUDriver::speed_control [private] |
Definition at line 284 of file PTUDriver.h.
double asr_flir_ptu_driver::PTUDriver::tilt_acceleration_time [private] |
Definition at line 294 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::tilt_max [protected] |
Definition at line 263 of file PTUDriver.h.
long asr_flir_ptu_driver::PTUDriver::tilt_min [protected] |
Definition at line 263 of file PTUDriver.h.
double asr_flir_ptu_driver::PTUDriver::tilt_resolution [protected] |
Definition at line 273 of file PTUDriver.h.
double asr_flir_ptu_driver::PTUDriver::tilt_slew_speed_time [private] |
Definition at line 295 of file PTUDriver.h.