jerrym | f157933 | 2013-02-07 01:56:28 +0000 | [diff] [blame] | 1 |
|
| 2 | /********************************************************************************
|
| 3 | * Project : FIRST Motor Controller
|
| 4 | * File Name : AxisCamera.cpp
|
| 5 | * Contributors : TD, ELF, JDG, SVK
|
| 6 | * Creation Date : July 29, 2008
|
| 7 | * Revision History : Source code & revision history maintained at sourceforge.WPI.edu
|
| 8 | * File Description : Axis camera access for the FIRST Vision API
|
| 9 | * The camera task runs as an independent thread
|
| 10 | */
|
| 11 | /*----------------------------------------------------------------------------*/
|
| 12 | /* Copyright (c) FIRST 2008. All Rights Reserved. */
|
| 13 | /* Open Source Software - may be modified and shared by FRC teams. The code */
|
| 14 | /* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
|
| 15 | /*----------------------------------------------------------------------------*/
|
| 16 |
|
| 17 |
|
| 18 | #include "sockLib.h"
|
| 19 | #include "vxWorks.h"
|
| 20 |
|
| 21 | #include "errno.h"
|
| 22 | #include "fioLib.h"
|
| 23 | #include "hostLib.h"
|
| 24 | #include "inetLib.h"
|
| 25 | #include "signal.h"
|
| 26 | #include "sigLib.h" // for signal
|
| 27 | #include <string>
|
| 28 | #include "time.h"
|
| 29 | #include "usrLib.h"
|
| 30 |
|
| 31 | #include "AxisCamera.h"
|
| 32 | #include "BaeUtilities.h"
|
| 33 | #include "FrcError.h"
|
| 34 | #include "Task.h"
|
| 35 | #include "Timer.h"
|
| 36 | #include "VisionAPI.h"
|
| 37 |
|
| 38 | /** packet size */
|
| 39 | #define DEFAULT_PACKET_SIZE 512
|
| 40 |
|
| 41 | /** Private NI function to decode JPEG */
|
| 42 | IMAQ_FUNC int Priv_ReadJPEGString_C(Image* _image, const unsigned char* _string, UINT32 _stringLength);
|
| 43 |
|
| 44 | // To locally enable debug printing: set AxisCamera_debugFlag to a 1, to disable set to 0
|
| 45 | int AxisCamera_debugFlag = 0;
|
| 46 | #define DPRINTF if(AxisCamera_debugFlag)dprintf
|
| 47 |
|
| 48 | /** @brief Camera data to be accessed globally */
|
| 49 | struct {
|
| 50 | int readerPID; // Set to taskID for signaling
|
| 51 | int index; /* -1,0,1 */
|
| 52 | int acquire; /* 0:STOP CAMERA; 1:START CAMERA */
|
| 53 | int cameraReady; /* 0: CAMERA NOT INITIALIZED; 1: CAMERA INITIALIZED */
|
| 54 | int decode; /* 0:disable decoding; 1:enable decoding to HSL Image */
|
| 55 | struct {
|
| 56 | //
|
| 57 | // To find the latest image timestamp, access:
|
| 58 | // globalCamera.data[globalCamera.index].timestamp
|
| 59 | //
|
| 60 | double timestamp; // when image was taken
|
| 61 | char* cameraImage; // jpeg image string
|
| 62 | int cameraImageSize; // image size
|
| 63 | Image* decodedImage; // image decoded to NI Image object
|
| 64 | int decodedImageSize; // size of decoded image
|
| 65 | }data[2];
|
| 66 | int cameraMetrics[CAM_NUM_METRICS];
|
| 67 | }globalCamera;
|
| 68 |
|
| 69 | /* run flag */
|
| 70 | static short cont = 0;
|
| 71 |
|
| 72 | /**
|
| 73 | * @brief Get the most recent camera image.
|
| 74 | * Supports IMAQ_IMAGE_RGB and IMAQ_IMAGE_HSL.
|
| 75 | * @param image Image to return to; image must have been first created using frcCreateImage.
|
| 76 | * When you are done, use frcDispose.
|
| 77 | * @param timestamp Timestamp to return; will record the time at which the image was stored.
|
| 78 | * @param lastImageTimestamp Input - timestamp of last image; prevents serving of stale images
|
| 79 | * @return 0 is failure, 1 is success
|
| 80 | * @sa frcCreateImage(), frcDispose()
|
| 81 | */
|
| 82 | int GetImageBlocking(Image* image, double *timestamp, double lastImageTimestamp)
|
| 83 | {
|
| 84 | char funcName[]="GetImageBlocking";
|
| 85 | int success;
|
| 86 | double startTime = GetTime();
|
| 87 |
|
| 88 | while (1)
|
| 89 | {
|
| 90 | success = GetImage(image, timestamp);
|
| 91 | if (!success) return (success);
|
| 92 |
|
| 93 | if (*timestamp > lastImageTimestamp)
|
| 94 | return (1); // GOOD IMAGE RETURNED
|
| 95 |
|
| 96 | if (GetTime() > (startTime + MAX_BLOCKING_TIME_SEC))
|
| 97 | {
|
| 98 | imaqSetError(ERR_CAMERA_BLOCKING_TIMEOUT, funcName);
|
| 99 | globalCamera.cameraMetrics[CAM_BLOCKING_TIMEOUT]++;
|
| 100 | return (0); // NO IMAGE AVAILABLE WITHIN specified time
|
| 101 | }
|
| 102 | globalCamera.cameraMetrics[CAM_BLOCKING_COUNT]++;
|
| 103 | taskDelay (1);
|
| 104 | }
|
| 105 | }
|
| 106 |
|
| 107 | /**
|
| 108 | * @brief Verifies that the camera is initialized
|
| 109 | * @return 0 for failure, 1 for success
|
| 110 | */
|
| 111 | int CameraInitialized()
|
| 112 | {
|
| 113 | char funcName[]="CameraInitialized";
|
| 114 | int success = 0;
|
| 115 | /* check to see if camera is initialized */
|
| 116 | if (!globalCamera.cameraReady) {
|
| 117 | imaqSetError(ERR_CAMERA_NOT_INITIALIZED, funcName);
|
| 118 | DPRINTF (LOG_DEBUG, "Camera request before camera is initialized");
|
| 119 | globalCamera.cameraMetrics[CAM_GETIMAGE_BEFORE_INIT]++;
|
| 120 | globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
|
| 121 | return success;
|
| 122 | }
|
| 123 |
|
| 124 | if (globalCamera.index == -1){
|
| 125 | imaqSetError(ERR_CAMERA_NO_BUFFER_AVAILABLE, funcName);
|
| 126 | DPRINTF (LOG_DEBUG, "No camera image available");
|
| 127 | globalCamera.cameraMetrics[CAM_GETIMAGE_BEFORE_AVAILABLE]++;
|
| 128 | globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
|
| 129 | return success;
|
| 130 | }
|
| 131 | return 1;
|
| 132 | }
|
| 133 |
|
| 134 | /**
|
| 135 | * @brief Gets the most recent camera image, as long as it is not stale.
|
| 136 | * Supported image types: IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL
|
| 137 | * @param image Image to return, must have first been created with frcCreateImage or imaqCreate.
|
| 138 | * When you finish with the image, call frcDispose() to dispose of it.
|
| 139 | * @param timestamp Returned timestamp of when the image was taken from the camera
|
| 140 | * @return failure = 0, success = 1
|
| 141 | */
|
| 142 | int GetImage(Image* image, double *timestamp)
|
| 143 | {
|
| 144 | char funcName[]="GetImage";
|
| 145 | int success = 0;
|
| 146 | int readIndex;
|
| 147 | int readCount = 10;
|
| 148 | double currentTime = time(NULL);
|
| 149 | double currentImageTimestamp;
|
| 150 |
|
| 151 | /* check to see if camera is initialized */
|
| 152 |
|
| 153 | if (!CameraInitialized()) {return success;}
|
| 154 |
|
| 155 | /* try readCount times to get an image */
|
| 156 | while (readCount) {
|
| 157 | readIndex = globalCamera.index;
|
| 158 | if (!imaqDuplicate(image, globalCamera.data[readIndex].decodedImage)) {
|
| 159 | int errorCode = GetLastVisionError();
|
| 160 | DPRINTF (LOG_DEBUG,"Error duplicating image= %i %s ", errorCode, GetVisionErrorText(errorCode));
|
| 161 | }
|
| 162 | // save the timestamp to check before returning
|
| 163 | currentImageTimestamp = globalCamera.data[readIndex].timestamp;
|
| 164 |
|
| 165 | // make sure this buffer is not being written to now
|
| 166 | if (readIndex == globalCamera.index) break;
|
| 167 | readCount--;
|
| 168 | }
|
| 169 |
|
| 170 | /* were we successful ? */
|
| 171 | if (readCount){
|
| 172 | success = 1;
|
| 173 | if (timestamp != NULL)
|
| 174 | *timestamp = currentImageTimestamp; // Return image timestamp
|
| 175 | } else{
|
| 176 | globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
|
| 177 | }
|
| 178 |
|
| 179 | /* Ensure the buffered image is not too old - set this "stale time" above */
|
| 180 | if (currentTime > globalCamera.data[globalCamera.index].timestamp + CAMERA_IMAGE_STALE_TIME_SEC){
|
| 181 | DPRINTF (LOG_CRITICAL, "STALE camera image (THIS COULD BE A BAD IMAGE)");
|
| 182 | imaqSetError(ERR_CAMERA_STALE_IMAGE, funcName);
|
| 183 | globalCamera.cameraMetrics[CAM_STALE_IMAGE]++;
|
| 184 | globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
|
| 185 | success = 0;
|
| 186 | }
|
| 187 | globalCamera.cameraMetrics[CAM_GETIMAGE_SUCCESS]++;
|
| 188 | return success;
|
| 189 | }
|
| 190 |
|
| 191 | /**
|
| 192 | * @brief Method to get a raw image from the buffer
|
| 193 | * @param imageData returned image data
|
| 194 | * @param numBytes returned number of bytes in buffer
|
| 195 | * @param currentImageTimestamp returned buffer time of image data
|
| 196 | * @return 0 if failure; 1 if success
|
| 197 | */
|
| 198 | int GetImageData(char** imageData, int* numBytes, double* currentImageTimestamp)
|
| 199 | {
|
| 200 | int success = 0;
|
| 201 | int readIndex;
|
| 202 | int readCount = 10;
|
| 203 | int cameraImageSize;
|
| 204 | char *cameraImageString;
|
| 205 |
|
| 206 | /* check to see if camera is initialized */
|
| 207 |
|
| 208 | if (!CameraInitialized()) {return success;}
|
| 209 |
|
| 210 | /* try readCount times to get an image */
|
| 211 | while (readCount) {
|
| 212 | readIndex = globalCamera.index;
|
| 213 | cameraImageSize = globalCamera.data[readIndex].cameraImageSize;
|
| 214 | //cameraImageString = (Image *) malloc(cameraImageSize);
|
| 215 | cameraImageString = new char[cameraImageSize];
|
| 216 | if (NULL == cameraImageString) {
|
| 217 | DPRINTF (LOG_DEBUG, "Unable to allocate cameraImage");
|
| 218 | globalCamera.cameraMetrics[CAM_GETIMAGE_FAILURE]++;
|
| 219 | return success;
|
| 220 | }
|
| 221 | memcpy (cameraImageString, globalCamera.data[readIndex].cameraImage, cameraImageSize);
|
| 222 | *currentImageTimestamp = globalCamera.data[readIndex].timestamp;
|
| 223 | // make sure this buffer is not being written to now
|
| 224 | if (readIndex == globalCamera.index) break;
|
| 225 | free (cameraImageString);
|
| 226 | readCount--;
|
| 227 | }
|
| 228 | if (readCount){
|
| 229 | *imageData = cameraImageString;
|
| 230 | *numBytes = cameraImageSize;
|
| 231 | return 1;
|
| 232 | }
|
| 233 | return (OK);
|
| 234 | }
|
| 235 |
|
| 236 | /**
|
| 237 | * @brief Blocking call to get images for PC.
|
| 238 | * This should be called from a separate task to maintain camera read performance.
|
| 239 | * It is intended to be used for sending raw (undecoded) image data to the PC.
|
| 240 | * @param imageData image data to return
|
| 241 | * @param numBytes number of bytes in buffer
|
| 242 | * @param timestamp timestamp of buffer returned
|
| 243 | * @param lastImageTimestamp buffer time of last image data sent to PC
|
| 244 | * @return 0 if failure; 1 if success
|
| 245 | */
|
| 246 | int GetImageDataBlocking(char** imageData, int* numBytes, double* timestamp, double lastImageTimestamp)
|
| 247 | {
|
| 248 |
|
| 249 | char funcName[]="GetImageDataBlocking";
|
| 250 | int success;
|
| 251 | double startTime = GetTime();
|
| 252 |
|
| 253 | *imageData = NULL;
|
| 254 | while (1)
|
| 255 | {
|
| 256 | success = GetImageData(imageData, numBytes, timestamp);
|
| 257 | if (!success) return (success);
|
| 258 |
|
| 259 | if (*timestamp > lastImageTimestamp)
|
| 260 | return (1); // GOOD IMAGE DATA RETURNED
|
| 261 |
|
| 262 | delete *imageData;
|
| 263 | *imageData = NULL;
|
| 264 |
|
| 265 | if (GetTime() > (startTime + MAX_BLOCKING_TIME_SEC))
|
| 266 | {
|
| 267 | imaqSetError(ERR_CAMERA_BLOCKING_TIMEOUT, funcName);
|
| 268 | return (0); // NO IMAGE AVAILABLE WITHIN specified time
|
| 269 | }
|
| 270 | globalCamera.cameraMetrics[CAM_BLOCKING_COUNT]++;
|
| 271 | taskDelay (1);
|
| 272 | }
|
| 273 | }
|
| 274 |
|
| 275 | /**
|
| 276 | * @brief Accessor for camera instrumentation data
|
| 277 | * @param the counter queried
|
| 278 | * @return the counter value
|
| 279 | */
|
| 280 | int GetCameraMetric(FrcvCameraMetric metric)
|
| 281 | { return globalCamera.cameraMetrics[metric]; }
|
| 282 |
|
| 283 | /**
|
| 284 | * @brief Close socket & report error
|
| 285 | * @param errstring String to print
|
| 286 | * @param socket Socket to close
|
| 287 | * @return error
|
| 288 | */
|
| 289 | int CameraCloseSocket(char *errstring, int socket)
|
| 290 | {
|
| 291 | DPRINTF (LOG_CRITICAL, "Closing socket - CAMERA ERROR: %s", errstring );
|
| 292 | close (socket);
|
| 293 | return (ERROR);
|
| 294 | }
|
| 295 |
|
| 296 |
|
| 297 | /**
|
| 298 | * @brief Reads one line from the TCP stream.
|
| 299 | * @param camSock The socket.
|
| 300 | * @param buffer A buffer with bufSize allocated for it.
|
| 301 | * On return, bufSize-1 amount of data or data upto first line ending
|
| 302 | * whichever is smaller, null terminated.
|
| 303 | * @param bufSize The size of buffer.
|
| 304 | * @param stripLineEnding If true, strips the line ending chacters from the buffer before return.
|
| 305 | * @return 0 if failure; 1 if success
|
| 306 | */
|
| 307 | static int CameraReadLine(int camSock, char* buffer, int bufSize, bool stripLineEnding) {
|
| 308 | char funcName[]="CameraReadLine";
|
| 309 | // Need at least 3 bytes in the buffer to pull this off.
|
| 310 | if (bufSize < 3) {
|
| 311 | imaqSetError(ERR_CAMERA_FAILURE, funcName);
|
| 312 | return 0;
|
| 313 | }
|
| 314 | // Reduce size by 1 to allow for null terminator.
|
| 315 | --bufSize;
|
| 316 | // Read upto bufSize characters.
|
| 317 | for (int i=0;i < bufSize;++i, ++buffer) {
|
| 318 | // Read one character.
|
| 319 | if (read (camSock, buffer, 1) <= 0) {
|
| 320 | imaqSetError(ERR_CAMERA_FAILURE, funcName);
|
| 321 | return 0;
|
| 322 | }
|
| 323 | // Line endings can be "\r\n" or just "\n". So always
|
| 324 | // look for a "\n". If you got just a "\n" and
|
| 325 | // stripLineEnding is false, then convert it into a \r\n
|
| 326 | // because callers expect a \r\n.
|
| 327 | // If the combination of the previous character and the current character
|
| 328 | // is "\r\n", the line ending
|
| 329 | if (*buffer=='\n') {
|
| 330 | // If asked to strip the line ending, then set the buffer to the previous
|
| 331 | // character.
|
| 332 | if (stripLineEnding) {
|
| 333 | if (i > 0 && *(buffer-1)=='\r') {
|
| 334 | --buffer;
|
| 335 | }
|
| 336 | }
|
| 337 | else {
|
| 338 | // If the previous character was not a '\r',
|
| 339 | if (i == 0 || *(buffer-1)!='\r') {
|
| 340 | // Make the current character a '\r'.
|
| 341 | *buffer = '\r';
|
| 342 | // If space permits, add back the '\n'.
|
| 343 | if (i < bufSize-1) {
|
| 344 | ++buffer;
|
| 345 | *buffer = '\n';
|
| 346 | }
|
| 347 | }
|
| 348 | // Set the buffer past the current character ('\n')
|
| 349 | ++buffer;
|
| 350 | }
|
| 351 | break;
|
| 352 | }
|
| 353 | }
|
| 354 | // Null terminate.
|
| 355 | *buffer = '\0';
|
| 356 | return 1;
|
| 357 | }
|
| 358 |
|
| 359 | /**
|
| 360 | @brief Skips read data until the first empty line.
|
| 361 |
|
| 362 | @param camSock An open tcp socket to the camera to read the data from.
|
| 363 | @return sucess 0 if failure; 1 if success
|
| 364 | */
|
| 365 | static int CameraSkipUntilEmptyLine(int camSock) {
|
| 366 | char buffer[1024];
|
| 367 | int success = 0;
|
| 368 | while(1) {
|
| 369 | success = CameraReadLine(camSock, buffer, sizeof(buffer), true);
|
| 370 | if (*buffer == '\0') {
|
| 371 | return success;
|
| 372 | }
|
| 373 | }
|
| 374 | return success;
|
| 375 | }
|
| 376 |
|
| 377 | /**
|
| 378 | @brief Opens a socket.
|
| 379 |
|
| 380 | Issues the given http request with the required added information
|
| 381 | and authentication. It cycles through an array of predetermined
|
| 382 | encrypted username, password combinations that we expect the users
|
| 383 | to have at any point in time. If none of the username, password
|
| 384 | combinations work, it outputs a "Unknown user or password" error.
|
| 385 | If the request succeeds, it returns the socket number.
|
| 386 |
|
| 387 | @param serverName The information about the host from which this request originates
|
| 388 | @param request The request to send to the camera not including boilerplate or
|
| 389 | authentication. This is usually in the form of "GET <string>"
|
| 390 | @return int - failure = ERROR; success = socket number;
|
| 391 | */
|
| 392 | static int CameraOpenSocketAndIssueAuthorizedRequest(const char* serverName, const char* request)
|
| 393 | {
|
| 394 | char funcName[]="cameraOpenSocketAndIssueAuthorizedRequest";
|
| 395 |
|
| 396 | struct sockaddr_in cameraAddr;
|
| 397 | int sockAddrSize;
|
| 398 | int camSock = ERROR;
|
| 399 |
|
| 400 | // The camera is expected to have one of the following username, password combinations.
|
| 401 | // This routine will return an error if it does not find one of these.
|
| 402 | static const char* authenticationStrings[] = {
|
| 403 | "RlJDOkZSQw==", /* FRC, FRC */
|
| 404 | "cm9vdDpwYXNz", /* root, admin*/
|
| 405 | "cm9vdDphZG1pbg==" /* root, pass*/
|
| 406 | };
|
| 407 |
|
| 408 | static const int numAuthenticationStrings = sizeof(authenticationStrings)/sizeof(authenticationStrings[0]);
|
| 409 |
|
| 410 | static const char *requestTemplate = "%s " \
|
| 411 | "HTTP/1.1\n" \
|
| 412 | "User-Agent: HTTPStreamClient\n" \
|
| 413 | "Connection: Keep-Alive\n" \
|
| 414 | "Cache-Control: no-cache\n" \
|
| 415 | "Authorization: Basic %s\n\n";
|
| 416 |
|
| 417 | int i = 0;
|
| 418 | for (;i < numAuthenticationStrings;++i) {
|
| 419 | char buffer[1024];
|
| 420 |
|
| 421 | sprintf(buffer, requestTemplate, request, authenticationStrings[i]);
|
| 422 |
|
| 423 | /* create camera socket */
|
| 424 | //DPRINTF (LOG_DEBUG, "creating camSock" );
|
| 425 | if ((camSock = socket (AF_INET, SOCK_STREAM, 0)) == ERROR) {
|
| 426 | imaqSetError(ERR_CAMERA_SOCKET_CREATE_FAILED, funcName);
|
| 427 | perror("Failed to create socket");
|
| 428 | return (ERROR);
|
| 429 | }
|
| 430 |
|
| 431 | sockAddrSize = sizeof (struct sockaddr_in);
|
| 432 | bzero ((char *) &cameraAddr, sockAddrSize);
|
| 433 | cameraAddr.sin_family = AF_INET;
|
| 434 | cameraAddr.sin_len = (u_char) sockAddrSize;
|
| 435 | cameraAddr.sin_port = htons (CAMERA_PORT);
|
| 436 |
|
| 437 | if (( (int)(cameraAddr.sin_addr.s_addr = inet_addr (const_cast<char*>(serverName)) ) == ERROR) &&
|
| 438 | ( (int)(cameraAddr.sin_addr.s_addr = hostGetByName (const_cast<char*>(serverName)) ) == ERROR))
|
| 439 | {
|
| 440 | imaqSetError(ERR_CAMERA_CONNECT_FAILED, funcName);
|
| 441 | return CameraCloseSocket("Failed to get IP, check hostname or IP", camSock);
|
| 442 | }
|
| 443 |
|
| 444 | //DPRINTF (LOG_INFO, "connecting camSock" );
|
| 445 | if (connect (camSock, (struct sockaddr *) &cameraAddr, sockAddrSize) == ERROR) {
|
| 446 | imaqSetError(ERR_CAMERA_CONNECT_FAILED, funcName);
|
| 447 | return CameraCloseSocket("Failed to connect to camera - check networ", camSock);
|
| 448 | }
|
| 449 |
|
| 450 | //DPRINTF (LOG_DEBUG, "writing GET request to camSock" );
|
| 451 | if (write (camSock, buffer, strlen(buffer) ) == ERROR) {
|
| 452 | imaqSetError(ERR_CAMERA_CONNECT_FAILED, funcName);
|
| 453 | return CameraCloseSocket("Failed to send GET request", camSock);
|
| 454 | }
|
| 455 |
|
| 456 | // Read one line with the line ending removed.
|
| 457 | if (!CameraReadLine(camSock, buffer, 1024, true)) {
|
| 458 | return CameraCloseSocket("Bad response to GET request", camSock);
|
| 459 | }
|
| 460 |
|
| 461 | // Check if the response is of the format HTTP/<version> 200 OK.
|
| 462 | float discard;
|
| 463 | if (sscanf(buffer, "HTTP/%f 200 OK", &discard) == 1) {
|
| 464 | break;
|
| 465 | }
|
| 466 |
|
| 467 | // We have to close the connection because in the case of failure
|
| 468 | // the server closes the connection.
|
| 469 | close(camSock);
|
| 470 | }
|
| 471 | // If none of the attempts were successful, then let the caller know.
|
| 472 | if (numAuthenticationStrings == i) {
|
| 473 | imaqSetError(ERR_CAMERA_AUTHORIZATION_FAILED, funcName);
|
| 474 | fprintf(stderr, "Expected username/password combination not found on camera");
|
| 475 | return ERROR;
|
| 476 | }
|
| 477 | return camSock;
|
| 478 | }
|
| 479 |
|
| 480 |
|
| 481 | /**
|
| 482 | * @brief Sends a configuration message to the camera
|
| 483 | * @param configString configuration message to the camera
|
| 484 | * @return success: 0=failure; 1=success
|
| 485 | */
|
| 486 | int ConfigureCamera(char *configString){
|
| 487 | char funcName[]="ConfigureCamera";
|
| 488 | char *serverName = "192.168.0.90"; /* camera @ */
|
| 489 | int success = 0;
|
| 490 | int camSock = 0;
|
| 491 |
|
| 492 | /* Generate camera configuration string */
|
| 493 | char * getStr1 =
|
| 494 | "GET /axis-cgi/admin/param.cgi?action=update&ImageSource.I0.Sensor.";
|
| 495 |
|
| 496 | char cameraRequest[strlen(getStr1) + strlen(configString)];
|
| 497 | sprintf (cameraRequest, "%s%s", getStr1, configString);
|
| 498 | DPRINTF(LOG_DEBUG, "camera configuration string: \n%s", cameraRequest);
|
| 499 | camSock = CameraOpenSocketAndIssueAuthorizedRequest(serverName, cameraRequest);
|
| 500 | DPRINTF(LOG_DEBUG, "camera socket# = %i", camSock);
|
| 501 |
|
| 502 | //read response
|
| 503 | success = CameraSkipUntilEmptyLine(camSock);
|
| 504 | //DPRINTF(LOG_DEBUG, "succcess from CameraSkipUntilEmptyLine: %i", success);
|
| 505 | char buffer[3]; // set property - 3
|
| 506 | success = CameraReadLine(camSock, buffer, 3, true);
|
| 507 | //DPRINTF(LOG_DEBUG, "succcess from CameraReadLine: %i", success);
|
| 508 | DPRINTF(LOG_DEBUG, "line read from camera \n%s", buffer);
|
| 509 | if (strcmp(buffer, "OK") != 0) {
|
| 510 | imaqSetError(ERR_CAMERA_COMMAND_FAILURE, funcName);
|
| 511 | DPRINTF(LOG_DEBUG, "setting ERR_CAMERA_COMMAND_FAILURE - OK not found");
|
| 512 | }
|
| 513 | DPRINTF (LOG_INFO, "\nConfigureCamera ENDING success = %i\n", success );
|
| 514 |
|
| 515 | /* clean up */
|
| 516 | close (camSock);
|
| 517 | return (1);
|
| 518 | }
|
| 519 |
|
| 520 |
|
| 521 | /**
|
| 522 | * @brief Sends a request message to the camera
|
| 523 | * @param configString request message to the camera
|
| 524 | * @param cameraResponse response from camera
|
| 525 | * @return success: 0=failure; 1=success
|
| 526 | */
|
| 527 | int GetCameraSetting(char *configString, char *cameraResponse){
|
| 528 | char *serverName = "192.168.0.90"; /* camera @ */
|
| 529 | int success = 0;
|
| 530 | int camSock = 0;
|
| 531 |
|
| 532 | /* Generate camera request string */
|
| 533 | char * getStr1 =
|
| 534 | "GET /axis-cgi/admin/param.cgi?action=list&group=ImageSource.I0.Sensor.";
|
| 535 | char cameraRequest[strlen(getStr1) + strlen(configString)];
|
| 536 | sprintf (cameraRequest, "%s%s", getStr1, configString);
|
| 537 | DPRINTF(LOG_DEBUG, "camera configuration string: \n%s", cameraRequest);
|
| 538 | camSock = CameraOpenSocketAndIssueAuthorizedRequest(serverName, cameraRequest);
|
| 539 | DPRINTF(LOG_DEBUG, "return from CameraOpenSocketAndIssueAuthorizedRequest %i", camSock);
|
| 540 |
|
| 541 | //read response
|
| 542 | success = CameraSkipUntilEmptyLine(camSock);
|
| 543 | success = CameraReadLine(camSock, cameraResponse, 1024, true);
|
| 544 | DPRINTF(LOG_DEBUG, "succcess from CameraReadLine: %i", success);
|
| 545 | DPRINTF(LOG_DEBUG, "line read from camera \n%s", cameraResponse);
|
| 546 | DPRINTF (LOG_INFO, "\nGetCameraSetting ENDING success = %i\n", success );
|
| 547 |
|
| 548 | /* clean up */
|
| 549 | close (camSock);
|
| 550 | return (1);
|
| 551 | }
|
| 552 |
|
| 553 | /**
|
| 554 | * @brief Sends a request message to the camera for image appearance property
|
| 555 | * (resolution, compression, rotation)
|
| 556 | * @param configString request message to the camera
|
| 557 | * @param cameraResponse response from camera
|
| 558 | * @return success: 0=failure; 1=success
|
| 559 | */
|
| 560 | int GetImageSetting(char *configString, char *cameraResponse){
|
| 561 | char *serverName = "192.168.0.90"; /* camera @ */
|
| 562 | int success = 0;
|
| 563 | int camSock = 0;
|
| 564 |
|
| 565 | /* Generate camera request string */
|
| 566 | char *getStr1 = "GET /axis-cgi/admin/param.cgi?action=list&group=Image.I0.Appearance.";
|
| 567 | char cameraRequest[strlen(getStr1) + strlen(configString)];
|
| 568 | sprintf (cameraRequest, "%s%s", getStr1, configString);
|
| 569 | DPRINTF(LOG_DEBUG, "camera configuration string: \n%s", cameraRequest);
|
| 570 | camSock = CameraOpenSocketAndIssueAuthorizedRequest(serverName, cameraRequest);
|
| 571 | DPRINTF(LOG_DEBUG, "return from CameraOpenSocketAndIssueAuthorizedRequest %i", camSock);
|
| 572 |
|
| 573 | //read response
|
| 574 | success = CameraSkipUntilEmptyLine(camSock);
|
| 575 | success = CameraReadLine(camSock, cameraResponse, 1024, true);
|
| 576 | DPRINTF(LOG_DEBUG, "succcess from CameraReadLine: %i", success);
|
| 577 | DPRINTF(LOG_DEBUG, "line read from camera \n%s", cameraResponse);
|
| 578 | DPRINTF (LOG_INFO, "\nGetCameraSetting ENDING success = %i\n", success );
|
| 579 |
|
| 580 | /* clean up */
|
| 581 | close (camSock);
|
| 582 | return (1);
|
| 583 | }
|
| 584 |
|
| 585 |
|
| 586 | #define MEASURE_SOCKET_TIME 1
|
| 587 |
|
| 588 | /**
|
| 589 | * @brief Manage access to the camera. Sets up sockets and reads images
|
| 590 | * @param frames Frames per second
|
| 591 | * @param compression Camera image compression
|
| 592 | * @param resolution Camera image size
|
| 593 | * @param rotation Camera image rotation
|
| 594 | * @return error
|
| 595 | */
|
| 596 | int cameraJPEGServer(int frames, int compression, ImageResolution resolution, ImageRotation rotation)
|
| 597 | {
|
| 598 | char funcName[]="cameraJPEGServer";
|
| 599 | char *serverName = "192.168.0.90"; /* camera @ */
|
| 600 | cont = 1;
|
| 601 | int errorCode = 0;
|
| 602 | int printCounter = 0;
|
| 603 | int writeIndex;
|
| 604 | int authorizeCount = 0;
|
| 605 | int authorizeConfirmed = 0;
|
| 606 | static const int authenticationStringsCount = 3;
|
| 607 | static const char* authenticationStrings[] = {
|
| 608 | "cm9vdDphZG1pbg==", /* root, admin*/
|
| 609 | "RlJDOkZSQw==", /* FRC, FRC */
|
| 610 | "cm9vdDpwYXNz==" /* root, pass*/
|
| 611 | };
|
| 612 |
|
| 613 | DPRINTF (LOG_DEBUG, "cameraJPEGServer" );
|
| 614 |
|
| 615 | struct sockaddr_in cameraAddr;
|
| 616 | int sockAddrSize;
|
| 617 | int camSock = 0;
|
| 618 |
|
| 619 | char resStr[10];
|
| 620 | switch (resolution) {
|
| 621 | case k640x480: { sprintf(resStr,"640x480"); break; }
|
| 622 | case k320x240: { sprintf(resStr,"320x240"); break; }
|
| 623 | case k160x120: { sprintf(resStr,"160x120"); break; }
|
| 624 | default: {DPRINTF (LOG_DEBUG, "code error - resolution input" ); break; }
|
| 625 | }
|
| 626 |
|
| 627 | /* Generate camera initialization string */
|
| 628 | /* changed resolution to 160x120 from 320x240 */
|
| 629 | /* supported resolutions are: 640x480, 640x360, 320x240, 160x120 */
|
| 630 | char * getStr1 =
|
| 631 | "GET /axis-cgi/mjpg/video.cgi?showlength=1&camera=1&";
|
| 632 |
|
| 633 | char insertStr[100];
|
| 634 | sprintf (insertStr, "des_fps=%i&compression=%i&resolution=%s&rotation=%i",
|
| 635 | frames, compression, resStr, (int)rotation);
|
| 636 |
|
| 637 | char * getStr2 = " HTTP/1.1\n\
|
| 638 | User-Agent: HTTPStreamClient\n\
|
| 639 | Host: 192.150.1.100\n\
|
| 640 | Connection: Keep-Alive\n\
|
| 641 | Cache-Control: no-cache\n\
|
| 642 | Authorization: Basic %s;\n\n";
|
| 643 |
|
| 644 | char getStr[strlen(getStr1) + strlen(insertStr) + strlen(getStr2)];
|
| 645 | sprintf (getStr, "%s:%s%s", getStr1, insertStr, getStr2);
|
| 646 |
|
| 647 | DPRINTF(LOG_DEBUG, "revised camera string: \n%s", getStr);
|
| 648 | /* Allocation */
|
| 649 | char tempBuffer[1024];
|
| 650 |
|
| 651 | RETRY:
|
| 652 | Wait(0.1); //bug fix - don't pester camera if it's booting
|
| 653 | while (globalCamera.acquire == 0) Wait(0.1);
|
| 654 |
|
| 655 | if (!authorizeConfirmed){
|
| 656 | if (authorizeCount < authenticationStringsCount){
|
| 657 | sprintf (tempBuffer, getStr, authenticationStrings[authorizeCount]);
|
| 658 | } else {
|
| 659 | imaqSetError(ERR_CAMERA_AUTHORIZATION_FAILED, funcName);
|
| 660 | fprintf(stderr, "Camera authorization failed ... Incorrect password on camera!!");
|
| 661 | return (ERROR);
|
| 662 | }
|
| 663 | }
|
| 664 |
|
| 665 | while (1)
|
| 666 | {
|
| 667 | globalCamera.cameraMetrics[CAM_SOCKET_INIT_ATTEMPTS]++;
|
| 668 |
|
| 669 | /* create camera socket */
|
| 670 | DPRINTF (LOG_DEBUG, "creating camSock" );
|
| 671 | if ((camSock = socket (AF_INET, SOCK_STREAM, 0)) == ERROR) {
|
| 672 | imaqSetError(ERR_CAMERA_SOCKET_CREATE_FAILED, funcName);
|
| 673 | perror("Failed to create socket");
|
| 674 | cont = 0;
|
| 675 | return (ERROR);
|
| 676 | }
|
| 677 |
|
| 678 | sockAddrSize = sizeof (struct sockaddr_in);
|
| 679 | bzero ((char *) &cameraAddr, sockAddrSize);
|
| 680 | cameraAddr.sin_family = AF_INET;
|
| 681 | cameraAddr.sin_len = (u_char) sockAddrSize;
|
| 682 | cameraAddr.sin_port = htons (CAMERA_PORT);
|
| 683 |
|
| 684 | DPRINTF (LOG_DEBUG, "getting IP" );
|
| 685 | if (( (int)(cameraAddr.sin_addr.s_addr = inet_addr (serverName) ) == ERROR) &&
|
| 686 | ( (int)(cameraAddr.sin_addr.s_addr = hostGetByName (serverName) ) == ERROR))
|
| 687 | {
|
| 688 | CameraCloseSocket("Failed to get IP, check hostname or IP", camSock);
|
| 689 | continue;
|
| 690 | }
|
| 691 |
|
| 692 | DPRINTF (LOG_INFO, "Attempting to connect to camSock" );
|
| 693 | if (connect (camSock, (struct sockaddr *) &cameraAddr, sockAddrSize) == ERROR) {
|
| 694 | imaqSetError(ERR_CAMERA_CONNECT_FAILED, funcName);
|
| 695 | CameraCloseSocket("Failed to connect to camera - check network", camSock);
|
| 696 | continue;
|
| 697 | }
|
| 698 |
|
| 699 | #if MEASURE_SOCKET_SETUP
|
| 700 | socketEndTime = GetTime();
|
| 701 | setupTime = socketEndTime - socketStartTime;
|
| 702 | printf("\n***socket setup time = %g\n", setupTime );
|
| 703 | #endif
|
| 704 |
|
| 705 | globalCamera.cameraMetrics[CAM_SOCKET_OPEN]++;
|
| 706 | break;
|
| 707 | } // end while (trying to connect to camera)
|
| 708 |
|
| 709 | DPRINTF (LOG_DEBUG, "writing GET request to camSock" );
|
| 710 | if (write (camSock, tempBuffer , strlen(tempBuffer) ) == ERROR) {
|
| 711 | return CameraCloseSocket("Failed to send GET request", camSock);
|
| 712 | }
|
| 713 |
|
| 714 | //DPRINTF (LOG_DEBUG, "reading header" );
|
| 715 | /* Find content-length, then read that many bytes */
|
| 716 | int counter = 2;
|
| 717 | char* contentString = "Content-Length: ";
|
| 718 | char* authorizeString = "200 OK";
|
| 719 |
|
| 720 | #define MEASURE_TIME 0
|
| 721 | #if MEASURE_TIME
|
| 722 | //timing parameters - only measure one at the time
|
| 723 | double loopStartTime = 0.0; // measuring speed of execution loop
|
| 724 | double loopEndTime = 0.0;
|
| 725 | double cameraStartTime = 0.0;
|
| 726 | double cameraEndTime = 0.0;
|
| 727 | double previousStartTime = 0.0;
|
| 728 | int performanceLoopCounter = 0;
|
| 729 | int maxCount = 30;
|
| 730 | #endif
|
| 731 |
|
| 732 | while (cont) {
|
| 733 | #if MEASURE_TIME
|
| 734 | previousStartTime = loopStartTime; // first time is bogus
|
| 735 | loopStartTime = GetTime();
|
| 736 | #endif
|
| 737 | // If camera has been turned OFF, jump to RETRY
|
| 738 | //if (globalCamera.acquire == 0) goto RETRY;
|
| 739 |
|
| 740 | /* Determine writer index */
|
| 741 | if (globalCamera.index == 0)
|
| 742 | writeIndex = 1;
|
| 743 | else
|
| 744 | writeIndex = 0;
|
| 745 |
|
| 746 | /* read header */
|
| 747 | //TODO: check for error in header, increment ERR_CAMERA_HEADER_ERROR
|
| 748 | char initialReadBuffer[DEFAULT_PACKET_SIZE] = "";
|
| 749 | char intermediateBuffer[1];
|
| 750 | char *trailingPtr = initialReadBuffer;
|
| 751 | int trailingCounter = 0;
|
| 752 |
|
| 753 |
|
| 754 | #if MEASURE_TIME
|
| 755 | cameraStartTime = GetTime();
|
| 756 | #endif
|
| 757 |
|
| 758 | while (counter) {
|
| 759 | if (read (camSock, intermediateBuffer, 1) <= 0) {
|
| 760 | CameraCloseSocket("Failed to read image header", camSock);
|
| 761 | globalCamera.cameraMetrics[ERR_CAMERA_HEADER_ERROR]++;
|
| 762 | goto RETRY;
|
| 763 | }
|
| 764 |
|
| 765 | strncat(initialReadBuffer, intermediateBuffer, 1);
|
| 766 | if (NULL != strstr(trailingPtr, "\r\n\r\n")) {
|
| 767 |
|
| 768 | if (!authorizeConfirmed){
|
| 769 |
|
| 770 | if (strstr(initialReadBuffer, authorizeString))
|
| 771 | {
|
| 772 | authorizeConfirmed = 1;
|
| 773 | /* set camera to initialized */
|
| 774 | globalCamera.cameraReady = 1;
|
| 775 | }
|
| 776 | else
|
| 777 | {
|
| 778 | CameraCloseSocket("Not authorized to connect to camera", camSock);
|
| 779 | authorizeCount++;
|
| 780 | goto RETRY;
|
| 781 | }
|
| 782 | }
|
| 783 | --counter;
|
| 784 | }
|
| 785 | if (++trailingCounter >= 4) {
|
| 786 | trailingPtr++;
|
| 787 | }
|
| 788 | }
|
| 789 |
|
| 790 | counter = 1;
|
| 791 | char *contentLength = strstr(initialReadBuffer, contentString);
|
| 792 | if (contentLength == NULL) {
|
| 793 | globalCamera.cameraMetrics[ERR_CAMERA_HEADER_ERROR]++;
|
| 794 | CameraCloseSocket("No content-length token found in packet", camSock);
|
| 795 | goto RETRY;
|
| 796 | }
|
| 797 | /* get length of image content */
|
| 798 | contentLength = contentLength + strlen(contentString);
|
| 799 | globalCamera.data[writeIndex].cameraImageSize = atol (contentLength);
|
| 800 |
|
| 801 | if(globalCamera.data[writeIndex].cameraImage)
|
| 802 | free(globalCamera.data[writeIndex].cameraImage);
|
| 803 | //globalCamera.data[writeIndex].cameraImage = (Image *) malloc(globalCamera.data[writeIndex].cameraImageSize);
|
| 804 | globalCamera.data[writeIndex].cameraImage = (char*)malloc(globalCamera.data[writeIndex].cameraImageSize);
|
| 805 | if (NULL == globalCamera.data[writeIndex].cameraImage) {
|
| 806 | return CameraCloseSocket("Failed to allocate space for imageString", camSock);
|
| 807 | }
|
| 808 | globalCamera.cameraMetrics[CAM_BUFFERS_WRITTEN]++;
|
| 809 |
|
| 810 | //
|
| 811 | // This is a blocking camera read function, and will block if the camera
|
| 812 | // has been disconnected from the cRIO. If however the camera is
|
| 813 | // POWERED OFF while connected to the cRIO, this function NEVER RETURNS
|
| 814 | //
|
| 815 | int bytesRead = fioRead (camSock, (char *)globalCamera.data[writeIndex].cameraImage,
|
| 816 | globalCamera.data[writeIndex].cameraImageSize);
|
| 817 |
|
| 818 | #if MEASURE_TIME
|
| 819 | cameraEndTime = GetTime();
|
| 820 | #endif
|
| 821 |
|
| 822 | //DPRINTF (LOG_DEBUG, "Completed fioRead function - bytes read:%d", bytesRead);
|
| 823 | if (bytesRead <= 0) {
|
| 824 | CameraCloseSocket("Failed to read image data", camSock);
|
| 825 | goto RETRY;
|
| 826 | } else if (bytesRead != globalCamera.data[writeIndex].cameraImageSize){
|
| 827 | fprintf(stderr, "ERROR: Failed to read entire image: readLength does not match bytes read");
|
| 828 | globalCamera.cameraMetrics[CAM_BAD_IMAGE_SIZE]++;
|
| 829 | }
|
| 830 | // if decoding the JPEG to an HSL Image, do it here
|
| 831 | if (globalCamera.decode) {
|
| 832 | if(globalCamera.data[writeIndex].decodedImage)
|
| 833 | frcDispose(globalCamera.data[writeIndex].decodedImage);
|
| 834 | globalCamera.data[writeIndex].decodedImage = frcCreateImage(IMAQ_IMAGE_HSL);
|
| 835 | if (! Priv_ReadJPEGString_C(globalCamera.data[writeIndex].decodedImage,
|
| 836 | (const unsigned char *)globalCamera.data[writeIndex].cameraImage,
|
| 837 | globalCamera.data[writeIndex].cameraImageSize) ) {
|
| 838 | DPRINTF (LOG_DEBUG, "failure creating Image");
|
| 839 | }
|
| 840 | }
|
| 841 |
|
| 842 | // TODO: React to partial image
|
| 843 | globalCamera.data[writeIndex].timestamp = GetTime();
|
| 844 | globalCamera.index = writeIndex;
|
| 845 |
|
| 846 | /* signal a listening task */
|
| 847 | if (globalCamera.readerPID) {
|
| 848 | if (taskKill (globalCamera.readerPID,SIGUSR1) == OK)
|
| 849 | DPRINTF (LOG_DEBUG, "SIGNALING PID= %i", globalCamera.readerPID);
|
| 850 | else
|
| 851 | globalCamera.cameraMetrics[CAM_PID_SIGNAL_ERR]++;
|
| 852 | DPRINTF (LOG_DEBUG, "ERROR SIGNALING PID= %i", globalCamera.readerPID);
|
| 853 | }
|
| 854 |
|
| 855 | globalCamera.cameraMetrics[CAM_NUM_IMAGE]++;
|
| 856 | printCounter ++;
|
| 857 | if (printCounter == 1000) {
|
| 858 | DPRINTF (LOG_DEBUG, "imageCounter = %i", globalCamera.cameraMetrics[CAM_NUM_IMAGE]);
|
| 859 | printCounter=0;
|
| 860 | }
|
| 861 |
|
| 862 | taskDelay(1);
|
| 863 |
|
| 864 | #if MEASURE_TIME
|
| 865 | loopEndTime = GetTime();
|
| 866 | performanceLoopCounter++;
|
| 867 | if (performanceLoopCounter <= maxCount) {
|
| 868 | DPRINTF (LOG_DEBUG, "%i DONE!!!: loop = ,%g, camera = ,%g, difference = ,%g, loopRate= ,%g,",
|
| 869 | performanceLoopCounter, loopEndTime-loopStartTime, cameraEndTime-cameraStartTime,
|
| 870 | (loopEndTime-loopStartTime) - (cameraEndTime-cameraStartTime),
|
| 871 | loopStartTime-previousStartTime);
|
| 872 | }
|
| 873 | #endif
|
| 874 | } /* end while (cont) */
|
| 875 |
|
| 876 | /* clean up */
|
| 877 | close (camSock);
|
| 878 | cont = 0;
|
| 879 | DPRINTF (LOG_INFO, "\nJPEG SERVER ENDING errorCode = %i\n", errorCode );
|
| 880 |
|
| 881 | return (OK);
|
| 882 | }
|
| 883 |
|
| 884 | /**
|
| 885 | * @brief Start signaling a task when new images are available
|
| 886 | * @param taskID number for task to get the signal
|
| 887 | */
|
| 888 | void StartImageSignal(int taskId) // Start issuing a SIGUSR1 signal to the specified taskId
|
| 889 | { globalCamera.readerPID = taskId; }
|
| 890 |
|
| 891 | /**
|
| 892 | * @brief Start serving images
|
| 893 | */
|
| 894 | void StartImageAcquisition()
|
| 895 | {
|
| 896 | globalCamera.cameraMetrics[CAM_STARTS]++;
|
| 897 | globalCamera.acquire = 1;
|
| 898 | DPRINTF(LOG_DEBUG, "starting acquisition");
|
| 899 | }
|
| 900 |
|
| 901 |
|
| 902 | /**
|
| 903 | * @brief Stop serving images
|
| 904 | */
|
| 905 | void StopImageAcquisition()
|
| 906 | { globalCamera.cameraMetrics[CAM_STOPS]++; globalCamera.acquire = 0; }
|
| 907 |
|
| 908 |
|
| 909 | /**
|
| 910 | * @brief This is the routine that is run when the task is spawned
|
| 911 | * It initializes the camera with the image settings passed in, and
|
| 912 | * starts image acquisition.
|
| 913 | * @param frames Frames per second
|
| 914 | * @param compression Camera image compression
|
| 915 | * @param resolution Camera image size
|
| 916 | * @param rotation Camera image rotation
|
| 917 | */
|
| 918 | static int initCamera(int frames, int compression, ImageResolution resolution, ImageRotation rotation)
|
| 919 | {
|
| 920 | //SetDebugFlag ( DEBUG_SCREEN_AND_FILE ) ;
|
| 921 |
|
| 922 | DPRINTF(LOG_DEBUG, "\n+++++ camera task starting: rotation = %i", (int)rotation);
|
| 923 | int errorCode;
|
| 924 |
|
| 925 | /* Initialize globalCamera area
|
| 926 | * Set decode to 1 - always want to decode images for processing
|
| 927 | * If ONLY sending images to the dashboard, you could set it to 0 */
|
| 928 | bzero ((char *)&globalCamera, sizeof(globalCamera));
|
| 929 | globalCamera.index = -1;
|
| 930 | globalCamera.decode = 1;
|
| 931 |
|
| 932 | /* allow writing to vxWorks target */
|
| 933 | Priv_SetWriteFileAllowed(1);
|
| 934 |
|
| 935 | /* start acquisition immediately */
|
| 936 | StartImageAcquisition();
|
| 937 |
|
| 938 | /* cameraJPEGServer runs until camera is stopped */
|
| 939 | DPRINTF (LOG_DEBUG, "calling cameraJPEGServer" );
|
| 940 | errorCode = cameraJPEGServer(frames, compression, resolution, rotation);
|
| 941 | DPRINTF (LOG_INFO, "errorCode from cameraJPEGServer = %i\n", errorCode );
|
| 942 | return (OK);
|
| 943 | }
|
| 944 |
|
| 945 | Task g_axisCameraTask("Camera", (FUNCPTR)initCamera);
|
| 946 |
|
| 947 | /**
|
| 948 | * @brief Start the camera task
|
| 949 | * @param frames Frames per second
|
| 950 | * @param compression Camera image compression
|
| 951 | * @param resolution Camera image size
|
| 952 | * @param rotation Camera image rotation (ROT_0 or ROT_180)
|
| 953 | * @return TaskID of camera task, or -1 if error.
|
| 954 | */
|
| 955 | int StartCameraTask()
|
| 956 | {
|
| 957 | return StartCameraTask(10, 0, k160x120, ROT_0);
|
| 958 | }
|
| 959 | int StartCameraTask(int frames, int compression, ImageResolution resolution, ImageRotation rotation)
|
| 960 | {
|
| 961 | char funcName[]="startCameraTask";
|
| 962 | DPRINTF(LOG_DEBUG, "starting camera");
|
| 963 |
|
| 964 | int cameraTaskID = 0;
|
| 965 |
|
| 966 | //range check
|
| 967 | if (frames < 1) frames = 1;
|
| 968 | else if (frames > 30) frames = 30;
|
| 969 | if (compression < 0) compression = 0;
|
| 970 | else if (compression > 100) compression = 100;
|
| 971 |
|
| 972 | // stop any prior copy of running task
|
| 973 | StopCameraTask();
|
| 974 |
|
| 975 | // spawn camera task
|
| 976 | bool started = g_axisCameraTask.Start(frames, compression, resolution, rotation);
|
| 977 | cameraTaskID = g_axisCameraTask.GetID();
|
| 978 | DPRINTF(LOG_DEBUG, "spawned task id %i", cameraTaskID);
|
| 979 |
|
| 980 | if (!started) {
|
| 981 | DPRINTF(LOG_DEBUG, "camera task failed to start");
|
| 982 | imaqSetError(ERR_CAMERA_TASK_SPAWN_FAILED, funcName);
|
| 983 | return -1;
|
| 984 | }
|
| 985 | return cameraTaskID;
|
| 986 | }
|
| 987 |
|
| 988 | /**
|
| 989 | * @brief Stops the camera task
|
| 990 | * @return TaskID of camera task killed, or -1 if none was running.
|
| 991 | */
|
| 992 | int StopCameraTask()
|
| 993 | {
|
| 994 | std::string taskName("FRC_Camera");
|
| 995 | // check for prior copy of running task
|
| 996 | int oldTaskID = taskNameToId(const_cast<char*>(taskName.c_str()));
|
| 997 | if(oldTaskID != ERROR) { taskDelete(oldTaskID); }
|
| 998 | return oldTaskID;
|
| 999 | }
|
| 1000 |
|
| 1001 | #if 0
|
| 1002 | /* if you want to run this task by itself to debug
|
| 1003 | * enable this code and make RunProgram the entry point
|
| 1004 | */
|
| 1005 | extern "C"
|
| 1006 | {
|
| 1007 | void RunProgram();
|
| 1008 | int AxisCamera_StartupLibraryInit();
|
| 1009 | }
|
| 1010 | /** * @brief Start point of the program */
|
| 1011 | void RunProgram()
|
| 1012 | { StartCameraTask();}
|
| 1013 |
|
| 1014 | /** * @brief This is the main program that is run by the debugger or the robot on boot. */
|
| 1015 | int AxisCamera_StartupLibraryInit()
|
| 1016 | { RunProgram(); return 0; }
|
| 1017 |
|
| 1018 | #endif
|
| 1019 |
|
| 1020 |
|
| 1021 |
|