PTUFree.cpp
Go to the documentation of this file.
00001 #include "driver/PTUFree.h"
00002 
00003 namespace ptu_free {
00004 
00005     PTUFree::PTUFree():ptu_io_service(), timer_io_service(), ptu_port(ptu_io_service) {
00006 
00007     }
00008     PTUFree::PTUFree(boost::asio::io_service& io): timer_io_service(), ptu_port(io) {
00009 
00010     }
00011 
00012     bool PTUFree::setBaudRate(int baud) {
00013         printf("Setting baud rate\n");
00014         boost::system::error_code set_option_error_code;
00015         ptu_port.set_option(boost::asio::serial_port_base::baud_rate(baud), set_option_error_code);
00016         if(set_option_error_code.value() != boost::system::errc::success) {
00017             std::string error_reason = getErrorString(set_option_error_code);
00018             printf("Setting baud to %d failed with error message: %s\n", baud, error_reason.c_str());
00019             return false;
00020         }
00021         else {
00022             printf("Success\n");
00023             return true;
00024         }
00025     }
00026 
00027     bool PTUFree::setNewSerialConnection(std::string port, int baud)
00028     {
00029         printf("Setting new Connection\n");
00030         if(ptu_port.is_open()) {
00031             printf("Closing current Serial Port Connection\n");
00032             closeSerialConnection();
00033         }
00034 
00035         boost::system::error_code open_error_code;
00036         ptu_port.open(port, open_error_code);
00037         if(open_error_code.value() != boost::system::errc::success) {
00038             std::string error_reason = getErrorString(open_error_code);
00039             printf("Opening port %s failed with error message: %s", port.c_str(), error_reason.c_str());
00040             return false;
00041         }
00042         //PTU sends some data at the beginning, eg. distrubuter and model name. This sleep command makes sure that everything has been send before buffer is cleared
00043         sleep(2);
00044         //To get rid of possible remaing stuff in the buffer of the new port used (from possible former usage, e.g. through other program)
00045         tcflush(ptu_port.lowest_layer().native_handle(), TCIOFLUSH);
00046 
00047         ptu_port.set_option(boost::asio::serial_port_base::baud_rate(9600));
00048         ptu_port.set_option(boost::asio::serial_port_base::character_size(8));
00049         ptu_port.set_option(boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::one));
00050         ptu_port.set_option(boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::none));
00051         ptu_port.set_option(boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::none));
00052 
00053         communicate("ed ");
00054         reset();
00055         //Are those neccesary or rather bad because it works against the defaults if set? NOTE: temporarily solved by comments in the method documentation
00056         awaitPositionCommandCompletion();
00057         setPositionLimitEnforcementMode(FACTORY_LIMITS_ENABLED);
00058         setPositionExecutionMode(IMMEDIATE_POSITION_EXECUTION_MODE);
00059         //necessary to get initial values for the internal variables
00060         factory_pan_min = getCurrentUsedMinimumPanPositionLimit();
00061         factory_pan_max = getCurrentUsedMaximumPanPositionLimit();
00062         factory_tilt_min = getCurrentUsedMinimumTiltPositionLimit();
00063         factory_tilt_max = getCurrentUsedMaximumTiltPositionLimit();
00064         return true;
00065     }
00066 
00067     void PTUFree::closeSerialConnection() {
00068         ptu_port.close();
00069     }
00070 
00071     std::string PTUFree::communicate(std::string request) {
00072         boost::asio::write(ptu_port, boost::asio::buffer(request.c_str(), request.size()));
00073         std::string response = readPTUResponse();
00074         return response;
00075     }
00076 
00077 
00078 
00079     std::string PTUFree::readPTUResponse() {
00080         std::string recieved_message;
00081         char current_letter;
00082         while(true) {
00083             boost::asio::read(ptu_port, boost::asio::buffer(&current_letter,1));
00084             if(current_letter == '\n') {
00085                 //HOTFIX solution: Asynchronous responses in successfull messages get cut out. In unsuccessfull messages they stay in because they gonna return false/ERROR later on anyway
00086                 //Only printf message can be messed up in error case a little bit. Since that error does not occure often it is tolerated for the moment.
00087                 size_t start_pos = recieved_message.find('*');
00088                 if(start_pos != std::string::npos) {
00089                     recieved_message = recieved_message.substr(start_pos);
00090                 }
00091                 return recieved_message;
00092             }
00093             else {
00094                 recieved_message.push_back(current_letter);
00095             }
00096         }
00097     }
00098 
00099     std::vector<std::string> PTUFree::evaluateResponse(std::string response) {
00100         std::vector<std::string> result;
00101         result.push_back(response.substr(0, 1));
00102         if(response.at(0) == '*') {
00103             result.push_back(response.substr(1, response.length() - 1));
00104             int start_position = 10000;
00105             int end_position = 0;
00106             size_t first_found_position = 0;
00107             size_t last_found_position = 0;
00108             for (int i = 0; i < 10; i++) {
00109                 first_found_position = response.find(boost::lexical_cast<std::string>(i));
00110                 if(first_found_position != std::string::npos) {
00111                         if((int) first_found_position < start_position) {
00112                             start_position = first_found_position;
00113                         }
00114                 }
00115                 last_found_position = response.rfind(boost::lexical_cast<std::string>(i));
00116                 if( last_found_position != std::string::npos) {
00117                         if((int) last_found_position > end_position) {
00118                             end_position = last_found_position;
00119                         }
00120                 }
00121             }
00122             if(start_position <= end_position) {
00123                 if(response.at(start_position - 1) == '-') {
00124                     start_position -= 1;
00125                 }
00126                 result.push_back(response.substr(start_position, end_position - start_position + 1));
00127             }
00128         }
00129         //In this case the first character is '!'
00130         else {
00131             //First character identifies if it was successfull or not and therefore is not needed here.
00132             result.push_back(response.substr(1, response.length() - 1));
00133         }
00134         return result;
00135     }
00136 
00137 
00138 
00139     bool PTUFree::setDesiredPanPositionAbsolute(short int position) {
00140         std::string command = "pp" + boost::lexical_cast<std::string>(position) + " ";
00141         std::string response = communicate(command);
00142         std::vector<std::string> response_parts = evaluateResponse(response);
00143         if(response_parts[0].at(0) == '*') {
00144             return true;
00145         }
00146         else {
00147             printf("Error while setting desired absolute pan position to %d: %s\n", position, response_parts[1].c_str());
00148             return false;
00149         }
00150     }
00151 
00152     bool PTUFree::setDesiredPanPositionRelative(short int position_offset) {
00153         std::string command = "po" + boost::lexical_cast<std::string>(position_offset) + " ";
00154         std::string response = communicate(command);
00155         std::vector<std::string> response_parts = evaluateResponse(response);
00156         if(response_parts[0].at(0) == '*') {
00157             return true;
00158         }
00159         else {
00160             printf("Error while adding desired pan position offset of %d: %s\n", position_offset, response_parts[1].c_str());
00161             return false;
00162         }
00163     }
00164 
00165     bool PTUFree::setDesiredPanSpeedAbsolute(short int speed) {
00166         std::string command = "ps" + boost::lexical_cast<std::string>(speed) + " ";
00167         std::string response = communicate(command);
00168         std::vector<std::string> response_parts = evaluateResponse(response);
00169         if(response_parts[0].at(0) == '*') {
00170             return true;
00171         }
00172         else {
00173             printf("Error while setting desired absolute pan speed to %d: %s\n", speed, response_parts[1].c_str());
00174             return false;
00175         }
00176     }
00177 
00178     //WARNING: OFFSET FROM CURRENT (NOT DESIRED) SPEED IS SET TO DESIRED SPEED (Example: Current speed = 0, Desired Speed = 500. set_desired_pan_speed_realtive(100) will result in
00179     //current speed being 0 and desired speed being 0 + 100 = 100
00180     bool PTUFree::setDesiredPanSpeedRelative(short int speed_offset) {
00181         std::string command = "pd" + boost::lexical_cast<std::string>(speed_offset) + " ";
00182         std::string response = communicate(command);
00183         std::vector<std::string> response_parts = evaluateResponse(response);
00184         if(response_parts[0].at(0) == '*') {
00185             return true;
00186         }
00187         else {
00188             printf("Error while setting desired pan speed offset to %d: %s\n", speed_offset, response_parts[1].c_str());
00189             return false;
00190         }
00191     }
00192 
00193     bool PTUFree::setDesiredPanAccelerationAbsolute(short int acceleration) {
00194         std::string command = "pa" + boost::lexical_cast<std::string>(acceleration) + " ";
00195         std::string response = communicate(command);
00196         std::vector<std::string> response_parts = evaluateResponse(response);
00197         if(response_parts[0].at(0) == '*') {
00198             return true;
00199         }
00200         else {
00201             printf("Error while setting absolute pan acceleration to %d: %s\n", acceleration, response_parts[1].c_str());
00202             return false;
00203         }
00204     }
00205 
00206 
00207     //WARNING: TAKES EXTREMLY LONG OR DOES NOT WORK. ACCORDING TO MANUAL THIS DOES NOT WORK ON THE FLY, IN TESTING EVEN 300 SECONDS WERE NOT ENOUGH. THEREFORE NOT SUCCESSFULLY TESTED, DO NOT USE
00208     bool PTUFree::setDesiredPanUpperSpeedLimit(short int upper_speed_limit) {
00209         std::string command = "pu" + boost::lexical_cast<std::string>(upper_speed_limit) + " ";
00210         std::string response = communicate(command);
00211         std::vector<std::string> response_parts = evaluateResponse(response);
00212         if(response_parts[0].at(0) == '*') {
00213             return true;
00214         }
00215         else {
00216             printf("Error while setting absolute pan base speed to %d: %s\n", upper_speed_limit, response_parts[1].c_str());
00217             return false;
00218         }
00219     }
00220 
00221 
00222     //WARNING: MUST BE 0 or >= 57 (last value depending on ptu)
00223     //WARNING: Consumes a lot of time (usually >6 seconds) until changes are in place (not possible on the fly)
00224     bool PTUFree::setDesiredPanLowerSpeedLimit(short int lower_speed_limit) {
00225         std::string command = "pl" + boost::lexical_cast<std::string>(lower_speed_limit) + " ";
00226         std::string response = communicate(command);
00227         std::vector<std::string> response_parts = evaluateResponse(response);
00228         if(response_parts[0].at(0) == '*') {
00229             return true;
00230         }
00231         else {
00232             printf("Error while setting absolute lower speed limit to %d: %s\n", lower_speed_limit, response_parts[1].c_str());
00233             return false;
00234         }
00235     }
00236 
00237     bool PTUFree::setPanBaseSpeed(short int base_speed) {
00238         std::string command = "pb" + boost::lexical_cast<std::string>(base_speed) + " ";
00239         std::string response = communicate(command);
00240         std::vector<std::string> response_parts = evaluateResponse(response);
00241         if(response_parts[0].at(0) == '*') {
00242             return true;
00243         }
00244         else {
00245             printf("Error while setting pan base speed to %d: %s\n", base_speed, response_parts[1].c_str());
00246             return false;
00247         }
00248     }
00249 
00250 
00251 
00252     long PTUFree::getCurrentPanPosition() {
00253         std::string command = "pp ";
00254         std::string response = communicate(command);
00255         std::vector<std::string> response_parts = evaluateResponse(response);
00256         if(response_parts[0].at(0) == '*') {
00257             return boost::lexical_cast<long>(response_parts[2]);
00258         }
00259         else {
00260             printf("Error while getting current pan position: %s\n", response_parts[1].c_str());
00261             return LONG_MIN;
00262         }
00263     }
00264 
00265     long PTUFree::getCurrentPanSpeed() {
00266         std::string command = "pd ";
00267         std::string response = communicate(command);
00268         std::vector<std::string> response_parts = evaluateResponse(response);
00269         if(response_parts[0].at(0) == '*') {
00270             return boost::lexical_cast<long>(response_parts[2]);
00271         }
00272         else {
00273             printf("Error while getting current pan speed: %s\n", response_parts[1].c_str());
00274             return LONG_MIN;
00275         }
00276     }
00277 
00278 
00279 
00280 
00281     long PTUFree::getPanUpperSpeedLimit() {
00282         std::string command = "pu ";
00283         std::string response = communicate(command);
00284         std::vector<std::string> response_parts = evaluateResponse(response);
00285         if(response_parts[0].at(0) == '*') {
00286             return boost::lexical_cast<long>(response_parts[2]);
00287         }
00288         else {
00289             printf("Error while getting current pan upper speed limit: %s\n", response_parts[1].c_str());
00290             return LONG_MIN;
00291         }
00292     }
00293 
00294     long PTUFree::getPanLowerSpeedLimit() {
00295         std::string command = "pl ";
00296         std::string response = communicate(command);
00297         std::vector<std::string> response_parts = evaluateResponse(response);
00298         if(response_parts[0].at(0) == '*') {
00299             return boost::lexical_cast<long>(response_parts[2]);
00300         }
00301         else {
00302             printf("Error while getting curent pan lower speed limit: %s\n", response_parts[1].c_str());
00303             return LONG_MIN;
00304         }
00305     }
00306 
00307     double PTUFree::getPanResolution() {
00308         std::string command = "pr ";
00309         std::string response = communicate(command);
00310         std::vector<std::string> response_parts = evaluateResponse(response);
00311         if(response_parts[0].at(0) == '*') {
00312             return boost::lexical_cast<double>(response_parts[2]);
00313         }
00314         else {
00315             printf("Error while getting pan resolution: %s\n", response_parts[1].c_str());
00316             return -1.0;
00317         }
00318     }
00319 
00320     long PTUFree::getDesiredPanPosition() {
00321         std::string command = "po ";
00322         std::string response = communicate(command);
00323         std::vector<std::string> response_parts = evaluateResponse(response);
00324         if(response_parts[0].at(0) == '*') {
00325             return boost::lexical_cast<long>(response_parts[2]);
00326         }
00327         else {
00328             printf("Error while getting desired pan position: %s\n", response_parts[1].c_str());
00329             return LONG_MIN;
00330         }
00331     }
00332 
00333     long PTUFree::getDesiredPanSpeed() {
00334         std::string command = "ps ";
00335         std::string response = communicate(command);
00336         std::vector<std::string> response_parts = evaluateResponse(response);
00337         if(response_parts[0].at(0) == '*') {
00338             return boost::lexical_cast<long>(response_parts[2]);
00339         }
00340         else {
00341             printf("Error while getting desired pan speed: %s\n", response_parts[1].c_str());
00342             return LONG_MIN;
00343         }
00344     }
00345 
00346     long PTUFree::getPanAcceleartion() {
00347         std::string command = "pa ";
00348         std::string response = communicate(command);
00349         std::vector<std::string> response_parts = evaluateResponse(response);
00350         if(response_parts[0].at(0) == '*') {
00351             return boost::lexical_cast<long>(response_parts[2]);
00352         }
00353         else {
00354             printf("Error while getting desired pan acceleration (desired == current in this case): %s\n", response_parts[1].c_str());
00355             return LONG_MIN;
00356         }
00357     }
00358 
00359     long PTUFree::getPanBaseSpeed() {
00360         std::string command = "pb ";
00361         std::string response = communicate(command);
00362         std::vector<std::string> response_parts = evaluateResponse(response);
00363         if(response_parts[0].at(0) == '*') {
00364             return boost::lexical_cast<long>(response_parts[2]);
00365         }
00366         else {
00367             printf("Error while getting desired pan base speed: %s\n", response_parts[1].c_str());
00368             return LONG_MIN;
00369         }
00370     }
00371 
00372 
00373 
00374 
00375     bool PTUFree::setDesiredTiltPositionAbsolute(short int position) {
00376         std::string command = "tp" + boost::lexical_cast<std::string>(position) + " ";
00377         std::string response = communicate(command);
00378         std::vector<std::string> response_parts = evaluateResponse(response);
00379         if(response_parts[0].at(0) == '*') {
00380             return true;
00381         }
00382         else {
00383             printf("Error while setting desired absolute tilt position to %d: %s\n", position, response_parts[1].c_str());
00384             return false;
00385         }
00386     }
00387 
00388     bool PTUFree::setDesiredTiltPositionRelative(short int position_offset) {
00389         std::string command = "to" + boost::lexical_cast<std::string>(position_offset) + " ";
00390         std::string response = communicate(command);
00391         std::vector<std::string> response_parts = evaluateResponse(response);
00392         if(response_parts[0].at(0) == '*') {
00393             return true;
00394         }
00395         else {
00396             printf("Error while adding desired tilt position offset of %d: %s\n", position_offset, response_parts[1].c_str());
00397             return false;
00398         }
00399     }
00400 
00401     bool PTUFree::setDesiredTiltSpeedAbsolute(short int speed) {
00402         std::string command = "ts" + boost::lexical_cast<std::string>(speed) + " ";
00403         std::string response = communicate(command);
00404         std::vector<std::string> response_parts = evaluateResponse(response);
00405         if(response_parts[0].at(0) == '*') {
00406             return true;
00407         }
00408         else {
00409             printf("Error while setting desired absolute tilt speed to %d: %s\n", speed, response_parts[1].c_str());
00410             return false;
00411         }
00412     }
00413 
00414     //WARNING: OFFSET FROM CURRENT (NOT DESIRED) SPEED IS SET TO DESIRED SPEED (Example: Current speed = 0, Desired Speed = 500. setDesiredTiltSpeedRelative(100) will result in
00415     //current speed being 0 and desired speed being 0 + 100 = 100
00416     bool PTUFree::setDesiredTiltSpeedRelative(short int speed_offset) {
00417         std::string command = "td" + boost::lexical_cast<std::string>(speed_offset) + " ";
00418         std::string response = communicate(command);
00419         std::vector<std::string> response_parts = evaluateResponse(response);
00420         if(response_parts[0].at(0) == '*') {
00421             return true;
00422         }
00423         else {
00424             printf("Error while setting desired tilt speed offset to %d: %s\n", speed_offset, response_parts[1].c_str());
00425             return false;
00426         }
00427     }
00428 
00429     bool PTUFree::setDesiredTiltAccelerationAbsolute(short int acceleration) {
00430         std::string command = "ta" + boost::lexical_cast<std::string>(acceleration) + " ";
00431         std::string response = communicate(command);
00432         std::vector<std::string> response_parts = evaluateResponse(response);
00433         if(response_parts[0].at(0) == '*') {
00434             return true;
00435         }
00436         else {
00437             printf("Error while setting absolute tilt acceleration to %d: %s\n", acceleration, response_parts[1].c_str());
00438             return false;
00439         }
00440     }
00441 
00442 
00443     //WARNING: TAKES EXTREMLY LONG OR DOES NOT WORK. ACCORDING TO MANUAL THIS DOES NOT WORK ON THE FLY, IN TESTING EVEN 300 SECONDS WERE NOT ENOUGH. THEREFORE NOT SUCCESSFULLY TESTED, DO NOT USE
00444     bool PTUFree::setDesiredTiltUpperSpeedLimit(short int upper_speed_limit) {
00445         std::string command = "tu" + boost::lexical_cast<std::string>(upper_speed_limit) + " ";
00446         std::string response = communicate(command);
00447         std::vector<std::string> response_parts = evaluateResponse(response);
00448         if(response_parts[0].at(0) == '*') {
00449             return true;
00450         }
00451         else {
00452             printf("Error while setting desired tilt base speed to %d: %s\n", upper_speed_limit, response_parts[1].c_str());
00453             return false;
00454         }
00455     }
00456 
00457 
00458     //WARNING: MUST BE 0 or >= 57 (last value depending on ptu)
00459     //WARNING: Consumes a lot of time (usually >6 seconds) until changes are in place (not possible on the fly)
00460     bool PTUFree::setDesiredTiltLowerSpeedLimit(short int lower_speed_limit) {
00461         std::string command = "tl" + boost::lexical_cast<std::string>(lower_speed_limit) + " ";
00462         std::string response = communicate(command);
00463         std::vector<std::string> response_parts = evaluateResponse(response);
00464         if(response_parts[0].at(0) == '*') {
00465             return true;
00466         }
00467         else {
00468             printf("Error while setting desired tilt lower speed limit to %d: %s\n", lower_speed_limit, response_parts[1].c_str());
00469             return false;
00470         }
00471     }
00472 
00473     bool PTUFree::setTiltBaseSpeed(short int base_speed) {
00474         std::string command = "tb" + boost::lexical_cast<std::string>(base_speed) + " ";
00475         std::string response = communicate(command);
00476         std::vector<std::string> response_parts = evaluateResponse(response);
00477         if(response_parts[0].at(0) == '*') {
00478             return true;
00479         }
00480         else {
00481             printf("Error while setting tilt base speed to %d: %s\n", base_speed, response_parts[1].c_str());
00482             return false;
00483         }
00484     }
00485 
00486 
00487 
00488     long PTUFree::getCurrentTiltPosition() {
00489         std::string command = "tp ";
00490         std::string response = communicate(command);
00491         std::vector<std::string> response_parts = evaluateResponse(response);
00492         if(response_parts[0].at(0) == '*') {
00493             return boost::lexical_cast<long>(response_parts[2]);
00494         }
00495         else {
00496             printf("Error while getting current tilt position: %s\n", response_parts[1].c_str());
00497             return LONG_MIN;
00498         }
00499     }
00500 
00501     long PTUFree::getCurrentTiltSpeed() {
00502         std::string command = "td ";
00503         std::string response = communicate(command);
00504         std::vector<std::string> response_parts = evaluateResponse(response);
00505         if(response_parts[0].at(0) == '*') {
00506             return boost::lexical_cast<long>(response_parts[2]);
00507         }
00508         else {
00509             printf("Error while getting current tilt speed: %s\n", response_parts[1].c_str());
00510             return LONG_MIN;
00511         }
00512     }
00513 
00514 
00515 
00516 
00517     long PTUFree::getTiltUpperSpeedLimit() {
00518         std::string command = "tu ";
00519         std::string response = communicate(command);
00520         std::vector<std::string> response_parts = evaluateResponse(response);
00521         if(response_parts[0].at(0) == '*') {
00522             return boost::lexical_cast<long>(response_parts[2]);
00523         }
00524         else {
00525             printf("Error while getting current tilt upper speed limit: %s\n", response_parts[1].c_str());
00526             return LONG_MIN;
00527         }
00528     }
00529 
00530     long PTUFree::getTiltLowerSpeedLimit() {
00531         std::string command = "tl ";
00532         std::string response = communicate(command);
00533         std::vector<std::string> response_parts = evaluateResponse(response);
00534         if(response_parts[0].at(0) == '*') {
00535             return boost::lexical_cast<long>(response_parts[2]);
00536         }
00537         else {
00538             printf("Error while getting curent tilt lower speed limit: %s\n", response_parts[1].c_str());
00539             return LONG_MIN;
00540         }
00541     }
00542 
00543     double PTUFree::getTiltResolution() {
00544         std::string command = "tr ";
00545         std::string response = communicate(command);
00546         std::vector<std::string> response_parts = evaluateResponse(response);
00547         if(response_parts[0].at(0) == '*') {
00548             return boost::lexical_cast<double>(response_parts[2]);
00549         }
00550         else {
00551             printf("Error while getting tilt resolution: %s\n", response_parts[1].c_str());
00552             return -1.0;
00553         }
00554     }
00555 
00556     long PTUFree::getDesiredTiltPosition() {
00557         std::string command = "to ";
00558         std::string response = communicate(command);
00559         std::vector<std::string> response_parts = evaluateResponse(response);
00560         if(response_parts[0].at(0) == '*') {
00561             return boost::lexical_cast<long>(response_parts[2]);
00562         }
00563         else {
00564             printf("Error while getting desired tilt position: %s\n", response_parts[1].c_str());
00565             return LONG_MIN;
00566         }
00567     }
00568 
00569     long PTUFree::getDesiredTiltSpeed() {
00570         std::string command = "ts ";
00571         std::string response = communicate(command);
00572         std::vector<std::string> response_parts = evaluateResponse(response);
00573         if(response_parts[0].at(0) == '*') {
00574             return boost::lexical_cast<long>(response_parts[2]);
00575         }
00576         else {
00577             printf("Error while getting desired tilt speed: %s\n", response_parts[1].c_str());
00578             return LONG_MIN;
00579         }
00580     }
00581 
00582     long PTUFree::getTiltAcceleartion() {
00583         std::string command = "ta ";
00584         std::string response = communicate(command);
00585         std::vector<std::string> response_parts = evaluateResponse(response);
00586         if(response_parts[0].at(0) == '*') {
00587             return boost::lexical_cast<long>(response_parts[2]);
00588         }
00589         else {
00590             printf("Error while getting desired tilt acceleration (desired == current in this case): %s\n", response_parts[1].c_str());
00591             return LONG_MIN;
00592         }
00593     }
00594 
00595     long PTUFree::getTiltBaseSpeed() {
00596         std::string command = "tb ";
00597         std::string response = communicate(command);
00598         std::vector<std::string> response_parts = evaluateResponse(response);
00599         if(response_parts[0].at(0) == '*') {
00600             return boost::lexical_cast<long>(response_parts[2]);
00601         }
00602         else {
00603             printf("Error while getting desired tilt  base speed: %s\n", response_parts[1].c_str());
00604             return LONG_MIN;
00605         }
00606     }
00607 
00608 
00609     //WARNING: USER_DEFINED_LIMITS_ENABLED NOT SUPPORTED IN OLDER PTU VERSIONS, CASE WITH THAT LIMIT MODE NOT TESTED (PTU VERSION TOO OLD)
00610     bool PTUFree::setPositionLimitEnforcementMode(long enable) {
00611         std::string command;
00612         if(enable == FACTORY_LIMITS_ENABLED) {
00613             command = "le ";
00614         }
00615         else if (enable == USER_DEFINED_LIMITS_ENABLED) {
00616             command = "lu ";
00617         }
00618         else if (enable == LIMITS_DISABLED) {
00619             command = "ld ";
00620         }
00621         else {
00622             printf("Error while setting limit enforcement mode: Unknown mode\n");
00623             return false;
00624         }
00625         std::string response = communicate(command);
00626         std::vector<std::string> response_parts = evaluateResponse(response);
00627         if(response_parts[0].at(0) == '*') {
00628             return true;
00629         }
00630         else {
00631             printf("Error while setting limit enforcement: %s\n", response_parts[1].c_str());
00632             return false;
00633         }
00634     }
00635 
00636     bool PTUFree::setMinimumPanPositionLimit(short int position) {
00637         std::string command = "pn" + boost::lexical_cast<std::string>(position) + " ";
00638         std::string response = communicate(command);
00639         std::vector<std::string> response_parts = evaluateResponse(response);
00640         if(response_parts[0].at(0) == '*') {
00641             return true;
00642         }
00643         else {
00644             printf("Error while setting minimum user pan position limit to %d: %s\n", position, response_parts[1].c_str());
00645             return false;
00646         }
00647     }
00648     bool PTUFree::setMaximumPanPositionLimit(short int position) {
00649         std::string command = "px" + boost::lexical_cast<std::string>(position) + " ";
00650         std::string response = communicate(command);
00651         std::vector<std::string> response_parts = evaluateResponse(response);
00652         if(response_parts[0].at(0) == '*') {
00653             return true;
00654         }
00655         else {
00656             printf("Error while setting maximum user pan position limit to %d: %s\n", position, response_parts[1].c_str());
00657             return false;
00658         }
00659     }
00660     bool PTUFree::setMinimumTiltPositionLimit(short int position) {
00661         std::string command = "tn" + boost::lexical_cast<std::string>(position) + " ";
00662         std::string response = communicate(command);
00663         std::vector<std::string> response_parts = evaluateResponse(response);
00664         if(response_parts[0].at(0) == '*') {
00665             return true;
00666         }
00667         else {
00668             printf("Error while setting minimum user tilt position limit to %d: %s\n", position, response_parts[1].c_str());
00669             return false;
00670         }
00671     }
00672     bool PTUFree::setMaximumTiltPositionLimit(short int position) {
00673         std::string command = "tx" + boost::lexical_cast<std::string>(position) + " ";
00674         std::string response = communicate(command);
00675         std::vector<std::string> response_parts = evaluateResponse(response);
00676         if(response_parts[0].at(0) == '*') {
00677             return true;
00678         }
00679         else {
00680             printf("Error while setting maximum user tilt position limit to %d: %s\n", position, response_parts[1].c_str());
00681             return false;
00682         }
00683     }
00684 
00685     //WARNING: NOT SUPPORTED IN OLDER PTU VERSIONS, NOT TESTED (PTU VERSION TOO OLD)
00686     long PTUFree::getUserMinimumPanPositionLimit() {
00687         std::string command = "pnu ";
00688         std::string response = communicate(command);
00689         std::vector<std::string> response_parts = evaluateResponse(response);
00690         if(response_parts[0].at(0) == '*') {
00691             return boost::lexical_cast<long>(response_parts[2]);
00692         }
00693         else {
00694             printf("Error while getting minimum user pan position limit: %s\n", response_parts[1].c_str());
00695             return ERROR;
00696         }
00697     }
00698 
00699     //WARNING: NOT SUPPORTED IN OLDER PTU VERSIONS, NOT TESTED (PTU VERSION TOO OLD)
00700     long PTUFree::getUserMaximumPanPositionLimit() {
00701         std::string command = "pxu ";
00702         std::string response = communicate(command);
00703         std::vector<std::string> response_parts = evaluateResponse(response);
00704         if(response_parts[0].at(0) == '*') {
00705             return boost::lexical_cast<long>(response_parts[2]);
00706         }
00707         else {
00708             printf("Error while getting maximum user pan position limit: %s\n", response_parts[1].c_str());
00709             return ERROR;
00710         }
00711     }
00712 
00713     //WARNING: NOT SUPPORTED IN OLDER PTU VERSIONS, NOT TESTED (PTU VERSION TOO OLD)
00714     long PTUFree::getUserMinimumTiltPositionLimit() {
00715         std::string command = "tnu ";
00716         std::string response = communicate(command);
00717         std::vector<std::string> response_parts = evaluateResponse(response);
00718         if(response_parts[0].at(0) == '*') {
00719             return boost::lexical_cast<long>(response_parts[2]);
00720         }
00721         else {
00722             printf("Error while getting minimum user tilt position limit: %s\n", response_parts[1].c_str());
00723             return ERROR;
00724         }
00725     }
00726 
00727     //WARNING: NOT SUPPORTED IN OLDER PTU VERSIONS, NOT TESTED (PTU VERSION TOO OLD)
00728     long PTUFree::getUserMaximumTiltPositionLimit() {
00729         std::string command = "txu ";
00730         std::string response = communicate(command);
00731         std::vector<std::string> response_parts = evaluateResponse(response);
00732         if(response_parts[0].at(0) == '*') {
00733             return boost::lexical_cast<long>(response_parts[2]);
00734         }
00735         else {
00736             printf("Error while getting maximum user tilt position limit: %s\n", response_parts[1].c_str());
00737             return ERROR;
00738         }
00739     }
00740     //Needed because there is no specific command to always get the factory limits, only a command to get the limits depending on selected mode
00741     long PTUFree::getFactoryMinimumPanPositionLimit() {
00742         return factory_pan_min;
00743     }
00744     long PTUFree::getFactoryMaximumPanPositionLimit() {
00745         return factory_pan_max;
00746     }
00747     long PTUFree::getFactoryMinimumTiltPositionLimit() {
00748         return factory_tilt_min;
00749     }
00750     long PTUFree::getFactoryMaximumTiltPositionLimit() {
00751         return factory_tilt_max;
00752     }
00753     long PTUFree::getCurrentUsedMinimumPanPositionLimit() {
00754         std::string command = "pn ";
00755         std::string response = communicate(command);
00756         std::vector<std::string> response_parts = evaluateResponse(response);
00757         if(response_parts[0].at(0) == '*') {
00758             return boost::lexical_cast<long>(response_parts[2]);
00759         }
00760         else {
00761             printf("Error while getting currently used minimum pan position limit: %s\n", response_parts[1].c_str());
00762             return ERROR;
00763         }
00764     }
00765     long PTUFree::getCurrentUsedMaximumPanPositionLimit() {
00766         std::string command = "px ";
00767         std::string response = communicate(command);
00768         std::vector<std::string> response_parts = evaluateResponse(response);
00769         if(response_parts[0].at(0) == '*') {
00770             return boost::lexical_cast<long>(response_parts[2]);
00771         }
00772         else {
00773             printf("Error while getting currently used maximum pan position limit: %s\n", response_parts[1].c_str());
00774             return ERROR;
00775         }
00776     }
00777     long PTUFree::getCurrentUsedMinimumTiltPositionLimit() {
00778         std::string command = "tn ";
00779         std::string response = communicate(command);
00780         std::vector<std::string> response_parts = evaluateResponse(response);
00781         if(response_parts[0].at(0) == '*') {
00782             return boost::lexical_cast<long>(response_parts[2]);
00783         }
00784         else {
00785             printf("Error while getting currently used minimum tilt position limit: %s\n", response_parts[1].c_str());
00786             return ERROR;
00787         }
00788     }
00789     long PTUFree::getCurrentUsedMaximumTiltPositionLimit() {
00790         std::string command = "tx ";
00791         std::string response = communicate(command);
00792         std::vector<std::string> response_parts = evaluateResponse(response);
00793         if(response_parts[0].at(0) == '*') {
00794             return boost::lexical_cast<long>(response_parts[2]);
00795         }
00796         else {
00797             printf("Error while getting currently used maximum tilt position limit: %s\n", response_parts[1].c_str());
00798             return ERROR;
00799         }
00800     }
00801 
00802 
00803 
00804     long PTUFree::getPositionLimitEnforcementMode() {
00805         std::string command = "l ";
00806         std::string response = communicate(command);
00807         std::vector<std::string> response_parts = evaluateResponse(response);
00808         if(response.at(0) == '*') {
00809             if(response_parts[1].find("DISABLED") != std::string::npos) {
00810                 return LIMITS_DISABLED;
00811             }
00812             else if (response_parts[1].find("user") != std::string::npos) {
00813                 return USER_DEFINED_LIMITS_ENABLED;
00814             }
00815             else {
00816                 return FACTORY_LIMITS_ENABLED;
00817             }
00818         }
00819         else {
00820             printf("Error while getting currently used limit enforcement mode, %s\n", response_parts[1].c_str());
00821             return ERROR;
00822         }
00823     }
00824 
00825     bool PTUFree::setPositionExecutionMode(long mode) {
00826         std::string command;
00827         long new_mode;
00828         if(mode == IMMEDIATE_POSITION_EXECUTION_MODE) {
00829             command = "i ";
00830             new_mode = IMMEDIATE_POSITION_EXECUTION_MODE;
00831         }
00832         else if (mode == SLAVED_POSITION_EXECUTION_MODE) {
00833             command = "s ";
00834             new_mode = SLAVED_POSITION_EXECUTION_MODE;
00835         }
00836         else {
00837             printf("Error while setting position execution mode: Unknown mode\n");
00838             return false;
00839         }
00840         std::string response = communicate(command);
00841         std::vector<std::string> response_parts = evaluateResponse(response);
00842         if(response_parts[0].at(0) == '*') {
00843             position_execution_mode = new_mode;
00844             return true;
00845         }
00846         else {
00847             printf("Error while setting position execution mode: %s\n", response_parts[1].c_str());
00848             return false;
00849         }
00850     }
00851 
00852 
00853     //no method found on ptu interface to get this mode
00854     long PTUFree::getPositionExecutionMode() {
00855         return position_execution_mode;
00856     }
00857 
00858     //PTU waits until last position command is fully executed
00859     bool PTUFree::awaitPositionCommandCompletion() {
00860         std::string command = "a ";
00861         std::string response = communicate(command);
00862         std::vector<std::string> response_parts = evaluateResponse(response);
00863         if(response_parts[0].at(0) == '*') {
00864             return true;
00865         }
00866         else {
00867             printf("Error while awaiting command completion: %s\n", response_parts[1].c_str());
00868             return false;
00869         }
00870     }
00871 
00872     bool PTUFree::halt(long axis) {
00873         std::string command;
00874         if(axis == HALT_PAN_ONLY) {
00875             command = "hp ";
00876         }
00877         else if (axis == HALT_TILT_ONLY) {
00878             command = "ht ";
00879         }
00880         else if (axis == HALT_BOTH) {
00881             command = "h ";
00882         }
00883         else {
00884             printf("Error while halting axis: Unknown mode\n");
00885             return false;
00886         }
00887         std::string response = communicate(command);
00888         std::vector<std::string> response_parts = evaluateResponse(response);
00889         if(response_parts[0].at(0) == '*') {
00890             return true;
00891         }
00892         else {
00893             printf("Error while halting axis: %s\n", response_parts[1].c_str());
00894             return false;
00895         }
00896     }
00897 
00898     //Typical errors (e.g. pan/tilt out of bounds) get handled properly, untypical errors can not be handled really well due to the usage of serial port, in that case false is returned to indicate the error
00899     //and the functions print the kind of error to console.
00900     bool PTUFree::setDesiredPanTiltPositionAbsoluteSlaved(short int pan, short int tilt) {
00901         long previous_mode = getPositionExecutionMode();
00902         bool worked = setPositionExecutionMode(SLAVED_POSITION_EXECUTION_MODE);
00903         if(!worked) {
00904             return false;
00905         }
00906         short int prev_pan = getDesiredPanPosition();
00907         worked = setDesiredPanPositionAbsolute(pan);
00908         if(!worked) {
00909             setPositionExecutionMode(previous_mode);
00910             return false;
00911         }
00912         short int prev_tilt = getDesiredTiltPosition();
00913         worked = setDesiredTiltPositionAbsolute(tilt);
00914         if(!worked) {
00915             setDesiredPanPositionAbsolute(prev_pan);
00916             setPositionExecutionMode(previous_mode);
00917             return false;
00918         }
00919         worked = awaitPositionCommandCompletion();
00920         if(!worked) {
00921             setDesiredPanPositionAbsolute(prev_pan);
00922             setDesiredTiltPositionAbsolute(prev_tilt);
00923             setPositionExecutionMode(previous_mode);
00924             return false;
00925         }
00926         worked = setPositionExecutionMode(previous_mode);
00927         if(!worked) {
00928             return false;
00929         }
00930         return true;
00931     }
00932 
00933 
00934 
00935     //WARNING: NOT SUPPORTED IN OLDER PTU VERSIONS, NOT TESTED (PTU VERSION TOO OLD)
00936     bool PTUFree::setPreset(int preset_index, short int pan, short int tilt) {
00937         short int prev_pan = getDesiredPanPosition();
00938         if(!setDesiredPanPositionAbsolute(pan)) {
00939             return false;
00940         }
00941         if(!setDesiredTiltPositionAbsolute(tilt)) {
00942             setDesiredPanPositionAbsolute(prev_pan);
00943             return false;
00944         }
00945         awaitPositionCommandCompletion();
00946         return setPreset(preset_index);
00947 
00948     }
00949 
00950 
00951     //WARNING: NOT SUPPORTED IN OLDER PTU VERSIONS, NOT TESTED (PTU VERSION TOO OLD)
00952     bool PTUFree::setPreset(int preset_index) {
00953         if((0 > preset_index) || (preset_index > 32)) {
00954             return false;
00955         }
00956         std::string command = "xs" + boost::lexical_cast<std::string>(preset_index) + " ";
00957         std::string response = communicate(command);
00958         std::vector<std::string> response_parts = evaluateResponse(response);
00959         if(response_parts[0].at(0) == '*') {
00960             return true;
00961         }
00962         else {
00963             printf("Error while setting position preset: %s\n", response_parts[1].c_str());
00964             return false;
00965         }
00966     }
00967 
00968     //WARNING: NOT SUPPORTED IN OLDER PTU VERSIONS, NOT TESTED (PTU VERSION TOO OLD)
00969     bool PTUFree::gotoPreset(int preset_index) {
00970         std::string command = "xg" + boost::lexical_cast<std::string>(preset_index) + " ";
00971         std::string response = communicate(command);
00972         std::vector<std::string> response_parts = evaluateResponse(response);
00973         if(response_parts[0].at(0) == '*') {
00974             return true;
00975         }
00976         else {
00977             printf("Error while going to position preset: %s\n", response_parts[1].c_str());
00978             return false;
00979         }
00980     }
00981 
00982     //WARNING: NOT SUPPORTED IN OLDER PTU VERSIONS, NOT TESTED (PTU VERSION TOO OLD)
00983     bool PTUFree::clearPreset() {
00984         std::string command = "xc ";
00985         std::string response = communicate(command);
00986         std::vector<std::string> response_parts = evaluateResponse(response);
00987         if(response_parts[0].at(0) == '*') {
00988             return true;
00989         }
00990         else {
00991             printf("Error while clearing position presets: %s\n", response_parts[1].c_str());
00992             return false;
00993         }
00994     }
00995 
00996     bool PTUFree::setSpeedControlMode(long mode) {
00997         std::string command;
00998         if(mode == INDEPENDENT_SPEED_MODE) {
00999             command = "ci ";
01000         }
01001         else if (mode == PURE_VELOCITY_CONTROL_MODE) {
01002             command = "cv ";
01003         }
01004         else {
01005             printf("Error while setting speed control mode: Unknown command\n");
01006             return false;
01007         }
01008         std::string response = communicate(command);
01009         std::vector<std::string> response_parts = evaluateResponse(response);
01010         if(response_parts[0].at(0) == '*') {
01011             return true;
01012         }
01013         else {
01014             printf("Error while setting speed control mode: %s\n", response_parts[1].c_str());
01015             return false;
01016         }
01017     }
01018 
01019 
01020     long PTUFree::getSpeedControlMode() {
01021         std::string command = "c ";
01022         std::string response = communicate(command);
01023         std::vector<std::string> response_parts = evaluateResponse(response);
01024         if(response_parts[0].at(0) == '*') {
01025             if(response_parts[1].find("independent") != std::string::npos) {
01026                 return INDEPENDENT_SPEED_MODE;
01027             }
01028             else {
01029                 return PURE_VELOCITY_CONTROL_MODE;
01030             }
01031         }
01032         else {
01033             printf("Error while getting speed control mode: %s\n", response_parts[1].c_str());
01034             return ERROR;
01035         }
01036     }
01037 
01038     bool PTUFree::reset() {
01039         std::string command = "r ";
01040         std::string response = communicate(command);
01041         printf("RESET MESSAGE: %s\n", response.c_str());
01042         std::vector<std::string> response_parts = evaluateResponse(response);
01043         if(response_parts[0].at(0) == '*') {
01044             return true;
01045         }
01046         else {
01047             printf("Error while resetting the ptu unit: %s\n", response_parts[1].c_str());
01048             return false;
01049         }
01050     }
01051 
01052     bool PTUFree::setResetMode(long mode) {
01053         std::string command;
01054         if(mode == NO_RESET_MODE) {
01055             command = "rd ";
01056         }
01057         else if (mode == PAN_ONLY_RESET_MODE) {
01058             command = "rp ";
01059         }
01060         else if (mode == TILT_ONLY_RESET_MODE) {
01061             command = "rt ";
01062         }
01063         else if (mode == BOTH_RESET_MODE) {
01064             command = "re ";
01065         }
01066         else {
01067             printf("Error while setting reset mode: Unknown command\n");
01068             return false;
01069         }
01070         std::string response = communicate(command);
01071         std::vector<std::string> response_parts = evaluateResponse(response);
01072         if(response_parts[0].at(0) == '*') {
01073             return true;
01074         }
01075         else {
01076             printf("Error while setting reset mode: %s\n", response_parts[1].c_str());
01077             return false;
01078         }
01079     }
01080 
01081     bool PTUFree::saveDefault() {
01082         std::string command = "ds ";
01083         std::string response = communicate(command);
01084         std::vector<std::string> response_parts = evaluateResponse(response);
01085         if(response_parts[0].at(0) == '*') {
01086             return true;
01087         }
01088         else {
01089             printf("Error while saving current axis settings as default: %s\n", response_parts[1].c_str());
01090             return false;
01091         }
01092     }
01093 
01094     bool PTUFree::restoreDefault() {
01095         std::string command = "dr ";
01096         std::string response = communicate(command);
01097         std::vector<std::string> response_parts = evaluateResponse(response);
01098         if(response_parts[0].at(0) == '*') {
01099             return true;
01100         }
01101         else {
01102             printf("Error while restoring default axis settings: %s\n", response_parts[1].c_str());
01103             return false;
01104         }
01105     }
01106 
01107     bool PTUFree::restoreFactoryDefault() {
01108         std::string command = "df ";
01109         std::string response = communicate(command);
01110         std::vector<std::string> response_parts = evaluateResponse(response);
01111         if(response_parts[0].at(0) == '*') {
01112             return true;
01113         }
01114         else {
01115             printf("Error while restoring factory default axis settings: %s\n", response_parts[1].c_str());
01116             return false;
01117         }
01118     }
01119 
01120     bool PTUFree::setPanStationaryPowerMode(long mode) {
01121         std::string command;
01122         if(mode == REGULAR_HOLD_POWER_MODE) {
01123             command = "phr ";
01124         }
01125         else if (mode == LOW_HOLD_POWER_MODE) {
01126             command = "phl ";
01127         }
01128         else if (mode == OFF_HOLD_POWER_MODE) {
01129             command = "pho ";
01130         }
01131         else {
01132             printf("Error while setting pan stationary power mode: Unknown command\n");
01133             return false;
01134         }
01135         std::string response = communicate(command);
01136         std::vector<std::string> response_parts = evaluateResponse(response);
01137         if(response_parts[0].at(0) == '*') {
01138             return true;
01139         }
01140         else {
01141             printf("Error while setting pan stationary power mode: %s\n", response_parts[1].c_str());
01142             return false;
01143         }
01144     }
01145 
01146     bool PTUFree::setTiltStationaryPowerMode(long mode) {
01147         std::string command;
01148         if(mode == REGULAR_HOLD_POWER_MODE) {
01149             command = "thr ";
01150         }
01151         else if (mode == LOW_HOLD_POWER_MODE) {
01152             command = "thl ";
01153         }
01154         else if (mode == OFF_HOLD_POWER_MODE) {
01155             command = "tho ";
01156         }
01157         else {
01158             printf("Error while setting pan stationary power mode: Unknown command\n");
01159             return false;
01160         }
01161         std::string response = communicate(command);
01162         std::vector<std::string> response_parts = evaluateResponse(response);
01163         if(response_parts[0].at(0) == '*') {
01164             return true;
01165         }
01166         else {
01167             printf("Error while setting pan stationary power mode: %s\n", response_parts[1].c_str());
01168             return false;
01169         }
01170     }
01171 
01172     long PTUFree::getPanStationaryPowerMode() {
01173         std::string command = "ph ";
01174         std::string response = communicate(command);
01175         std::vector<std::string> response_parts = evaluateResponse(response);
01176         if(response_parts[0].at(0) == '*') {
01177             if(response_parts[1].find("REGULAR") != std::string::npos) {
01178                 return REGULAR_HOLD_POWER_MODE;
01179             }
01180             if(response_parts[1].find("LOW") != std::string::npos) {
01181                 return LOW_HOLD_POWER_MODE;
01182             }
01183             else {
01184                 return OFF_HOLD_POWER_MODE;
01185             }
01186         }
01187         else {
01188             printf("Error while getting pan stationary power mode: %s\n", response_parts[1].c_str());
01189             return ERROR;
01190         }
01191     }
01192     long PTUFree::getTiltStationaryPowerMode() {
01193         std::string command = "th ";
01194         std::string response = communicate(command);
01195         std::vector<std::string> response_parts = evaluateResponse(response);
01196         if(response_parts[0].at(0) == '*') {
01197             if(response_parts[1].find("REGULAR") != std::string::npos) {
01198                 return REGULAR_HOLD_POWER_MODE;
01199             }
01200             if(response_parts[1].find("LOW") != std::string::npos) {
01201                 return LOW_HOLD_POWER_MODE;
01202             }
01203             else {
01204                 return OFF_HOLD_POWER_MODE;
01205             }
01206         }
01207         else {
01208             printf("Error while getting tilt stationary power mode: %s\n", response_parts[1].c_str());
01209             return ERROR;
01210         }
01211     }
01212 
01213     bool PTUFree::setPanInMotionPowerMode(long mode) {
01214         std::string command;
01215         if(mode == HIGH_MOVE_POWER_MODE) {
01216             command = "pmh ";
01217         }
01218         else if (mode == REGULAR_MOVE_POWER_MODE) {
01219             command = "pmr ";
01220         }
01221         else if (mode == LOW_MOVE_POWER_MODE) {
01222             command = "pml ";
01223         }
01224         else {
01225             printf("Error while setting pan in-motion power mode: Unknown command\n");
01226             return false;
01227         }
01228         std::string response = communicate(command);
01229         std::vector<std::string> response_parts = evaluateResponse(response);
01230         if(response_parts[0].at(0) == '*') {
01231             return true;
01232         }
01233         else {
01234             printf("Error while setting pan in-motion power mode: %s\n", response_parts[1].c_str());
01235             return false;
01236         }
01237     }
01238     bool PTUFree::setTiltInMotionPowerMode(long mode) {
01239         std::string command;
01240         if(mode == HIGH_MOVE_POWER_MODE) {
01241             command = "tmh ";
01242         }
01243         else if (mode == REGULAR_MOVE_POWER_MODE) {
01244             command = "tmr ";
01245         }
01246         else if (mode == LOW_MOVE_POWER_MODE) {
01247             command = "tml ";
01248         }
01249         else {
01250             printf("Error while setting tilt in-motion power mode: Unknown command\n");
01251             return false;
01252         }
01253         std::string response = communicate(command);
01254         std::vector<std::string> response_parts = evaluateResponse(response);
01255         if(response_parts[0].at(0) == '*') {
01256             return true;
01257         }
01258         else {
01259             printf("Error while setting tilt in-motion power mode: %s\n", response_parts[1].c_str());
01260             return false;
01261         }
01262     }
01263 
01264     long PTUFree::getPanInMotionPowerMode() {
01265         std::string command = "pm ";
01266         std::string response = communicate(command);
01267         std::vector<std::string> response_parts = evaluateResponse(response);
01268         if(response_parts[0].at(0) == '*') {
01269             if(response_parts[1].find("REGULAR") != std::string::npos) {
01270                 return REGULAR_MOVE_POWER_MODE;
01271             }
01272             if(response_parts[1].find("LOW") != std::string::npos) {
01273                 return LOW_MOVE_POWER_MODE;
01274             }
01275             else {
01276                 return HIGH_MOVE_POWER_MODE;
01277             }
01278         }
01279         else {
01280             printf("Error while getting pan in-motion power mode: %s\n", response_parts[1].c_str());
01281             return ERROR;
01282         }
01283     }
01284     long PTUFree::getTiltInMotionPowerMode() {
01285         std::string command = "tm ";
01286         std::string response = communicate(command);
01287         std::vector<std::string> response_parts = evaluateResponse(response);
01288         if(response_parts[0].at(0) == '*') {
01289             if(response_parts[1].find("REGULAR") != std::string::npos) {
01290                 return REGULAR_MOVE_POWER_MODE;
01291             }
01292             if(response_parts[1].find("LOW") != std::string::npos) {
01293                 return LOW_MOVE_POWER_MODE;
01294             }
01295             else {
01296                 return HIGH_MOVE_POWER_MODE;
01297             }
01298         }
01299         else {
01300             printf("Error while getting tilt in-motion power mode: %s\n", response_parts[1].c_str());
01301             return ERROR;
01302         }
01303     }
01304 
01305     std::string PTUFree::getErrorString(boost::system::error_code error) {
01306         switch (error.value()) {
01307             case boost::system::errc::success: {
01308                 return "success";
01309             }
01310             break;
01311             case boost::system::errc::address_family_not_supported: {
01312                 return "address_family_not_supported | EAFNOSUPPORT";
01313             }
01314             break;
01315             case boost::system::errc::address_in_use: {
01316                 return "address_in_use | EADDRINUSE";
01317             }
01318             break;
01319             case boost::system::errc::address_not_available: {
01320                 return "address_not_available | EADDRNOTAVAIL";
01321             }
01322             break;
01323             case boost::system::errc::already_connected: {
01324                 return "already_connected | EISCONN";
01325             }
01326             break;
01327             case boost::system::errc::argument_list_too_long: {
01328                 return "argument_list_too_long | E2BIG";
01329             }
01330             break;
01331             case boost::system::errc::argument_out_of_domain: {
01332                 return "argument_out_of_domain | EDOM";
01333             }
01334             break;
01335             case boost::system::errc::bad_address: {
01336                 return "bad_address | EFAULT";
01337             }
01338             break;
01339             case boost::system::errc::bad_file_descriptor: {
01340                 return "bad_file_descriptor | EBADF";
01341             }
01342             break;
01343             case boost::system::errc::bad_message: {
01344                 return "bad_message | EBADMSG";
01345             }
01346             break;
01347             case boost::system::errc::broken_pipe: {
01348                 return "broken_pipe | EPIPE";
01349             }
01350             break;
01351             case boost::system::errc::connection_aborted: {
01352                 return "connection_aborted | ECONNABORTED";
01353             }
01354             break;
01355             case boost::system::errc::connection_already_in_progress: {
01356                 return "connection_already_in_progress | EALREADY";
01357             }
01358             break;
01359             case boost::system::errc::connection_refused: {
01360                 return "connection_refused | ECONNREFUSED";
01361             }
01362             break;
01363             case boost::system::errc::connection_reset: {
01364                 return "connection_reset | ECONNRESET";
01365             }
01366             break;
01367             case boost::system::errc::cross_device_link: {
01368                 return "cross_device_link | EXDEV";
01369             }
01370             break;
01371             case boost::system::errc::destination_address_required: {
01372                 return "destination_address_required | EDESTADDRREQ";
01373             }
01374             break;
01375             case boost::system::errc::device_or_resource_busy: {
01376                 return "device_or_resource_busy | EBUSY";
01377             }
01378             break;
01379             case boost::system::errc::directory_not_empty: {
01380                 return "directory_not_empty | ENOTEMPTY";
01381             }
01382             break;
01383             case boost::system::errc::executable_format_error: {
01384                 return "executable_format_error | ENOEXEC";
01385             }
01386             break;
01387             case boost::system::errc::file_exists: {
01388                 return "file_exists | EEXIST";
01389             }
01390             break;
01391             case boost::system::errc::file_too_large: {
01392                 return "file_too_large | EFBIG";
01393             }
01394             break;
01395             case boost::system::errc::filename_too_long: {
01396                 return "filename_too_long | ENAMETOOLONG";
01397             }
01398             break;
01399             case boost::system::errc::function_not_supported: {
01400                 return "function_not_supported | ENOSYS";
01401             }
01402             break;
01403             case boost::system::errc::host_unreachable: {
01404                 return "host_unreachable | EHOSTUNREACH";
01405             }
01406             break;
01407             case boost::system::errc::identifier_removed: {
01408                 return "identifier_removed | EIDRM";
01409             }
01410             break;
01411             case boost::system::errc::illegal_byte_sequence: {
01412                 return "illegal_byte_sequence | EILSEQ";
01413             }
01414             break;
01415             case boost::system::errc::inappropriate_io_control_operation: {
01416                 return "inappropriate_io_control_operation | ENOTTY";
01417             }
01418             break;
01419             case boost::system::errc::interrupted: {
01420                 return "interrupted | EINTR";
01421             }
01422             break;
01423             case boost::system::errc::invalid_argument: {
01424                 return "invalid_argument | EINVAL";
01425             }
01426             break;
01427             case boost::system::errc::invalid_seek: {
01428                 return "invalid_seek | ESPIPE";
01429             }
01430             break;
01431             case boost::system::errc::io_error: {
01432                 return "io_error | EIO";
01433             }
01434             break;
01435             case boost::system::errc::is_a_directory: {
01436                 return "is_a_directory | EISDIR";
01437             }
01438             break;
01439             case boost::system::errc::message_size: {
01440                 return "message_size | EMSGSIZE";
01441             }
01442             break;
01443             case boost::system::errc::network_down: {
01444                 return "network_down | ENETDOWN";
01445             }
01446             break;
01447             case boost::system::errc::network_reset: {
01448                 return "network_reset | ENETRESET";
01449             }
01450             break;
01451             case boost::system::errc::network_unreachable: {
01452                 return "network_unreachable | ENETUNREACH";
01453             }
01454             break;
01455             case boost::system::errc::no_buffer_space: {
01456                 return "no_buffer_space | ENOBUFS";
01457             }
01458             break;
01459             case boost::system::errc::no_child_process: {
01460                 return "no_child_process | ECHILD";
01461             }
01462             break;
01463             case boost::system::errc::no_link: {
01464                 return "no_link | ENOLINK";
01465             }
01466             break;
01467             case boost::system::errc::no_lock_available: {
01468                 return "no_lock_available | ENOLCK";
01469             }
01470             break;
01471             case boost::system::errc::no_message_available: {
01472                 return "no_message_available | ENODATA";
01473             }
01474             break;
01475             case boost::system::errc::no_message: {
01476                 return "no_message | ENOMSG";
01477             }
01478             break;
01479             case boost::system::errc::no_protocol_option: {
01480                 return "no_protocol_option | ENOPROTOOPT";
01481             }
01482             break;
01483             case boost::system::errc::no_space_on_device: {
01484                 return "no_space_on_device | ENOSPC";
01485             }
01486             break;
01487             case boost::system::errc::no_stream_resources: {
01488                 return "no_stream_resources | ENOSR";
01489             }
01490             break;
01491             case boost::system::errc::no_such_device_or_address: {
01492                 return "no_such_device_or_address | ENXIO";
01493             }
01494             break;
01495             case boost::system::errc::no_such_device: {
01496                 return "no_such_device | ENODEV";
01497             }
01498             break;
01499             case boost::system::errc::no_such_file_or_directory: {
01500                 return "no_such_file_or_directory | ENOENT";
01501             }
01502             break;
01503             case boost::system::errc::no_such_process: {
01504                 return "no_such_process | ESRCH";
01505             }
01506             break;
01507             case boost::system::errc::not_a_directory: {
01508                 return "not_a_directory | ENOTDIR";
01509             }
01510             break;
01511             case boost::system::errc::not_a_socket: {
01512                 return "not_a_socket | ENOTSOCK";
01513             }
01514             break;
01515             case boost::system::errc::not_a_stream: {
01516                 return "not_a_stream | ENOSTR";
01517             }
01518             break;
01519             case boost::system::errc::not_connected: {
01520                 return "not_connected | ENOTCONN";
01521             }
01522             break;
01523             case boost::system::errc::not_enough_memory: {
01524                 return "not_enough_memory | ENOMEM";
01525             }
01526             break;
01527             case boost::system::errc::not_supported: {
01528                 return "not_supported | ENOTSUP";
01529             }
01530             break;
01531             case boost::system::errc::operation_canceled: {
01532                 return "operation_canceled | ECANCELED";
01533             }
01534             break;
01535             case boost::system::errc::operation_in_progress: {
01536                 return "operation_in_progress | EINPROGRESS";
01537             }
01538             break;
01539             case boost::system::errc::operation_not_permitted: {
01540                 return "operation_not_permitted | EPERM";
01541             }
01542             break;
01543             //Uses internal same error code as operation_not_supported
01544             //case boost::system::errc::operation_not_supported: {
01545             //    return "operation_not_supported | EOPNOTSUPP";
01546             //}
01547             //break;
01548             //Uses internal same error code as recources_unavailable_try_again
01549             //case boost::system::errc::operation_would_block: {
01550             //    return "operation_would_block | EWOULDBLOCK";
01551             //}
01552             //break;
01553             case boost::system::errc::owner_dead: {
01554                 return "owner_dead | EOWNERDEAD";
01555             }
01556             break;
01557             case boost::system::errc::permission_denied: {
01558                 return "permission_denied | EACCES";
01559             }
01560             break;
01561             case boost::system::errc::protocol_error: {
01562                 return "protocol_error | EPROTO";
01563             }
01564             break;
01565             case boost::system::errc::protocol_not_supported: {
01566                 return "protocol_not_supported | EPROTONOSUPPORT";
01567             }
01568             break;
01569             case boost::system::errc::read_only_file_system: {
01570                 return "read_only_file_system | EROFS";
01571             }
01572             break;
01573             case boost::system::errc::resource_deadlock_would_occur: {
01574                 return "resource_deadlock_would_occur | EDEADLK";
01575             }
01576             break;
01577             case boost::system::errc::resource_unavailable_try_again: {
01578                 return "resource_unavailable_try_again | EAGAIN";
01579             }
01580             break;
01581             case boost::system::errc::result_out_of_range: {
01582                 return "result_out_of_range | ERANGE";
01583             }
01584             break;
01585             case boost::system::errc::state_not_recoverable: {
01586                 return "state_not_recoverable | ENOTRECOVERABLE";
01587             }
01588             break;
01589             case boost::system::errc::stream_timeout: {
01590                 return "stream_timeout | ETIME";
01591             }
01592             break;
01593             case boost::system::errc::text_file_busy: {
01594                 return "text_file_busy | ETXTBSY";
01595             }
01596             break;
01597             case boost::system::errc::timed_out: {
01598                 return "timed_out | ETIMEDOUT";
01599             }
01600             break;
01601             case boost::system::errc::too_many_files_open_in_system: {
01602                 return "too_many_files_open_in_system | ENFILE";
01603             }
01604             break;
01605             case boost::system::errc::too_many_files_open: {
01606                 return "too_many_files_open | EMFILE";
01607             }
01608             break;
01609             case boost::system::errc::too_many_links: {
01610                 return "too_many_links | EMLINK";
01611             }
01612             break;
01613             //Most likely not available in current boost version (compiler error)
01614             //case boost::system::errc::too_many_synbolic_link_levels: {
01615             //    return "too_many_synbolic_link_levels | ELOOP";
01616             //}
01617             //break;
01618             case boost::system::errc::value_too_large: {
01619                 return "value_too_large | EOVERFLOW";
01620             }
01621             break;
01622             case boost::system::errc::wrong_protocol_type: {
01623                 return "wrong_protocol_type | EPROTOTYPE";
01624             }
01625             break;
01626             default: {
01627                 return "unknown error";
01628             }
01629             break;
01630         }
01631     }
01632 
01633     void PTUFree::test() {
01634 
01635             long pan_pos = getCurrentPanPosition();
01636             if(pan_pos != 0) {
01637                 printf("Error getting initial pan position. Expected 0, got %ld\n", pan_pos);
01638                 return;
01639             }
01640 
01641             if(!setDesiredPanPositionAbsolute(300)) {
01642                 printf("Error while setting pan position to 300");
01643                 return;
01644             }
01645 
01646             long desired_pan_position = getDesiredPanPosition();
01647             if(desired_pan_position != 300) {
01648                     printf("Error while setting or getting (desired) pan position. Expected 300, desired %ld", desired_pan_position);
01649                     return;
01650             }
01651 
01652             pan_pos = getCurrentPanPosition();
01653             if((pan_pos < 0) || (pan_pos >= 300)) {
01654                 printf("Error getting pan position while ptu is moving position. Expected value between 0 and 300, got %ld\n", pan_pos);
01655                 if(pan_pos == 300) {
01656                     printf("Pan Position was 300 but it should not be at the moment. This can also happen due to to slow serial port or sceduling, testing will be continued therefore.");
01657                 }
01658                 else {
01659                     return;
01660                 }
01661             }
01662 
01663             pan_pos = getCurrentPanPosition();
01664             if((pan_pos < 0) || (pan_pos >= 300)) {
01665                 printf("Error getting pan position while ptu is moving position. Expected value between 0 and 300, got %ld\n", pan_pos);
01666                 if(pan_pos == 300) {
01667                     printf("Pan Position was 300 but it should not be at the moment. This can also happen due to to slow serial port or sceduling, testing will be continued therefore.");
01668                 }
01669                 else {
01670                     return;
01671                 }
01672             }
01673 
01674             if(!awaitPositionCommandCompletion()) {
01675                 printf("Execution of await command failed");
01676                 return;
01677             }
01678 
01679             pan_pos = getCurrentPanPosition();
01680             if((pan_pos != 300)) {
01681                 printf("Setting pan position, getting pan position or await command failed. Expected pan position 300, but got %ld\n", pan_pos);
01682                 return;
01683             }
01684 
01685             long tilt_pos = getCurrentTiltPosition();
01686             if(tilt_pos != 0) {
01687                 printf("Error getting initial tilt position. Expected 0, got %ld\n", tilt_pos);
01688                 return;
01689             }
01690 
01691             if(!setDesiredTiltPositionAbsolute(-350)) {
01692                 printf("Error while setting tilt position to -350");
01693                 return;
01694             }
01695 
01696             long desired_tilt_position = getDesiredTiltPosition();
01697             if(desired_tilt_position != -350) {
01698                     printf("Error while setting or getting (desired) tilt position. Expected -350, desired %ld", desired_tilt_position);
01699                     return;
01700             }
01701 
01702 
01703             tilt_pos = getCurrentTiltPosition();
01704             if((tilt_pos > 0) || (tilt_pos <= -350)) {
01705                 printf("Error getting tilt position while ptu is moving position. Expected value between 0 and -350, got %ld\n", tilt_pos);
01706                 if(pan_pos == -350) {
01707                     printf("Tilt Position was -350 but it should not be at the moment. This can also happen due to to slow serial port or sceduling, testing will be continued therefore.");
01708                 }
01709                 else {
01710                     return;
01711                 }
01712             }
01713 
01714             tilt_pos = getCurrentTiltPosition();
01715             if((tilt_pos > 0) || (tilt_pos <= -350)) {
01716                 printf("Error getting tilt position while ptu is moving position. Expected value between 0 and -350, got %ld\n", tilt_pos);
01717                 if(tilt_pos == -350) {
01718                     printf("Tilt Position was -350 but it should not be at the moment. This can also happen due to to slow serial port or sceduling, testing will be continued therefore.");
01719                 }
01720                 else {
01721                     return;
01722                 }
01723             }
01724 
01725             if(!awaitPositionCommandCompletion()) {
01726                 printf("Execution of await command failed");
01727                 return;
01728             }
01729 
01730             tilt_pos = getCurrentTiltPosition();
01731             if((tilt_pos != -350)) {
01732                 printf("Setting tilt position, getting tilt position or await command failed. Expected tilt position -350, but got %ld\n", tilt_pos);
01733                 return;
01734             }
01735 
01736             if(!setDesiredPanPositionRelative(100)) {
01737                 printf("Setting pan position realtiv failed.");
01738                 return;
01739             }
01740 
01741             if(!awaitPositionCommandCompletion()) {
01742                 printf("Execution of await command failed");
01743                 return;
01744             }
01745 
01746             pan_pos = getCurrentPanPosition();
01747             if(pan_pos != 400) {
01748                 printf("After setting relative pan position, position == 400 was expected, but position was %ld\n", pan_pos);
01749             }
01750 
01751 
01752             if(!setDesiredTiltPositionRelative(100)) {
01753                 printf("Setting pan position realtiv failed.");
01754                 return;
01755             }
01756 
01757             if(!awaitPositionCommandCompletion()) {
01758                 printf("Execution of await command failed");
01759                 return;
01760             }
01761 
01762             tilt_pos = getCurrentTiltPosition();
01763             if(tilt_pos != -250) {
01764                 printf("After setting relative pan position, position == -250 was expected, but position was %ld\n", tilt_pos);
01765             }
01766 
01767 
01768 
01769             printf("SUCCESS: Setting pan and tilt testing successfull\n");
01770 
01771 
01772 
01773             if(!setPositionLimitEnforcementMode(FACTORY_LIMITS_ENABLED)) {
01774                 printf("Setting position limit enforcement to factory limits enabled failed\n");
01775                 return;
01776             }
01777             //some of those methods can take a while
01778             sleep(6);
01779             long limit_enforcement_mode = getPositionLimitEnforcementMode();
01780             if(limit_enforcement_mode != FACTORY_LIMITS_ENABLED) {
01781                 if(limit_enforcement_mode == USER_DEFINED_LIMITS_ENABLED) {
01782                     printf("setPositionLimitEnforcementMode or the corresponding get method failed. FACOTRY_LIMITS_ENABLED was expected, USER_DEFINED_LIMITS_ENABLE was retrieved\n");
01783                 }
01784                 else if (limit_enforcement_mode == LIMITS_DISABLED) {
01785                     printf("setPositionLimitEnforcementMode or the corresponding get method failed. FACOTRY_LIMITS_ENABLED was expected, LIMITS_DISABLED was retrieved\n");
01786                 }
01787                 else if(limit_enforcement_mode == ERROR) {
01788                     printf("getPositionLimitEnforcementMode failed with ERROR\n");
01789                 }
01790                 else {
01791                     printf("get_posiion_limit_enforcement_mode returned unexpected value after setting FACTORY_LIMITS_ENABLED\n");
01792                 }
01793                 return;
01794             }
01795 
01796 
01797             long pan_upper_limit = getFactoryMaximumPanPositionLimit();
01798             long pan_lower_limit = getFactoryMinimumPanPositionLimit();
01799             long tilt_upper_limit = getFactoryMaximumTiltPositionLimit();
01800             long tilt_lower_limit = getFactoryMinimumTiltPositionLimit();
01801 
01802             //The following also tells if the get_current methods with Factory Limits work, because the values returned by get_factory... are recieved from that function at launch
01803             if(pan_upper_limit == ERROR) {
01804                 printf("Function getCurrentUsedMaximumPanPositionLimit returned ERROR when used in FACTORY_LIMITS_ENABLES position enforcement mode\n");
01805                 return;
01806             }
01807             if(pan_lower_limit == ERROR) {
01808                 printf("Function getCurrentUsedMinimumPanPositionLimit returned ERROR when used in FACTORY_LIMITS_ENABLES position enforcement mode\n");
01809                 return;
01810             }
01811             if(tilt_upper_limit == ERROR) {
01812                 printf("Function getCurrentUsedMaximumTiltPositionLimit returned ERROR when used in FACTORY_LIMITS_ENABLES position enforcement mode\n");
01813                 return;
01814             }
01815             if(tilt_lower_limit == ERROR) {
01816                 printf("Function getCurrentUsedMinimumTiltPositionLimit returned ERROR when used in FACTORY_LIMITS_ENABLES position enforcement mode\n");
01817                 return;
01818             }
01819 
01820             if(setDesiredPanPositionAbsolute(pan_upper_limit + 1)) {
01821                 printf("FACTORY_LIMITS_ENABLED mode or any of the get functions did not work properly. Trying to move pan unit over the upper limit did not result in error\n");
01822                 return;
01823             }
01824             if(setDesiredPanPositionAbsolute(pan_lower_limit - 1)) {
01825                 printf("FACTORY_LIMITS_ENABLED mode or any of the get functions did not work properly. Trying to move pan unit over the lower limit did not result in error\n");
01826                 return;
01827             }
01828             if(setDesiredTiltPositionAbsolute(tilt_upper_limit + 1)) {
01829                 printf("FACTORY_LIMITS_ENABLED mode or any of the get functions did not work properly. Trying to move tilt unit over the upper limit did not result in error\n");
01830                 return;
01831             }
01832             if(setDesiredTiltPositionAbsolute(tilt_lower_limit - 1)) {
01833                 printf("FACTORY_LIMITS_ENABLED mode or any of the get functions did not work properly. Trying to move tilt unit over the lower limit did not result in error\n");
01834                 return;
01835             }
01836 
01837             sleep(6);
01838             //Does not work on older ptus
01839             /*
01840             if(!setMaximumPanPositionLimit(1000)) {
01841                 printf("Error while setting maximum_pan_position_limit to 1000\n");
01842                 return;
01843             }
01844             if(!setMinimumPanPositionLimit(-1000)) {
01845                 printf("Error while setting minimum_pan_position_limit to -1000\n");
01846                 return;
01847             }
01848             if(!setMinimumTiltPositionLimit(-300)) {
01849                 printf("Error while setting minimum_tilt_position_limit to -300\n");
01850                 return;
01851             }
01852             if(!setMaximumTiltPositionLimit(300)) {
01853                 printf("Error while setting maximum_tilt_position_limit to 300\n");
01854                 return;
01855             }
01856 
01857             sleep(6);
01858 
01859             long min_user_pan_limit = getUserMinimumPanPositionLimit();
01860             long max_user_pan_limit = getUserMaximumPanPositionLimit();
01861             long min_user_tilt_limit = getUserMinimumTiltPositionLimit();
01862             long max_user_tilt_limit = getUserMaximumTiltPositionLimit();
01863             if(min_user_pan_limit != -1000) {
01864                 printf("Error while getting minimum user pan position limit: -1000 expected, got %ld\n", min_user_pan_limit);
01865                 return;
01866             }
01867             if(max_user_pan_limit != 1000) {
01868                 printf("Error while getting maximum user pan position limit: 1000 expected, got %ld\n", max_user_pan_limit);
01869                 return;
01870             }
01871             if(min_user_tilt_limit != -300) {
01872                 printf("Error while getting minimum user tilt position limit: -300 expected, got %ld\n", min_user_tilt_limit);
01873                 return;
01874             }
01875             if(max_user_tilt_limit != 300) {
01876                 printf("Error while getting maximum user tilt position limit: 300 expected, got %ld\n", max_user_tilt_limit);
01877                 return;
01878             }
01879 
01880             if(!setPositionLimitEnforcementMode(USER_DEFINED_LIMITS_ENABLED)) {
01881                 printf("Setting position limit enforcement mode to USER_DEFINED_LIMITS_ENABLED failed");
01882                 return;
01883             }
01884             limit_enforcement_mode = getPositionLimitEnforcementMode();
01885 
01886             if(limit_enforcement_mode != USER_DEFINED_LIMITS_ENABLED) {
01887                 printf("Getting position limit enforcement mode failed. Expected: USER_DEFINED_LIMITS_ENABLED, Got: %ld\n", limit_enforcement_mode);
01888                 return;
01889             }
01890 
01891             long min_current_pan_limit = getCurrentUsedMinimumPanPositionLimit();
01892             long max_current_pan_limit = getCurrentUsedMaximumPanPositionLimit();
01893             long min_current_tilt_limit = getCurrentUsedMinimumTiltPositionLimit();
01894             long max_current_tilt_limit = getCurrentUsedMaximumTiltPositionLimit();
01895             if(min_current_pan_limit != -1000) {
01896                 printf("Error while getting minimum current used pan position limit: -1000 expected, got %ld\n", min_current_pan_limit);
01897                 return;
01898             }
01899             if(max_current_pan_limit != 1000) {
01900                 printf("Error while getting maximum current used pan position limit: 1000 expected, got %ld\n", max_current_pan_limit);
01901                 return;
01902             }
01903             if(min_current_tilt_limit != -300) {
01904                 printf("Error while getting minimum current used tilt position limit: -300 expected, got %ld\n", min_current_tilt_limit);
01905                 return;
01906             }
01907             if(max_current_tilt_limit != 300) {
01908                 printf("Error while getting maximum current used tilt position limit: 300 expected, got %ld\n", max_current_tilt_limit);
01909                 return;
01910             }
01911 
01912 
01913             */
01914             if(!setPositionLimitEnforcementMode(LIMITS_DISABLED)) {
01915                 printf("Setting position limit enforcement mode to LIMITS_DISABLED failed");
01916                 return;
01917             }
01918 
01919             limit_enforcement_mode = getPositionLimitEnforcementMode();
01920 
01921             if(limit_enforcement_mode != LIMITS_DISABLED) {
01922                 printf("Getting position limit enforcement mode failed. Expected: LIMITS_DISABLED, Got: %ld\n", limit_enforcement_mode);
01923                 return;
01924             }
01925 
01926             if(!setDesiredPanPositionAbsolute(4000)) {
01927                 printf("Setting position out of limits with LIMITS_DISABLED failed\n");
01928                 return;
01929             }
01930 
01931             sleep(6);
01932 
01933             setDesiredPanPositionAbsolute(300);
01934 
01935             sleep(6);
01936 
01937             printf("Testing Limit Enforcement succeeded\n");
01938 
01939 
01940             setDesiredPanPositionAbsolute(3000);
01941             awaitPositionCommandCompletion();
01942 
01943 
01944             long cur_pan_speed = getCurrentPanSpeed();
01945             long cur_tilt_speed = getCurrentTiltSpeed();
01946             if(cur_pan_speed != 0) {
01947                 printf("Error while getting current pan speed. 0 expected but got %ld\n", cur_pan_speed);
01948                 return;
01949             }
01950             if(cur_tilt_speed != 0) {
01951                 printf("Error while getting current tilt speed. 0 expected but got %ld\n", cur_tilt_speed);
01952                 return;
01953             }
01954 
01955             long des_pan_speed = getDesiredPanSpeed();
01956             long des_tilt_speed = getDesiredTiltSpeed();
01957             if(des_pan_speed <= 0) {
01958                 printf("Error while getting desired pan speed. Value >= 0 expected but got %ld\n", des_pan_speed);
01959                 return;
01960             }
01961             if(des_tilt_speed <= 0) {
01962                 printf("Error while getting desired tilt speed. Value >= 0 expected but got %ld\n", des_tilt_speed);
01963                 return;
01964             }
01965 
01966             if(!setDesiredPanSpeedAbsolute((des_pan_speed - 1))) {
01967                 printf("Error while setting desired pan speed absolute\n");
01968                 return;
01969             }
01970 
01971             long mod_desired_pan_speed = getDesiredPanSpeed();
01972             if(mod_desired_pan_speed != (des_pan_speed - 1)) {
01973                 printf("Error while getting or setting desired pan speed (absolute set). Expected %ld - 1, but got %ld\n", des_pan_speed, mod_desired_pan_speed);
01974                 return;
01975             }
01976 
01977             if(!setDesiredTiltSpeedAbsolute((des_tilt_speed - 2))) {
01978                 printf("Error while setting desired tilt speed absolute\n");
01979                 return;
01980             }
01981 
01982             long mod_desired_tilt_speed = getDesiredTiltSpeed();
01983             if(mod_desired_tilt_speed != (des_tilt_speed - 2)) {
01984                 printf("Error while getting or setting desired tilt speed (absolute set). Expected %ld - 2, but got %ld\n", des_tilt_speed, mod_desired_tilt_speed);
01985                 return;
01986             }
01987 
01988             //WARNING: OFFSET FROM CURRENT (NOT DESIRED) SPEED IS SET TO DESIRED SPEED (Example: Current speed = 0, Desired Speed = 500. setDesiredPanSpeedRelative will result in
01989             //current speed being 0 and desired speed being 0 + 100 = 100
01990             if(!setDesiredPanSpeedRelative(des_pan_speed - 2)) {
01991                 printf("Error while setting desired pan speed realtive\n");
01992                 return;
01993             }
01994 
01995             mod_desired_pan_speed = getDesiredPanSpeed();
01996             if(mod_desired_pan_speed != (des_pan_speed - 2)) {
01997                 printf("Error while getting or setting desired pan speed (realtive set). Expected %ld - 2, but got %ld\n", des_pan_speed, mod_desired_pan_speed);
01998                 return;
01999             }
02000 
02001             if(!setDesiredTiltSpeedRelative(des_tilt_speed - 4)) {
02002                 printf("Error while setting desired tilt speed relative\n");
02003                 return;
02004             }
02005 
02006             mod_desired_tilt_speed = getDesiredTiltSpeed();
02007             if(mod_desired_tilt_speed != (des_tilt_speed - 4)) {
02008                 printf("Error while getting or setting desired tilt speed (relative set). Expected %ld - 4, but got %ld\n", des_tilt_speed, mod_desired_tilt_speed);
02009                 return;
02010             }
02011 
02012             long upper_limit_pan = getPanUpperSpeedLimit();
02013             long lower_limit_pan = getPanLowerSpeedLimit();
02014             long upper_limit_tilt = getTiltUpperSpeedLimit();
02015             long lower_limit_tilt = getTiltLowerSpeedLimit();
02016 
02017             if(upper_limit_pan == ERROR) {
02018                 printf("Error while getting upper speed limit pan.\n");
02019                 return;
02020             }
02021             if(lower_limit_pan == ERROR) {
02022                 printf("Error while getting lower speed limit pan.\n");
02023                 return;
02024             }
02025             if(upper_limit_tilt == ERROR) {
02026                 printf("Error while getting upper speed limit tilt.\n");
02027                 return;
02028             }
02029             if(lower_limit_tilt == ERROR) {
02030                 printf("Error while getting lower speed limit tilt.\n");
02031                 return;
02032             }
02033 
02034             if(!setDesiredPanUpperSpeedLimit(upper_limit_pan - 1)) {
02035                 printf("Error while setting upper speed limit pan\n");
02036                 return;
02037             }
02038             if(!setDesiredPanLowerSpeedLimit(57)) {
02039                 printf("Error while setting lower speed limit pan\n");
02040                 return;
02041             }
02042             if(!setDesiredTiltUpperSpeedLimit(upper_limit_tilt - 2)) {
02043                 printf("Error while setting upper speed limit tilt\n");
02044                 return;
02045             }
02046             if(!setDesiredTiltLowerSpeedLimit(58)) {
02047                 printf("Error while setting lower speed limit tilt\n");
02048                 return;
02049             }
02050 
02051             //Changing speed bounds is not possible on the fly, needs long break
02052             sleep(6);
02053 
02054             //long mod_upper_limit_pan = getPanUpperSpeedLimit();
02055             long mod_lower_limit_pan = getPanLowerSpeedLimit();
02056             //long mod_upper_limit_tilt = getTiltUpperSpeedLimit();
02057             long mod_lower_limit_tilt = getTiltLowerSpeedLimit();
02058             /*
02059             if(mod_upper_limit_pan != (upper_limit_pan - 1)) {
02060                 printf("Error while getting or setting upper speed limit pan. Expected %ld - 1, but got %ld\n", upper_limit_pan, mod_upper_limit_pan);
02061                 return;
02062             }
02063             */
02064             if(mod_lower_limit_pan != (57)) {
02065                 printf("Error while getting or setting lower speed limit pan. Expected 57, but got %ld\n", mod_lower_limit_pan);
02066                 return;
02067             }
02068             /*
02069             if(mod_upper_limit_tilt != (upper_limit_tilt - 2)) {
02070                 printf("Error while getting or setting upper speed limit tilt. Expected %ld - 2, but got %ld\n", upper_limit_tilt, mod_upper_limit_tilt);
02071                 return;
02072             }
02073             */
02074             if(mod_lower_limit_tilt != (58)) {
02075                 printf("Error while getting or setting lower speed limit tilt. Expected 58, but got %ld\n", mod_lower_limit_tilt);
02076                 return;
02077             }
02078 
02079             long pan_base_speed = getPanBaseSpeed();
02080             long tilt_base_speed = getTiltBaseSpeed();
02081             if(pan_base_speed <= 0) {
02082                 printf("Error while getting pan_base_speed\n");
02083                 return;
02084             }
02085             if(tilt_base_speed <= 0) {
02086                 printf("Error while getting tilt_base_speed\n");
02087                 return;
02088             }
02089             if(!setPanBaseSpeed((pan_base_speed - 1))) {
02090                 printf("Error while setting pan_base_speed\n");
02091                 return;
02092             }
02093             if(!setTiltBaseSpeed((tilt_base_speed - 1))) {
02094                 printf("Error while setting tilt_base_speed\n");
02095                 return;
02096             }
02097             long mod_pan_base_speed = getPanBaseSpeed();
02098             long mod_tilt_base_speed = getTiltBaseSpeed();
02099             if((pan_base_speed - 1) != mod_pan_base_speed) {
02100                 printf("Error while getting pan_base_speed. Expected %ld - 1, got %ld\n", pan_base_speed, mod_pan_base_speed);
02101                 return;
02102             }
02103             if((tilt_base_speed - 1) != mod_tilt_base_speed) {
02104                 printf("Error while getting tilt_base_speed. Expected %ld - 1, got %ld\n", tilt_base_speed, mod_tilt_base_speed);
02105                 return;
02106             }
02107 
02108             long pan_accel = getPanAcceleartion();
02109             long tilt_accel = getTiltAcceleartion();
02110             if(pan_accel <= 0) {
02111                 printf("Error while getting pan acceleration\n");
02112                 return;
02113             }
02114             if(tilt_accel <= 0) {
02115                 printf("Error while getting tilt acceleration\n");
02116                 return;
02117             }
02118             if(!setDesiredPanAccelerationAbsolute((pan_accel - 1))) {
02119                 printf("Setting desired pan acceleration absolute failed\n");
02120                 return;
02121             }
02122             if(!setDesiredTiltAccelerationAbsolute((tilt_accel - 1))) {
02123                 printf("Setting desired pan acceleration absolute failed\n");
02124                 return;
02125             }
02126             long mod_pan_accel = getPanAcceleartion();
02127             long mod_tilt_accel = getTiltAcceleartion();
02128             if((pan_accel - 1) != mod_pan_accel) {
02129                 printf("Error while getting pan acceleration. Expected %ld - 1, got %ld\n", pan_accel, mod_pan_accel);
02130                 return;
02131             }
02132             if((tilt_accel - 1) != mod_tilt_accel) {
02133                 printf("Error while getting tilt acceleration. Expected %ld - 1, got %ld\n", tilt_accel, mod_tilt_accel);
02134                 return;
02135             }
02136 
02137             printf("Speed testing successfull\n");
02138 
02139             double pan_res = getPanResolution();
02140             double tilt_res = getTiltResolution();
02141 
02142             if(pan_res <= 0.0) {
02143                 printf("Error while getting pan resolution");
02144                 return;
02145             }
02146             if(tilt_res <= 0.0) {
02147                 printf("Error while getting tilt resolution");
02148                 return;
02149             }
02150 
02151             printf("Resolution testing successfull with Pan Resolution %f und Tilt Resolution %f\n", pan_res, tilt_res);
02152 
02153 
02154             if(!setPositionExecutionMode(SLAVED_POSITION_EXECUTION_MODE)) {
02155                 printf("Error while setting position execution mode to SLAVED_POSITION_EXECUTION_MODE\n");
02156                 return;
02157             }
02158             long pos_ex_mode = getPositionExecutionMode();
02159             if(pos_ex_mode != SLAVED_POSITION_EXECUTION_MODE) {
02160                 printf("Error while getting or setting position execution mode. SLAVED_POSITION_EXECUTION_MODE expected, got %ld\n", pos_ex_mode);
02161                 return;
02162             }
02163             if(!setPositionExecutionMode(IMMEDIATE_POSITION_EXECUTION_MODE)) {
02164                 printf("Error while setting position execution mode to IMMEDIATE_POSITION_EXECUTION_MODE\n");
02165                 return;
02166             }
02167             pos_ex_mode = getPositionExecutionMode();
02168             if(pos_ex_mode != IMMEDIATE_POSITION_EXECUTION_MODE) {
02169                 printf("Error while getting or setting position execution mode. IMMEDIATE_POSITION_EXECUTION_MODE expected, got %ld\n", pos_ex_mode);
02170                 return;
02171             }
02172 
02173 
02174 
02175             if(!halt(HALT_BOTH)) {
02176                 printf("Error while executing halt command with HALT_BOTH\n");
02177                 return;
02178             }
02179             if(!halt(HALT_PAN_ONLY)) {
02180                 printf("Error while executing halt command with HALT_PAN_ONLY\n");
02181                 return;
02182             }
02183             if(!halt(HALT_TILT_ONLY)) {
02184                 printf("Error while executing halt command with HALT_TILT_ONLY\n");
02185                 return;
02186             }
02187 
02188             if(!setDesiredPanTiltPositionAbsoluteSlaved(300, 300)) {
02189                 printf("Problem while setting preset with current location\n");
02190                 return;
02191             }
02192             awaitPositionCommandCompletion();
02193             long cur_pan_pos = getCurrentPanPosition();
02194             long cur_tilt_pos = getCurrentTiltPosition();
02195             if(cur_pan_pos != 300 || cur_tilt_pos != 300) {
02196                 printf("Synchronous setting of pan and tilt axis in setDesiredPanTiltPositionAbsoluteSlaved did not work properly, false position was set\n");
02197                 return;
02198             }
02199             /*
02200             if(!setPreset(1)) {
02201                 printf("Problem with setting implicit preset\n");
02202                 return;
02203             }
02204             setDesiredTiltPositionAbsolute(0);
02205             sleep(6);
02206             if(getCurrentTiltPosition()!= 0) {
02207                 printf("Probably problem after setting pan_tilt synchronous with setDesiredPanTiltPositionAbsoluteSlaved. Next regular pan only setting command returned wrong result or was not executed\n");
02208                 return;
02209             }
02210             if(!setPreset(2, -300, -300)) {
02211                 printf("Problem while setting preset with explizit pan and tilt pasing\n");
02212                 return;
02213             }
02214             if(!gotoPreset(1)) {
02215                 printf("Error while going to preset with Number 1\n");
02216                 return;
02217             }
02218             awaitPositionCommandCompletion();
02219             cur_pan_pos = getCurrentPanPosition();
02220             cur_tilt_pos = getCurrentTiltPosition();
02221             if(cur_pan_pos != 300 || cur_tilt_pos != 300) {
02222                 printf("setPreset did not work properly. When going to preset 1 wrong position is loaded\n");
02223                 return;
02224             }
02225             if(!gotoPreset(2)) {
02226                 printf("Error while going to preset with Number 1\n");
02227                 return;
02228             }
02229             awaitPositionCommandCompletion();
02230             cur_pan_pos = getCurrentPanPosition();
02231             cur_tilt_pos = getCurrentTiltPosition();
02232             if(cur_pan_pos != -300 || cur_tilt_pos != -300) {
02233                 printf("setPreset did not work properly. When going to preset 2 wrong position is loaded\n");
02234                 return;
02235             }
02236 
02237             clearPreset();
02238 
02239             if(gotoPreset(1)) {
02240                 printf("Goto preset 1 after clearing preset worked but it should not have worked\n");
02241                 return;
02242             }
02243             */
02244 
02245             if(!setSpeedControlMode(PURE_VELOCITY_CONTROL_MODE)) {
02246                 printf("Error while setting speed control mode to PURE_VELOCITY_CONTROL_MODE\n");
02247                 return;
02248             }
02249             long cur_speed_control_mode = getSpeedControlMode();
02250             if(cur_speed_control_mode != PURE_VELOCITY_CONTROL_MODE) {
02251                 printf("Error while getting or setting speed controle mode. Expected PURE_VELOCITY_CONTROL_MODE, got %ld\n", cur_speed_control_mode);
02252                 return;
02253             }
02254 
02255             if(!setSpeedControlMode(INDEPENDENT_SPEED_MODE)) {
02256                 printf("Error while setting speed control mode to INDEPENDENT_SPEED_MODE\n");
02257                 return;
02258             }
02259             cur_speed_control_mode = getSpeedControlMode();
02260             if(cur_speed_control_mode != INDEPENDENT_SPEED_MODE) {
02261                 printf("Error while getting or setting speed controle mode. Expected INDEPENDENT_SPEED_MODE, got %ld\n", cur_speed_control_mode);
02262                 return;
02263             }
02264 
02265 
02266             //NOTE: Only visual check on reset modes they are written to eeprom and there is no way to query the current mode.
02267             //Folowing commented out functions where also only visually checked (code review)
02268             //bool setResetMode(long mode);
02269             //bool saveDefault();
02270             //bool restoreDefault();
02271             //bool restoreFactoryDefault();
02272 
02273             long prev_pan_stat_power_mode = getPanStationaryPowerMode();
02274             long prev_tilt_stat_power_mode = getTiltStationaryPowerMode();
02275             if(!setPanStationaryPowerMode(REGULAR_HOLD_POWER_MODE)) {
02276                 printf("Error while setting pan stationary power mode to REGULAR_HOLD_POWER_MODE\n");
02277                 return;
02278             }
02279             if(!setTiltStationaryPowerMode(REGULAR_HOLD_POWER_MODE)) {
02280                 printf("Error while setting tilt stationary power mode to REGULAR_HOLD_POWER_MODE\n");
02281                 return;
02282             }
02283             long cur_pan_stat_power_mode = getPanStationaryPowerMode();
02284             long cur_tilt_stat_power_mode = getTiltStationaryPowerMode();
02285             if(cur_pan_stat_power_mode != REGULAR_HOLD_POWER_MODE) {
02286                 printf("Error while getting or setting pan stationary power mode. Expected: REGULAR_HOLD_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02287                 return;
02288             }
02289             if(cur_tilt_stat_power_mode != REGULAR_HOLD_POWER_MODE) {
02290                 printf("Error while getting or setting tilt stationary power mode. Expected: REGULAR_HOLD_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02291                 return;
02292             }
02293 
02294             if(!setPanStationaryPowerMode(LOW_HOLD_POWER_MODE)) {
02295                 printf("Error while setting pan stationary power mode to LOW_HOLD_POWER_MODE\n");
02296                 return;
02297             }
02298             if(!setTiltStationaryPowerMode(LOW_HOLD_POWER_MODE)) {
02299                 printf("Error while setting tilt stationary power mode to LOW_HOLD_POWER_MODE\n");
02300                 return;
02301             }
02302             cur_pan_stat_power_mode = getPanStationaryPowerMode();
02303             cur_tilt_stat_power_mode = getTiltStationaryPowerMode();
02304             if(cur_pan_stat_power_mode != LOW_HOLD_POWER_MODE) {
02305                 printf("Error while getting or setting pan stationary power mode. Expected: LOW_HOLD_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02306                 return;
02307             }
02308             if(cur_tilt_stat_power_mode != LOW_HOLD_POWER_MODE) {
02309                 printf("Error while getting or setting tilt stationary power mode. Expected: LOW_HOLD_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02310                 return;
02311             }
02312 
02313             if(!setPanStationaryPowerMode(OFF_HOLD_POWER_MODE)) {
02314                 printf("Error while setting pan stationary power mode to OFF_HOLD_POWER_MODE\n");
02315                 return;
02316             }
02317             if(!setTiltStationaryPowerMode(OFF_HOLD_POWER_MODE)) {
02318                 printf("Error while setting tilt stationary power mode to OFF_HOLD_POWER_MODE\n");
02319                 return;
02320             }
02321             cur_pan_stat_power_mode = getPanStationaryPowerMode();
02322             cur_tilt_stat_power_mode = getTiltStationaryPowerMode();
02323             if(cur_pan_stat_power_mode != OFF_HOLD_POWER_MODE) {
02324                 printf("Error while getting or setting pan stationary power mode. Expected: OFF_HOLD_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02325                 return;
02326             }
02327             if(cur_tilt_stat_power_mode != OFF_HOLD_POWER_MODE) {
02328                 printf("Error while getting or setting tilt stationary power mode. Expected: OFF_HOLD_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02329                 return;
02330             }
02331 
02332             setPanStationaryPowerMode(prev_pan_stat_power_mode);
02333             setTiltStationaryPowerMode(prev_tilt_stat_power_mode);
02334 
02335             long prev_pan_move_power_mode = getPanInMotionPowerMode();
02336             long prev_tilt_move_power_mode = getTiltInMotionPowerMode();
02337             if(!setPanInMotionPowerMode(REGULAR_MOVE_POWER_MODE)) {
02338                 printf("Error while setting pan in_motion power mode to REGULAR_MOVE_POWER_MODE\n");
02339                 return;
02340             }
02341             if(!setTiltInMotionPowerMode(REGULAR_MOVE_POWER_MODE)) {
02342                 printf("Error while setting tilt in_motion power mode to REGULAR_MOVE_POWER_MODE\n");
02343                 return;
02344             }
02345             long cur_pan_move_power_mode = getPanInMotionPowerMode();
02346             long cur_tilt_move_power_mode = getTiltInMotionPowerMode();
02347             if(cur_pan_move_power_mode != REGULAR_MOVE_POWER_MODE) {
02348                 printf("Error while getting or setting pan in_motion power mode. Expected: REGULAR_MOVE_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02349                 return;
02350             }
02351             if(cur_tilt_move_power_mode != REGULAR_MOVE_POWER_MODE) {
02352                 printf("Error while getting or setting tilt in_motion power mode. Expected: REGULAR_MOVE_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02353                 return;
02354             }
02355 
02356             if(!setPanInMotionPowerMode(LOW_MOVE_POWER_MODE)) {
02357                 printf("Error while setting pan in_motion power mode to LOW_MOVE_POWER_MODE\n");
02358                 return;
02359             }
02360             if(!setTiltInMotionPowerMode(LOW_MOVE_POWER_MODE)) {
02361                 printf("Error while setting tilt in_motion power mode to LOW_MOVE_POWER_MODE\n");
02362                 return;
02363             }
02364             cur_pan_move_power_mode = getPanInMotionPowerMode();
02365             cur_tilt_move_power_mode = getTiltInMotionPowerMode();
02366             if(cur_pan_move_power_mode != LOW_MOVE_POWER_MODE) {
02367                 printf("Error while getting or setting pan in_motion power mode. Expected: LOW_MOVE_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02368                 return;
02369             }
02370             if(cur_tilt_move_power_mode != LOW_MOVE_POWER_MODE) {
02371                 printf("Error while getting or setting tilt in_motion power mode. Expected: LOW_MOVE_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02372                 return;
02373             }
02374 
02375             if(!setPanInMotionPowerMode(HIGH_MOVE_POWER_MODE)) {
02376                 printf("Error while setting pan in_motion power mode to HIGH_MOVE_POWER_MODE\n");
02377                 return;
02378             }
02379             if(!setTiltInMotionPowerMode(HIGH_MOVE_POWER_MODE)) {
02380                 printf("Error while setting tilt in_motion power mode to HIGH_MOVE_POWER_MODE\n");
02381                 return;
02382             }
02383             cur_pan_move_power_mode = getPanInMotionPowerMode();
02384             cur_tilt_move_power_mode = getTiltInMotionPowerMode();
02385             if(cur_pan_move_power_mode != HIGH_MOVE_POWER_MODE) {
02386                 printf("Error while getting or setting pan in_motion power mode. Expected: HIGH_MOVE_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02387                 return;
02388             }
02389             if(cur_tilt_move_power_mode != HIGH_MOVE_POWER_MODE) {
02390                 printf("Error while getting or setting tilt in_motion power mode. Expected: HIGH_MOVE_POWER_MODE, got %ld\n", cur_pan_stat_power_mode);
02391                 return;
02392             }
02393 
02394             setPanInMotionPowerMode(prev_pan_move_power_mode);
02395             setTiltInMotionPowerMode(prev_tilt_move_power_mode);
02396 
02397 
02398             printf("Testing successfull\n");
02399     }
02400 
02401     bool PTUFree::isOpen() {
02402         return ptu_port.is_open();
02403     }
02404 }


asr_flir_ptu_driver
Author(s): Valerij Wittenbeck, Joachim Gehrung, Pascal Meißner, Patrick Schlosser
autogenerated on Thu Jun 6 2019 21:16:44