00001
00037 #include <stdlib.h>
00038 #include <algorithm>
00039
00040 #include "details/utility/Functional.hh"
00041
00042 #include "details/channel.hh"
00043 #include "details/query.hh"
00044
00045 #include "details/wire/VersionRequestMessage.h"
00046 #include "details/wire/VersionResponseMessage.h"
00047 #include "details/wire/StatusRequestMessage.h"
00048 #include "details/wire/StatusResponseMessage.h"
00049
00050 #include "details/wire/StreamControlMessage.h"
00051 #include "details/wire/SysGetDirectedStreamsMessage.h"
00052 #include "details/wire/SysDirectedStreamsMessage.h"
00053
00054 #include "details/wire/CamControlMessage.h"
00055 #include "details/wire/CamSetResolutionMessage.h"
00056 #include "details/wire/CamGetConfigMessage.h"
00057 #include "details/wire/CamConfigMessage.h"
00058 #include "details/wire/CamSetTriggerSourceMessage.h"
00059
00060 #include "details/wire/LidarSetMotorMessage.h"
00061
00062 #include "details/wire/LedGetStatusMessage.h"
00063 #include "details/wire/LedSetMessage.h"
00064 #include "details/wire/LedStatusMessage.h"
00065
00066 #include "details/wire/SysMtuMessage.h"
00067 #include "details/wire/SysGetMtuMessage.h"
00068 #include "details/wire/SysFlashOpMessage.h"
00069 #include "details/wire/SysGetNetworkMessage.h"
00070 #include "details/wire/SysNetworkMessage.h"
00071 #include "details/wire/SysGetDeviceInfoMessage.h"
00072 #include "details/wire/SysDeviceInfoMessage.h"
00073 #include "details/wire/SysGetCameraCalibrationMessage.h"
00074 #include "details/wire/SysCameraCalibrationMessage.h"
00075 #include "details/wire/SysGetLidarCalibrationMessage.h"
00076 #include "details/wire/SysLidarCalibrationMessage.h"
00077 #include "details/wire/SysGetDeviceModesMessage.h"
00078 #include "details/wire/SysDeviceModesMessage.h"
00079
00080 #include "details/wire/ImuGetInfoMessage.h"
00081 #include "details/wire/ImuGetConfigMessage.h"
00082 #include "details/wire/ImuInfoMessage.h"
00083 #include "details/wire/ImuConfigMessage.h"
00084
00085 #include "details/wire/SysTestMtuMessage.h"
00086 #include "details/wire/SysTestMtuResponseMessage.h"
00087
00088 namespace crl {
00089 namespace multisense {
00090 namespace details {
00091
00092
00093
00094
00095
00096 CRL_THREAD_LOCAL utility::BufferStream *dispatchBufferReferenceTP = NULL;
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107 Status impl::addIsolatedCallback(image::Callback callback,
00108 DataSource imageSourceMask,
00109 void *userDataP)
00110 {
00111 try {
00112
00113 utility::ScopedLock lock(m_dispatchLock);
00114 m_imageListeners.push_back(new ImageListener(callback,
00115 imageSourceMask,
00116 userDataP,
00117 MAX_USER_IMAGE_QUEUE_SIZE));
00118
00119 } catch (const std::exception& e) {
00120 CRL_DEBUG("exception: %s\n", e.what());
00121 return Status_Exception;
00122 }
00123 return Status_Ok;
00124 }
00125
00126
00127
00128
00129 Status impl::addIsolatedCallback(lidar::Callback callback,
00130 void *userDataP)
00131 {
00132 try {
00133
00134 utility::ScopedLock lock(m_dispatchLock);
00135 m_lidarListeners.push_back(new LidarListener(callback,
00136 0,
00137 userDataP,
00138 MAX_USER_LASER_QUEUE_SIZE));
00139
00140 } catch (const std::exception& e) {
00141 CRL_DEBUG("exception: %s\n", e.what());
00142 return Status_Exception;
00143 }
00144 return Status_Ok;
00145 }
00146
00147
00148
00149
00150 Status impl::addIsolatedCallback(pps::Callback callback,
00151 void *userDataP)
00152 {
00153 try {
00154
00155 utility::ScopedLock lock(m_dispatchLock);
00156 m_ppsListeners.push_back(new PpsListener(callback,
00157 0,
00158 userDataP,
00159 MAX_USER_PPS_QUEUE_SIZE));
00160
00161 } catch (const std::exception& e) {
00162 CRL_DEBUG("exception: %s\n", e.what());
00163 return Status_Exception;
00164 }
00165 return Status_Ok;
00166 }
00167
00168
00169
00170
00171 Status impl::addIsolatedCallback(imu::Callback callback,
00172 void *userDataP)
00173 {
00174 try {
00175
00176 utility::ScopedLock lock(m_dispatchLock);
00177 m_imuListeners.push_back(new ImuListener(callback,
00178 0,
00179 userDataP,
00180 MAX_USER_IMU_QUEUE_SIZE));
00181
00182 } catch (const std::exception& e) {
00183 CRL_DEBUG("exception: %s\n", e.what());
00184 return Status_Exception;
00185 }
00186 return Status_Ok;
00187 }
00188
00189
00190
00191
00192 Status impl::removeIsolatedCallback(image::Callback callback)
00193 {
00194 try {
00195 utility::ScopedLock lock(m_dispatchLock);
00196
00197 std::list<ImageListener*>::iterator it;
00198 for(it = m_imageListeners.begin();
00199 it != m_imageListeners.end();
00200 it ++) {
00201
00202 if ((*it)->callback() == callback) {
00203 delete *it;
00204 m_imageListeners.erase(it);
00205 return Status_Ok;
00206 }
00207 }
00208
00209 } catch (const std::exception& e) {
00210 CRL_DEBUG("exception: %s\n", e.what());
00211 return Status_Exception;
00212 }
00213
00214 return Status_Error;
00215 }
00216
00217
00218
00219
00220 Status impl::removeIsolatedCallback(lidar::Callback callback)
00221 {
00222 try {
00223 utility::ScopedLock lock(m_dispatchLock);
00224
00225 std::list<LidarListener*>::iterator it;
00226 for(it = m_lidarListeners.begin();
00227 it != m_lidarListeners.end();
00228 it ++) {
00229
00230 if ((*it)->callback() == callback) {
00231 delete *it;
00232 m_lidarListeners.erase(it);
00233 return Status_Ok;
00234 }
00235 }
00236
00237 } catch (const std::exception& e) {
00238 CRL_DEBUG("exception: %s\n", e.what());
00239 return Status_Exception;
00240 }
00241
00242 return Status_Error;
00243 }
00244
00245
00246
00247
00248 Status impl::removeIsolatedCallback(pps::Callback callback)
00249 {
00250 try {
00251 utility::ScopedLock lock(m_dispatchLock);
00252
00253 std::list<PpsListener*>::iterator it;
00254 for(it = m_ppsListeners.begin();
00255 it != m_ppsListeners.end();
00256 it ++) {
00257
00258 if ((*it)->callback() == callback) {
00259 delete *it;
00260 m_ppsListeners.erase(it);
00261 return Status_Ok;
00262 }
00263 }
00264
00265 } catch (const std::exception& e) {
00266 CRL_DEBUG("exception: %s\n", e.what());
00267 return Status_Exception;
00268 }
00269
00270 return Status_Error;
00271 }
00272
00273
00274
00275
00276 Status impl::removeIsolatedCallback(imu::Callback callback)
00277 {
00278 try {
00279 utility::ScopedLock lock(m_dispatchLock);
00280
00281 std::list<ImuListener*>::iterator it;
00282 for(it = m_imuListeners.begin();
00283 it != m_imuListeners.end();
00284 it ++) {
00285
00286 if ((*it)->callback() == callback) {
00287 delete *it;
00288 m_imuListeners.erase(it);
00289 return Status_Ok;
00290 }
00291 }
00292
00293 } catch (const std::exception& e) {
00294 CRL_DEBUG("exception: %s\n", e.what());
00295 return Status_Exception;
00296 }
00297
00298 return Status_Error;
00299 }
00300
00301
00302
00303
00304 void *impl::reserveCallbackBuffer()
00305 {
00306 if (dispatchBufferReferenceTP) {
00307
00308 try {
00309
00310 return reinterpret_cast<void*>(new utility::BufferStream(*dispatchBufferReferenceTP));
00311
00312 } catch (const std::exception& e) {
00313
00314 CRL_DEBUG("exception: %s\n", e.what());
00315
00316 } catch (...) {
00317
00318 CRL_DEBUG("unknown exception\n");
00319 }
00320 }
00321
00322 return NULL;
00323 }
00324
00325
00326
00327
00328 Status impl::releaseCallbackBuffer(void *referenceP)
00329 {
00330 if (referenceP) {
00331 try {
00332
00333 delete reinterpret_cast<utility::BufferStream*>(referenceP);
00334 return Status_Ok;
00335
00336 } catch (const std::exception& e) {
00337
00338 CRL_DEBUG("exception: %s\n", e.what());
00339 return Status_Exception;
00340
00341 } catch (...) {
00342
00343 CRL_DEBUG("unknown exception\n");
00344 return Status_Exception;
00345 }
00346 }
00347
00348 return Status_Error;
00349 }
00350
00351
00352
00353
00354 Status impl::getImageHistogram(int64_t frameId,
00355 image::Histogram& histogram)
00356 {
00357 try {
00358
00359 utility::ScopedLock lock(m_imageMetaCache.mutex());
00360
00361 const wire::ImageMeta *metaP = m_imageMetaCache.find_nolock(frameId);
00362 if (NULL == metaP) {
00363 CRL_DEBUG("no meta cached for frameId %ld",
00364 static_cast<long int>(frameId));
00365 return Status_Failed;
00366 }
00367
00368 histogram.channels = wire::ImageMeta::HISTOGRAM_CHANNELS;
00369 histogram.bins = wire::ImageMeta::HISTOGRAM_BINS;
00370
00371 const int entries = histogram.channels * histogram.bins;
00372 const int sizeBytes = entries * sizeof(uint32_t);
00373
00374 histogram.data.resize(entries);
00375 memcpy(&(histogram.data[0]), metaP->histogramP, sizeBytes);
00376
00377 return Status_Ok;
00378
00379 } catch (const std::exception& e) {
00380 CRL_DEBUG("exception: %s\n", e.what());
00381 return Status_Exception;
00382 }
00383
00384 return Status_Error;
00385 }
00386
00387
00388
00389
00390 Status impl::networkTimeSynchronization(bool enabled)
00391 {
00392 m_networkTimeSyncEnabled = enabled;
00393 return Status_Ok;
00394 }
00395
00396
00397
00398
00399 Status impl::startStreams(DataSource mask)
00400 {
00401 utility::ScopedLock lock(m_streamLock);
00402
00403 wire::StreamControl cmd;
00404
00405 cmd.enable(sourceApiToWire(mask));
00406
00407 Status status = waitAck(cmd);
00408 if (Status_Ok == status)
00409 m_streamsEnabled |= mask;
00410
00411 return status;
00412 }
00413 Status impl::stopStreams(DataSource mask)
00414 {
00415 utility::ScopedLock lock(m_streamLock);
00416
00417 wire::StreamControl cmd;
00418
00419 cmd.disable(sourceApiToWire(mask));
00420
00421 Status status = waitAck(cmd);
00422 if (Status_Ok == status)
00423 m_streamsEnabled &= ~mask;
00424
00425 return status;
00426 }
00427 Status impl::getEnabledStreams(DataSource& mask)
00428 {
00429 utility::ScopedLock lock(m_streamLock);
00430
00431 mask = m_streamsEnabled;
00432
00433 return Status_Ok;
00434 }
00435
00436
00437
00438
00439 Status impl::startDirectedStream(const DirectedStream& stream)
00440 {
00441 wire::SysDirectedStreams cmd(wire::SysDirectedStreams::CMD_START);
00442
00443 cmd.streams.push_back(wire::DirectedStream(stream.mask,
00444 stream.address,
00445 stream.udpPort,
00446 stream.fpsDecimation));
00447 return waitAck(cmd);
00448 }
00449
00450 Status impl::startDirectedStreams(const std::vector<DirectedStream>& streams)
00451 {
00452 wire::SysDirectedStreams cmd(wire::SysDirectedStreams::CMD_START);
00453
00454 for (uint32_t index = 0 ; index < streams.size() ; ++index) {
00455 DirectedStream stream = streams[index];
00456
00457 cmd.streams.push_back(wire::DirectedStream(stream.mask,
00458 stream.address,
00459 stream.udpPort,
00460 stream.fpsDecimation));
00461 }
00462 return waitAck(cmd);
00463 }
00464
00465 Status impl::stopDirectedStream(const DirectedStream& stream)
00466 {
00467 wire::SysDirectedStreams cmd(wire::SysDirectedStreams::CMD_STOP);
00468
00469 cmd.streams.push_back(wire::DirectedStream(stream.mask,
00470 stream.address,
00471 stream.udpPort,
00472 stream.fpsDecimation));
00473 return waitAck(cmd);
00474 }
00475
00476 Status impl::getDirectedStreams(std::vector<DirectedStream>& streams)
00477 {
00478 Status status;
00479 wire::SysDirectedStreams rsp;
00480
00481 streams.clear();
00482
00483 status = waitData(wire::SysGetDirectedStreams(), rsp);
00484 if (Status_Ok != status)
00485 return status;
00486
00487 std::vector<wire::DirectedStream>::const_iterator it = rsp.streams.begin();
00488 for(; it != rsp.streams.end(); ++it)
00489 streams.push_back(DirectedStream((*it).mask,
00490 (*it).address,
00491 (*it).udpPort,
00492 (*it).fpsDecimation));
00493 return Status_Ok;
00494 }
00495
00496 Status impl::maxDirectedStreams(uint32_t& maximum)
00497 {
00498 maximum = MAX_DIRECTED_STREAMS;
00499 return Status_Ok;
00500 }
00501
00502
00503
00504
00505 Status impl::setTriggerSource(TriggerSource s)
00506 {
00507 uint32_t wireSource;
00508
00509 switch(s) {
00510 case Trigger_Internal:
00511
00512 wireSource = wire::CamSetTriggerSource::SOURCE_INTERNAL;
00513 break;
00514
00515 case Trigger_External:
00516
00517 wireSource = wire::CamSetTriggerSource::SOURCE_EXTERNAL;
00518 break;
00519
00520 default:
00521
00522 return Status_Error;
00523 }
00524
00525 return waitAck(wire::CamSetTriggerSource(wireSource));
00526 }
00527
00528
00529
00530
00531 Status impl::setMotorSpeed(float rpm)
00532 {
00533 return waitAck(wire::LidarSetMotor(rpm));
00534 }
00535
00536
00537
00538
00539 Status impl::getLightingConfig(lighting::Config& c)
00540 {
00541 Status status;
00542 wire::LedStatus data;
00543
00544 status = waitData(wire::LedGetStatus(), data);
00545 if (Status_Ok != status)
00546 return status;
00547
00548 for(uint32_t i=0; i<lighting::MAX_LIGHTS; i++) {
00549 float duty=0.0f;
00550 if ((1<<i) & data.available)
00551 duty = (data.intensity[i] * 100.0f) / 255;
00552 c.setDutyCycle(i, duty);
00553 }
00554
00555 c.setFlash(data.flash != 0);
00556
00557 return Status_Ok;
00558 }
00559
00560 Status impl::setLightingConfig(const lighting::Config& c)
00561 {
00562 wire::LedSet msg;
00563
00564 msg.flash = c.getFlash() ? 1 : 0;
00565 for(uint32_t i=0; i<lighting::MAX_LIGHTS; i++) {
00566
00567 float duty = c.getDutyCycle(i);
00568 if (duty >= 0.0f) {
00569 msg.mask |= (1<<i);
00570 msg.intensity[i] = static_cast<uint8_t> (255.0f * (utility::boundValue(duty, 0.0f, 100.0f) / 100.0f));
00571 }
00572 }
00573
00574 return waitAck(msg);
00575 }
00576
00577
00578
00579
00580 Status impl::getSensorVersion(VersionType& version)
00581 {
00582 version = m_sensorVersion.firmwareVersion;
00583 return Status_Ok;
00584 }
00585
00586
00587
00588
00589 Status impl::getApiVersion(VersionType& version)
00590 {
00591 version = API_VERSION;
00592 return Status_Ok;
00593 }
00594
00595
00596
00597
00598 Status impl::getVersionInfo(system::VersionInfo& v)
00599 {
00600 v.apiBuildDate = std::string(__DATE__ ", " __TIME__);
00601 v.apiVersion = API_VERSION;
00602 v.sensorFirmwareBuildDate = m_sensorVersion.firmwareBuildDate;
00603 v.sensorFirmwareVersion = m_sensorVersion.firmwareVersion;
00604 v.sensorHardwareVersion = m_sensorVersion.hardwareVersion;
00605 v.sensorHardwareMagic = m_sensorVersion.hardwareMagic;
00606 v.sensorFpgaDna = m_sensorVersion.fpgaDna;
00607
00608 return Status_Ok;
00609 }
00610
00611
00612
00613
00614 Status impl::getImageConfig(image::Config& config)
00615 {
00616 Status status;
00617 wire::CamConfig d;
00618
00619 status = waitData(wire::CamGetConfig(), d);
00620 if (Status_Ok != status)
00621 return status;
00622
00623
00624 class ConfigAccess : public image::Config {
00625 public:
00626 void setCal(float fx, float fy, float cx, float cy,
00627 float tx, float ty, float tz,
00628 float r, float p, float w) {
00629 m_fx = fx; m_fy = fy; m_cx = cx; m_cy = cy;
00630 m_tx = tx; m_ty = ty; m_tz = tz;
00631 m_roll = r; m_pitch = p; m_yaw = w;
00632 };
00633 };
00634
00635
00636 ConfigAccess& a = *((ConfigAccess *) &config);
00637
00638 a.setResolution(d.width, d.height);
00639 if (-1 == d.disparities) {
00640 if (1024 == d.width)
00641 d.disparities = 128;
00642 else
00643 d.disparities = 0;
00644 }
00645 a.setDisparities(d.disparities);
00646 a.setFps(d.framesPerSecond);
00647 a.setGain(d.gain);
00648
00649 a.setExposure(d.exposure);
00650 a.setAutoExposure(d.autoExposure != 0);
00651 a.setAutoExposureMax(d.autoExposureMax);
00652 a.setAutoExposureDecay(d.autoExposureDecay);
00653 a.setAutoExposureThresh(d.autoExposureThresh);
00654
00655 a.setWhiteBalance(d.whiteBalanceRed, d.whiteBalanceBlue);
00656 a.setAutoWhiteBalance(d.autoWhiteBalance != 0);
00657 a.setAutoWhiteBalanceDecay(d.autoWhiteBalanceDecay);
00658 a.setAutoWhiteBalanceThresh(d.autoWhiteBalanceThresh);
00659 a.setStereoPostFilterStrength(d.stereoPostFilterStrength);
00660 a.setHdr(d.hdrEnabled);
00661
00662 a.setCal(d.fx, d.fy, d.cx, d.cy,
00663 d.tx, d.ty, d.tz,
00664 d.roll, d.pitch, d.yaw);
00665
00666 return Status_Ok;
00667 }
00668
00669
00670
00671
00672
00673
00674
00675 Status impl::setImageConfig(const image::Config& c)
00676 {
00677 Status status;
00678
00679 status = waitAck(wire::CamSetResolution(c.width(),
00680 c.height(),
00681 c.disparities()));
00682 if (Status_Ok != status)
00683 return status;
00684
00685 wire::CamControl cmd;
00686
00687 cmd.framesPerSecond = c.fps();
00688 cmd.gain = c.gain();
00689
00690 cmd.exposure = c.exposure();
00691 cmd.autoExposure = c.autoExposure() ? 1 : 0;
00692 cmd.autoExposureMax = c.autoExposureMax();
00693 cmd.autoExposureDecay = c.autoExposureDecay();
00694 cmd.autoExposureThresh = c.autoExposureThresh();
00695
00696 cmd.whiteBalanceRed = c.whiteBalanceRed();
00697 cmd.whiteBalanceBlue = c.whiteBalanceBlue();
00698 cmd.autoWhiteBalance = c.autoWhiteBalance() ? 1 : 0;
00699 cmd.autoWhiteBalanceDecay = c.autoWhiteBalanceDecay();
00700 cmd.autoWhiteBalanceThresh = c.autoWhiteBalanceThresh();
00701 cmd.stereoPostFilterStrength = c.stereoPostFilterStrength();
00702 cmd.hdrEnabled = c.hdrEnabled();
00703
00704 return waitAck(cmd);
00705 }
00706
00707
00708
00709
00710 Status impl::getImageCalibration(image::Calibration& c)
00711 {
00712 wire::SysCameraCalibration d;
00713
00714 Status status = waitData(wire::SysGetCameraCalibration(), d);
00715 if (Status_Ok != status)
00716 return status;
00717
00718 CPY_ARRAY_2(c.left.M, d.left.M, 3, 3);
00719 CPY_ARRAY_1(c.left.D, d.left.D, 8);
00720 CPY_ARRAY_2(c.left.R, d.left.R, 3, 3);
00721 CPY_ARRAY_2(c.left.P, d.left.P, 3, 4);
00722
00723 CPY_ARRAY_2(c.right.M, d.right.M, 3, 3);
00724 CPY_ARRAY_1(c.right.D, d.right.D, 8);
00725 CPY_ARRAY_2(c.right.R, d.right.R, 3, 3);
00726 CPY_ARRAY_2(c.right.P, d.right.P, 3, 4);
00727
00728 return Status_Ok;
00729 }
00730
00731
00732
00733
00734 Status impl::setImageCalibration(const image::Calibration& c)
00735 {
00736 wire::SysCameraCalibration d;
00737
00738 CPY_ARRAY_2(d.left.M, c.left.M, 3, 3);
00739 CPY_ARRAY_1(d.left.D, c.left.D, 8);
00740 CPY_ARRAY_2(d.left.R, c.left.R, 3, 3);
00741 CPY_ARRAY_2(d.left.P, c.left.P, 3, 4);
00742
00743 CPY_ARRAY_2(d.right.M, c.right.M, 3, 3);
00744 CPY_ARRAY_1(d.right.D, c.right.D, 8);
00745 CPY_ARRAY_2(d.right.R, c.right.R, 3, 3);
00746 CPY_ARRAY_2(d.right.P, c.right.P, 3, 4);
00747
00748 return waitAck(d);
00749 }
00750
00751
00752
00753
00754 Status impl::getLidarCalibration(lidar::Calibration& c)
00755 {
00756 wire::SysLidarCalibration d;
00757
00758 Status status = waitData(wire::SysGetLidarCalibration(), d);
00759 if (Status_Ok != status)
00760 return status;
00761
00762 CPY_ARRAY_2(c.laserToSpindle, d.laserToSpindle, 4, 4);
00763 CPY_ARRAY_2(c.cameraToSpindleFixed, d.cameraToSpindleFixed, 4, 4);
00764
00765 return Status_Ok;
00766 }
00767
00768
00769
00770
00771 Status impl::setLidarCalibration(const lidar::Calibration& c)
00772 {
00773 wire::SysLidarCalibration d;
00774
00775 CPY_ARRAY_2(d.laserToSpindle, c.laserToSpindle, 4, 4);
00776 CPY_ARRAY_2(d.cameraToSpindleFixed, c.cameraToSpindleFixed, 4, 4);
00777
00778 return waitAck(d);
00779 }
00780
00781
00782
00783
00784 Status impl::getDeviceModes(std::vector<system::DeviceMode>& modes)
00785 {
00786 wire::SysDeviceModes d;
00787
00788 Status status = waitData(wire::SysGetDeviceModes(), d);
00789 if (Status_Ok != status)
00790 return Status_Error;
00791
00792 modes.resize(d.modes.size());
00793 for(uint32_t i=0; i<d.modes.size(); i++) {
00794
00795 system::DeviceMode& a = modes[i];
00796 const wire::DeviceMode& w = d.modes[i];
00797
00798 a.width = w.width;
00799 a.height = w.height;
00800 a.supportedDataSources = sourceWireToApi(w.supportedDataSources);
00801 if (m_sensorVersion.firmwareVersion >= 0x0203)
00802 a.disparities = w.disparities;
00803 else
00804 a.disparities = (a.width == 1024) ? 128 : 0;
00805 }
00806
00807 return Status_Ok;
00808 }
00809
00810
00811
00812
00813 Status impl::setMtu(int32_t mtu)
00814 {
00815 Status status = Status_Ok;
00816
00817
00818
00819
00820
00821
00822 if (m_sensorVersion.firmwareVersion <= 0x0202)
00823 status = waitAck(wire::SysMtu(mtu));
00824 else {
00825
00826 wire::SysTestMtuResponse resp;
00827 status = waitData(wire::SysTestMtu(mtu), resp);
00828 if (Status_Ok == status)
00829 status = waitAck(wire::SysMtu(mtu));
00830 }
00831
00832 if (Status_Ok == status)
00833 m_sensorMtu = mtu;
00834
00835 return status;
00836 }
00837
00838 Status impl::getMtu(int32_t& mtu)
00839 {
00840 wire::SysMtu resp;
00841
00842 Status status = waitData(wire::SysGetMtu(), resp);
00843 if (Status_Ok == status)
00844 mtu = resp.mtu;
00845
00846 return status;
00847 }
00848
00849
00850
00851
00852 Status impl::setNetworkConfig(const system::NetworkConfig& c)
00853 {
00854 return waitAck(wire::SysNetwork(c.ipv4Address,
00855 c.ipv4Gateway,
00856 c.ipv4Netmask));
00857 }
00858
00859 Status impl::getNetworkConfig(system::NetworkConfig& c)
00860 {
00861 wire::SysNetwork resp;
00862
00863 Status status = waitData(wire::SysGetNetwork(), resp);
00864 if (Status_Ok == status) {
00865 c.ipv4Address = resp.address;
00866 c.ipv4Gateway = resp.gateway;
00867 c.ipv4Netmask = resp.netmask;
00868 }
00869
00870 return status;
00871 }
00872
00873
00874
00875
00876 Status impl::getDeviceInfo(system::DeviceInfo& info)
00877 {
00878 wire::SysDeviceInfo w;
00879
00880 Status status = waitData(wire::SysGetDeviceInfo(), w);
00881 if (Status_Ok != status)
00882 return status;
00883
00884 info.name = w.name;
00885 info.buildDate = w.buildDate;
00886 info.serialNumber = w.serialNumber;
00887 info.hardwareRevision = hardwareWireToApi(w.hardwareRevision);
00888 info.pcbs.clear();
00889
00890 for(uint8_t i=0; i<w.numberOfPcbs; i++) {
00891 system::PcbInfo pcb;
00892
00893 pcb.name = w.pcbs[i].name;
00894 pcb.revision = w.pcbs[i].revision;
00895
00896 info.pcbs.push_back(pcb);
00897 }
00898
00899 info.imagerName = w.imagerName;
00900 info.imagerType = imagerWireToApi(w.imagerType);
00901 info.imagerWidth = w.imagerWidth;
00902 info.imagerHeight = w.imagerHeight;
00903 info.lensName = w.lensName;
00904 info.lensType = w.lensType;
00905 info.nominalBaseline = w.nominalBaseline;
00906 info.nominalFocalLength = w.nominalFocalLength;
00907 info.nominalRelativeAperture = w.nominalRelativeAperture;
00908 info.lightingType = w.lightingType;
00909 info.numberOfLights = w.numberOfLights;
00910 info.laserName = w.laserName;
00911 info.laserType = w.laserType;
00912 info.motorName = w.motorName;
00913 info.motorType = w.motorType;
00914 info.motorGearReduction = w.motorGearReduction;
00915
00916 return Status_Ok;
00917 }
00918
00919
00920
00921
00922 Status impl::setDeviceInfo(const std::string& key,
00923 const system::DeviceInfo& info)
00924 {
00925 wire::SysDeviceInfo w;
00926
00927 w.key = key;
00928 w.name = info.name;
00929 w.buildDate = info.buildDate;
00930 w.serialNumber = info.serialNumber;
00931 w.hardwareRevision = hardwareApiToWire(info.hardwareRevision);
00932 w.numberOfPcbs = std::min((uint32_t) info.pcbs.size(),
00933 (uint32_t) wire::SysDeviceInfo::MAX_PCBS);
00934 for(uint32_t i=0; i<w.numberOfPcbs; i++) {
00935 w.pcbs[i].name = info.pcbs[i].name;
00936 w.pcbs[i].revision = info.pcbs[i].revision;
00937 }
00938
00939 w.imagerName = info.imagerName;
00940 w.imagerType = imagerApiToWire(info.imagerType);
00941 w.imagerWidth = info.imagerWidth;
00942 w.imagerHeight = info.imagerHeight;
00943 w.lensName = info.lensName;
00944 w.lensType = info.lensType;
00945 w.nominalBaseline = info.nominalBaseline;
00946 w.nominalFocalLength = info.nominalFocalLength;
00947 w.nominalRelativeAperture = info.nominalRelativeAperture;
00948 w.lightingType = info.lightingType;
00949 w.numberOfLights = info.numberOfLights;
00950 w.laserName = info.laserName;
00951 w.laserType = info.laserType;
00952 w.motorName = info.motorName;
00953 w.motorType = info.motorType;
00954 w.motorGearReduction = info.motorGearReduction;
00955
00956 return waitAck(w);
00957 }
00958
00959
00960
00961
00962 Status impl::flashBitstream(const std::string& filename)
00963 {
00964 return doFlashOp(filename,
00965 wire::SysFlashOp::OP_PROGRAM,
00966 wire::SysFlashOp::RGN_BITSTREAM);
00967 }
00968
00969
00970
00971
00972 Status impl::flashFirmware(const std::string& filename)
00973 {
00974 return doFlashOp(filename,
00975 wire::SysFlashOp::OP_PROGRAM,
00976 wire::SysFlashOp::RGN_FIRMWARE);
00977 }
00978
00979
00980
00981
00982 Status impl::verifyBitstream(const std::string& filename)
00983 {
00984 return doFlashOp(filename,
00985 wire::SysFlashOp::OP_VERIFY,
00986 wire::SysFlashOp::RGN_BITSTREAM);
00987 }
00988
00989
00990
00991
00992 Status impl::verifyFirmware(const std::string& filename)
00993 {
00994 return doFlashOp(filename,
00995 wire::SysFlashOp::OP_VERIFY,
00996 wire::SysFlashOp::RGN_FIRMWARE);
00997 }
00998
00999
01000
01001
01002 Status impl::getImuInfo(uint32_t& maxSamplesPerMessage,
01003 std::vector<imu::Info>& info)
01004 {
01005 wire::ImuInfo w;
01006
01007 Status status = waitData(wire::ImuGetInfo(), w);
01008 if (Status_Ok != status)
01009 return status;
01010
01011
01012
01013
01014 maxSamplesPerMessage = w.maxSamplesPerMessage;
01015 info.resize(w.details.size());
01016 for(uint32_t i=0; i<w.details.size(); i++) {
01017
01018 const wire::imu::Details& d = w.details[i];
01019
01020 info[i].name = d.name;
01021 info[i].device = d.device;
01022 info[i].units = d.units;
01023
01024 info[i].rates.resize(d.rates.size());
01025 for(uint32_t j=0; j<d.rates.size(); j++) {
01026 info[i].rates[j].sampleRate = d.rates[j].sampleRate;
01027 info[i].rates[j].bandwidthCutoff = d.rates[j].bandwidthCutoff;
01028 }
01029 info[i].ranges.resize(d.ranges.size());
01030 for(uint32_t j=0; j<d.ranges.size(); j++) {
01031 info[i].ranges[j].range = d.ranges[j].range;
01032 info[i].ranges[j].resolution = d.ranges[j].resolution;
01033 }
01034 }
01035
01036 return Status_Ok;
01037 }
01038
01039
01040
01041
01042 Status impl::getImuConfig(uint32_t& samplesPerMessage,
01043 std::vector<imu::Config>& c)
01044 {
01045 wire::ImuConfig w;
01046
01047 Status status = waitData(wire::ImuGetConfig(), w);
01048 if (Status_Ok != status)
01049 return status;
01050
01051
01052
01053
01054 samplesPerMessage = w.samplesPerMessage;
01055 c.resize(w.configs.size());
01056 for(uint32_t i=0; i<w.configs.size(); i++) {
01057 c[i].name = w.configs[i].name;
01058 c[i].enabled = (w.configs[i].flags & wire::imu::Config::FLAGS_ENABLED);
01059 c[i].rateTableIndex = w.configs[i].rateTableIndex;
01060 c[i].rangeTableIndex = w.configs[i].rangeTableIndex;
01061 }
01062
01063 return Status_Ok;
01064 }
01065
01066
01067
01068
01069 Status impl::setImuConfig(bool storeSettingsInFlash,
01070 uint32_t samplesPerMessage,
01071 const std::vector<imu::Config>& c)
01072 {
01073 wire::ImuConfig w;
01074
01075
01076
01077
01078 w.storeSettingsInFlash = storeSettingsInFlash ? 1 : 0;
01079 w.samplesPerMessage = samplesPerMessage;
01080 w.configs.resize(c.size());
01081 for(uint32_t i=0; i<c.size(); i++) {
01082 w.configs[i].name = c[i].name;
01083 w.configs[i].flags = c[i].enabled ? wire::imu::Config::FLAGS_ENABLED : 0;
01084 w.configs[i].rateTableIndex = c[i].rateTableIndex;
01085 w.configs[i].rangeTableIndex = c[i].rangeTableIndex;
01086 }
01087
01088 return waitAck(w);
01089 }
01090
01091
01092
01093
01094 Status impl::getLargeBufferDetails(uint32_t& bufferCount,
01095 uint32_t& bufferSize)
01096 {
01097 bufferCount = RX_POOL_LARGE_BUFFER_COUNT;
01098 bufferSize = RX_POOL_LARGE_BUFFER_SIZE;
01099
01100 return Status_Ok;
01101 }
01102
01103
01104
01105
01106 Status impl::setLargeBuffers(const std::vector<uint8_t*>& buffers,
01107 uint32_t bufferSize)
01108 {
01109 if (buffers.size() < RX_POOL_LARGE_BUFFER_COUNT)
01110 CRL_DEBUG("WARNING: supplying less than recommended number of large buffers: %ld/%ld\n",
01111 static_cast<long int>(buffers.size()),
01112 static_cast<long int>(RX_POOL_LARGE_BUFFER_COUNT));
01113 if (bufferSize < RX_POOL_LARGE_BUFFER_SIZE)
01114 CRL_DEBUG("WARNING: supplying smaller than recommended large buffers: %ld/%ld bytes\n",
01115 static_cast<long int>(bufferSize),
01116 static_cast<long int>(RX_POOL_LARGE_BUFFER_SIZE));
01117
01118 try {
01119
01120 utility::ScopedLock lock(m_rxLock);
01121
01122
01123
01124
01125
01126 BufferPool::const_iterator it;
01127 for(it = m_rxLargeBufferPool.begin();
01128 it != m_rxLargeBufferPool.end();
01129 ++it)
01130 delete *it;
01131
01132 m_rxLargeBufferPool.clear();
01133
01134 for(uint32_t i=0; i<buffers.size(); i++)
01135 m_rxLargeBufferPool.push_back(new utility::BufferStreamWriter(buffers[i], bufferSize));
01136
01137 } catch (const std::exception& e) {
01138 CRL_DEBUG("exception: %s\n", e.what());
01139 return Status_Exception;
01140 }
01141
01142 return Status_Ok;
01143 }
01144
01145
01146
01147
01148 Status impl::getLocalUdpPort(uint16_t& port)
01149 {
01150 port = m_serverSocketPort;
01151 return Status_Ok;
01152 }
01153
01154 }}};