API
 
Loading...
Searching...
No Matches
zylaCtrl.hpp
Go to the documentation of this file.
1/** \file zylaCtrl.hpp
2 * \brief The MagAO-X Andor sCMOS camera controller.
3 *
4 * \author Jared R. Males (jaredmales@gmail.com)
5 *
6 * \ingroup zylaCtrl_files
7 */
8
9#ifndef zylaCtrl_hpp
10#define zylaCtrl_hpp
11
12
13
14
15
16
17#include "../../libMagAOX/libMagAOX.hpp" //Note this is included on command line to trigger pch
18#include "../../magaox_git_version.h"
19
20
21#include "atcore.h"
22#include "atutility.h"
23
24namespace MagAOX
25{
26namespace app
27{
28
29
30/** \defgroup zylaCtrl Andor sCMOS Camera
31 * \brief Control of an Andor sCMOS Camera.
32 *
33 * <a href="../handbook/operating/software/apps/zylaCtrl.html">Application Documentation</a>
34 *
35 * \ingroup apps
36 *
37 */
38
39/** \defgroup zylaCtrl_files Andor sCMOS Camera Files
40 * \ingroup zylaCtrl
41 */
42
43/** MagAO-X application to control an Andor sCMOS Camera
44 *
45 * \ingroup zylaCtrl
46 *
47 */
48class zylaCtrl : public MagAOXApp<>, public dev::stdCamera<zylaCtrl>, public dev::frameGrabber<zylaCtrl>, public dev::telemeter<zylaCtrl>
49{
50
51 friend class dev::stdCamera<zylaCtrl>;
52 friend class dev::frameGrabber<zylaCtrl>;
53 friend class dev::telemeter<zylaCtrl>;
54
55public:
56 /** \name app::dev Configurations
57 *@{
58 */
59 static constexpr bool c_stdCamera_tempControl = true; ///< app::dev config to tell stdCamera to expose temperature controls
60
61 static constexpr bool c_stdCamera_temp = true; ///< app::dev config to tell stdCamera to expose temperature
62
63 static constexpr bool c_stdCamera_readoutSpeed = false; ///< app::dev config to tell stdCamera to expose readout speed controls
64
65 static constexpr bool c_stdCamera_vShiftSpeed = false; ///< app:dev config to tell stdCamera to expose vertical shift speed control
66 static constexpr bool c_stdCamera_fanSpeed = false; ///< app::dev config to tell stdCamera not to expose fan-speed control
67
68 static constexpr bool c_stdCamera_emGain = false; ///< app::dev config to tell stdCamera to expose EM gain controls
69
70 static constexpr bool c_stdCamera_exptimeCtrl = true; ///< app::dev config to tell stdCamera to expose exposure time controls
71
72 static constexpr bool c_stdCamera_fpsCtrl = true; ///< app::dev config to tell stdCamera to expose FPS controls
73
74 static constexpr bool c_stdCamera_fps = true; ///< app::dev config to tell stdCamera not to expose FPS status
75
76 static constexpr bool c_stdCamera_synchro = false; ///< app::dev config to tell stdCamera to not expose synchro mode controls
77
78 static constexpr bool c_stdCamera_usesModes = false; ///< app:dev config to tell stdCamera not to expose mode controls
79
80 static constexpr bool c_stdCamera_usesROI = true; ///< app:dev config to tell stdCamera to expose ROI controls
81
82 static constexpr bool c_stdCamera_cropMode = false; ///< app:dev config to tell stdCamera to expose Crop Mode controls
83
84 static constexpr bool c_stdCamera_hasShutter = false; ///< app:dev config to tell stdCamera to expose shutter controls
85
86 static constexpr bool c_stdCamera_usesStateString = false; ///< app::dev confg to tell stdCamera to expose the state string property
87
88 static constexpr bool c_frameGrabber_flippable = false; ///< app:dev config to tell framegrabber this camera can not be flipped
89
90 ///@}
91
92protected:
93
94 /** \name configurable parameters
95 *@{
96 */
97
98 std::string m_serial; ///< The camera serial number. This is a required configuration parameter.
99
100 unsigned int m_imageTimeout {1000}; ///< Timeout for waiting on images [msec]. Default is 1000 msec.
101
102 ///@}
103
104 bool m_libInit {false}; ///< Flag indicating whether the AT library is initialized.
105
106 AT_H m_handle {AT_HANDLE_UNINITIALISED}; ///< The Andor API handle to the camera
107
108 std::vector<unsigned char*> m_inputBuffers;
109 size_t m_nextBuffer {0};
110
112
113 unsigned char* m_outputBuffer {nullptr};
114
116
117 wchar_t m_pixelEncoding[256];
118
120
121public:
122
123 ///Default c'tor
124 zylaCtrl();
125
126 ///Destructor
128
129 /// Setup the configuration system (called by MagAOXApp::setup())
130 virtual void setupConfig();
131
132 /// load the configuration system results (called by MagAOXApp::setup())
133 virtual void loadConfig();
134
135 /// Startup functions
136 /** Sets up the INDI vars.
137 *
138 */
139 virtual int appStartup();
140
141 /// Implementation of the FSM for the Siglent SDG
142 virtual int appLogic();
143
144 /// Implementation of the on-power-off FSM logic
145 virtual int onPowerOff();
146
147 /// Implementation of the while-powered-off FSM
149
150 /// Do any needed shutdown tasks. Currently nothing in this app.
151 virtual int appShutdown();
152
153
154 /// Select the camera with the desired serial number.
155 int cameraSelect();
156
157
158 int getTemp();
159
160 int getExpTime();
161
162 int getFPS();
163
164
165 /** \name stdCamera Interface
166 *
167 * @{
168 */
169
170 /// Set defaults for a power on state.
171 /**
172 * \returns 0 on success
173 * \returns -1 on error
174 */
175 int powerOnDefaults();
176
177 /// Turn temperature control on or off.
178 /** Sets temperature control on or off based on the current value of m_tempControlStatus
179 * \returns 0 on success
180 * \returns -1 on error
181 */
182 int setTempControl();
183
184 /// Set the CCD temperature setpoint [stdCamera interface].
185 /** Sets the temperature to m_ccdTempSetpt.
186 * \returns 0 on success
187 * \returns -1 on error
188 */
189 int setTempSetPt();
190
191 /// Set the frame rate. [stdCamera interface]
192 /** Sets the frame rate to m_fpsSet.
193 *
194 * \returns 0 on success
195 * \returns -1 on error
196 */
197 int setFPS();
198
199 /// Required by stdCamera, but this does not do anything for this camera [stdCamera interface]
200 /**
201 * \returns 0 always
202 */
203 int setExpTime();
204
205 /// Required by stdCamera, checks the next ROI [stdCamera interface]
206 /** Checks if the target values are valid and adjusts them to the closest valid values if needed.
207 *
208 * \returns 0 if successful
209 * \returns -1 on error
210 */
211 int checkNextROI();
212
213 /// Required by stdCamera, but this does not do anything for this camera [stdCamera interface]
214 /**
215 * \returns 0 always
216 */
217 int setNextROI();
218
219 /// Required by stdCamera, but this does not do anything for this camera [stdCamera interface]
220 /**
221 * \returns 0 always
222 */
223 int setShutter(int sh);
224
225 ///@}
226
227
228
229 /** \name framegrabber Interface
230 *
231 * @{
232 */
233
235 float fps()
236 {
237 return m_fps;
238 }
239
240 int startAcquisition();
242 int loadImageIntoStream(void * dest);
243 int reconfig();
244
245 ///@}
246
247 /** \name Telemeter Interface
248 *
249 * @{
250 */
251 int checkRecordTimes();
252
253 int recordTelem( const telem_stdcam * );
254
255
256 ///@}
257
258};
259
260inline
261zylaCtrl::zylaCtrl() : MagAOXApp(MAGAOX_CURRENT_SHA1, MAGAOX_REPO_MODIFIED)
262{
263 m_powerMgtEnabled = true;
264 m_powerOnWait = 10;
265
266
267 m_startupTemp = 20;
268
269 m_expTimeSet = 0.05; //Set default for startup
270 m_fpsSet = 20; //Set default for startup
271
272 m_startup_x = 1075;
273 m_startup_y = 975;
274 m_startup_w = 128;
275 m_startup_h = 128;
276 m_startup_bin_x = 1;
277 m_startup_bin_y = 1;
278
279 m_full_x = 1023.5;
280 m_full_y = 1023.5;
281 m_full_w = 2048;
282 m_full_h = 2048;
283
284 return;
285}
286
287inline
289{
290 for(size_t n=0; n < m_inputBuffers.size(); ++n)
291 {
293 }
294
295 return;
296}
297
298inline
300{
302
303 config.add("camera.serial", "", "camera.serial", argType::Required, "camera", "serial", false, "string", "The camera serial number.");
304
307
308}
309
310
311
312inline
314{
316
317 config(m_serial, "camera.serial");
318
321}
322
323
324
325inline
327{
328 m_minROIx = 0;
329 m_maxROIx = 2047;
330 m_stepROIx = 0;
331
332 m_minROIy = 0;
333 m_maxROIy = 2047;
334 m_stepROIy = 0;
335
336 m_minROIWidth = 1;
337 m_maxROIWidth = 2048;
338 m_stepROIWidth = 4;
339
340 m_minROIHeight = 1;
341 m_maxROIHeight = 2048;
342 m_stepROIHeight = 1;
343
347
349 m_maxROIBinning_y = 1024;
351
353 {
355 }
356
358 {
360 }
361
363 {
364 return log<software_error,-1>({__FILE__,__LINE__});
365 }
366
367 m_inputBuffers.resize(3);
368 for(size_t n =0; n < m_inputBuffers.size(); ++n)
369 {
370 m_inputBuffers[n] = nullptr;
371 }
372 m_nextBuffer = 0;
373
375
376 return 0;
377
378}
379
380
381inline
383{
384 //and run stdCamera's appLogic
386 {
387 return log<software_error, -1>({__FILE__, __LINE__});
388 }
389
390 //first run frameGrabber's appLogic to see if the f.g. thread has exited.
392 {
393 return log<software_error, -1>({__FILE__, __LINE__});
394 }
395
396 if( state() == stateCodes::POWERON) return 0;
397
399 {
400 //Might have gotten here because of a power off.
401 if(m_powerState == 0) return 0;
402
403 int ret = cameraSelect();
404
405 if( ret != 0) //Probably not powered on yet.
406 {
407 sleep(1);
408 return 0;
409 }
410
412
413
414 }
415
417 {
418 //Get a lock
419 std::unique_lock<std::mutex> lock(m_indiMutex);
420
422
425
426 }
427
429 {
430 //Get a lock if we can
431 std::unique_lock<std::mutex> lock(m_indiMutex, std::try_to_lock);
432
433 //but don't wait for it, just go back around.
434 if(!lock.owns_lock()) return 0;
435
436 if(getTemp() < 0)
437 {
438 if(m_powerState == 0) return 0;
439
441 return 0;
442 }
443
444 if(getExpTime() < 0)
445 {
446 if(m_powerState == 0) return 0;
447
449 return 0;
450 }
451
452 if(getFPS() < 0)
453 {
454 if(m_powerState == 0) return 0;
455
457 return 0;
458 }
459
461 {
463 }
464
466 {
468 }
469
471 {
473 return 0;
474 }
475
476 }
477
478 //Fall through check?
479
480 return 0;
481
482}
483
484inline
486{
488
490 {
493 }
494
495 if(m_libInit)
496 {
499
500 m_libInit = false;
501 }
502
503 std::lock_guard<std::mutex> lock(m_indiMutex);
504
506
507 return 0;
508}
509
510inline
512{
513 std::lock_guard<std::mutex> lock(m_indiMutex);
514
516
517 return 0;
518}
519
520inline
522{
525
527 {
530 }
531
532 if(m_libInit)
533 {
536
537 m_libInit = false;
538 }
539
540
541
542 return 0;
543}
544
545inline
547{
548 int iErr;
549
551 {
552 log<software_warning>({__FILE__, __LINE__, "handle initialized on call to cameraSelect. Attempting to close and go on."});
553
555 if(iErr != AT_SUCCESS)
556 {
557 log<software_error>({__FILE__, __LINE__, "Error from AT_Close: " + std::to_string(iErr) + ". Attempting to go on." });
559 }
560 }
561
562 if(m_libInit)
563 {
565 if(iErr != AT_SUCCESS )
566 {
567 return log<software_critical,-1>({__FILE__, __LINE__, "Error from AT_FinaliseLibrary: " + std::to_string(iErr)});
568 }
570 if(iErr != AT_SUCCESS )
571 {
572 return log<software_critical,-1>({__FILE__, __LINE__, "Error from AT_FinaliseUtilityLibrary: " + std::to_string(iErr)});
573 }
574
575 m_libInit = false;
576 }
577
579 if( iErr != AT_SUCCESS )
580 {
581 return log<software_critical,-1>({__FILE__, __LINE__, "Error from AT_InitialiseLibrary: " + std::to_string(iErr)});
582 }
583
585 if( iErr != AT_SUCCESS )
586 {
587 return log<software_critical,-1>({__FILE__, __LINE__, "Error from AT_InitialiseUtilityLibrary: " + std::to_string(iErr)});
588 }
589
590 m_libInit = true;
591
592 long long DeviceCount = 0;
593
594 iErr = AT_GetInt(AT_HANDLE_SYSTEM, L"Device Count", &DeviceCount);
595
596 if (iErr != AT_SUCCESS)
597 {
598 return log<software_critical,-1>({__FILE__,__LINE__, "Error from AT_GetInt('Device Count'): " + std::to_string(iErr)});
599 }
600
601 std::cout << "Found " << DeviceCount << " Devices." << std::endl;
602
603 for (long long i=0; i<DeviceCount; i++)
604 {
606
607 iErr = AT_Open(static_cast<int>(i), &Hndl);
608
609 if (iErr != AT_SUCCESS)
610 {
611 return log<software_critical,-1>({__FILE__,__LINE__, "Error from AT_Open(): " + std::to_string(iErr)});
612 }
613
614 AT_WC CameraSerial[128];
615
616 iErr = AT_GetString(Hndl, L"SerialNumber", CameraSerial, 128);
617
618 if (iErr != AT_SUCCESS)
619 {
620 return log<software_critical,-1>({__FILE__,__LINE__, "Error from AT_GetString('SerialNumber'): " + std::to_string(iErr)});
621 }
622
623 char camSerial[128];
625
626 if(m_serial != camSerial)
627 {
628 iErr = AT_Close(Hndl);
629 if (iErr != AT_SUCCESS)
630 {
631 log<software_error>({__FILE__,__LINE__, "Error from AT_Close(): " + std::to_string(iErr)});
632 }
633
634 continue;
635 }
636
637 AT_WC CameraModel[128];
638
639 iErr = AT_GetString(Hndl, L"Camera Model", CameraModel, 128);
640
641 if (iErr != AT_SUCCESS)
642 {
643 return log<software_critical,-1>({__FILE__,__LINE__, "Error from AT_GetString('Camera Model'): " + std::to_string(iErr)});
644 }
645
646 char camModel[128];
648
649 log<text_log>({std::string("Found ") + camModel + " serial number " + m_serial}, logPrio::LOG_NOTICE);
650
651 m_handle = Hndl;
652 return 0;
653 }
654
655 log<text_log>({"Camera with serial number " + m_serial + " not found in " + std::to_string(DeviceCount) + "devices."}, logPrio::LOG_WARNING);
656
660
661 m_libInit = false;
662
663 return -1;
664
665}
666
667inline
669{
671 wchar_t temperatureStatus[256];
672 int rv = AT_GetEnumIndex(m_handle, L"TemperatureStatus", &temperatureStatusIndex);
673 if (rv != AT_SUCCESS)
674 {
675 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_EnumIndex('TemperatureStatus'): " + std::to_string(rv)});
676 }
677
679 if (rv != AT_SUCCESS)
680 {
681 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_EnumStringByIndex('TemperatureStatus'): " + std::to_string(rv)});
682 }
683
684 if(wcscmp(L"Stabilised",temperatureStatus) == 0)
685 {
686 m_tempControlStatusStr="Stabilised";
687 m_tempControlStatus = true;
689 }
690 else if(wcscmp(L"Cooler Off",temperatureStatus) == 0)
691 {
692 m_tempControlStatusStr="Cooler Off";
693 m_tempControlStatus = false;
694 m_tempControlOnTarget = false;
695 }
696 else if(wcscmp(L"Cooling",temperatureStatus) == 0)
697 {
698 m_tempControlStatusStr="Cooling";
699 m_tempControlStatus = true;
700 m_tempControlOnTarget = false;
701 }
702 else if(wcscmp(L"Drift",temperatureStatus) == 0)
703 {
705 m_tempControlStatus = true;
706 m_tempControlOnTarget = false;
707 }
708 else if(wcscmp(L"Not Stabilised",temperatureStatus) == 0)
709 {
710 m_tempControlStatusStr="Not Stabilised";
711 m_tempControlStatus = true;
712 m_tempControlOnTarget = false;
713 }
714 else if(wcscmp(L"Fault",temperatureStatus) == 0)
715 {
717 m_tempControlStatus = false;
718 m_tempControlOnTarget = false;
719 }
720 else
721 {
722 m_tempControlStatusStr="Unknown";
723 m_tempControlStatus = false;
724 m_tempControlOnTarget = false;
725 }
726
727 double val;
728 rv = AT_GetFloat(m_handle, L"SensorTemperature", &val);
729 if (rv != AT_SUCCESS)
730 {
731 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetFloat('SensorTemperature'): " + std::to_string(rv)});
732 }
733
734 m_ccdTemp = val;
735
736 //Check if we have the right target, and set it if not.
737 rv = AT_GetFloat(m_handle, L"TargetSensorTemperature", &val);
738 if (rv != AT_SUCCESS)
739 {
740 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetFloat('TargetSensorTemperature'): " + std::to_string(rv)});
741 }
742
744
745 recordCamera();
746
747 return 0;
748}
749
750inline
752{
753 return 0;
754
755}
756
757inline
759{
760 return 0;
761
762}
763
764
765//------------------------------------------------------------------------
766//----------------------- stdCamera interface ---------------------------
767//------------------------------------------------------------------------
768
769inline
771{
772 //Camera boots up with this true in most cases.
774 m_tempControlStatus =false;
775
776 m_ccdTempSetpt = 0; //This is the power on setpoint
777
784
785 return 0;
786}
787
788inline
790{
791 if(m_tempControlStatusSet == true)
792 {
793 int rv = AT_SetBool(m_handle, L"SensorCooling", AT_TRUE);
794 if(rv != AT_SUCCESS)
795 {
796 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetBool(<SensorCooling>): " + std::to_string(rv)});
797 }
798 log<text_log>({"cooling on"}, logPrio::LOG_NOTICE);
799 }
800 else
801 {
802 int rv = AT_SetBool(m_handle, L"SensorCooling", AT_FALSE);
803 if(rv != AT_SUCCESS)
804 {
805 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetBool(<SensorCooling>): " + std::to_string(rv)});
806 log<text_log>({"cooling off"}, logPrio::LOG_NOTICE);
807 }
808 }
809
810 recordCamera();
811 return 0;
812}
813
814inline
816{
817 std::cerr << "setTempSetPt is not implemented\n";
818 return 0;
819}
820
821inline
823{
824 std::cerr << "Set exposure time\n";
825 m_reconfig = true;
826 return 0;
827}
828
829inline
831{
832 std::cerr << "setFPS\n";
833 m_reconfig = true;
834 return 0;
835}
836
837inline
839{
840 return 0;
841}
842
843inline
845{
846 std::cerr << "setNextROI:\n";
847 std::cerr << " m_nextROI.x = " << m_nextROI.x << "\n";
848 std::cerr << " m_nextROI.y = " << m_nextROI.y << "\n";
849 std::cerr << " m_nextROI.w = " << m_nextROI.w << "\n";
850 std::cerr << " m_nextROI.h = " << m_nextROI.h << "\n";
851 std::cerr << " m_nextROI.bin_x = " << m_nextROI.bin_x << "\n";
852 std::cerr << " m_nextROI.bin_y = " << m_nextROI.bin_y << "\n";
853
854 m_reconfig = true;
855
856 updateSwitchIfChanged(m_indiP_roi_set, "request", pcf::IndiElement::Off, INDI_IDLE);
857
858 return 0;
859}
860
861inline
863{
864 static_cast<void>(sh);
865
866 return 0;
867}
868
869//------------------------------------------------------------------------
870//------------------- framegrabber interface ---------------------------
871//------------------------------------------------------------------------
872
873inline
875{
876 int rv;
877
879 {
880 log<software_error>({__FILE__, __LINE__, "camer or AT not initialized on configureAcquisition()."});
881 return -1;
882 }
883
884 //lock mutex
885 std::unique_lock<std::mutex> lock(m_indiMutex);
886
887
889 AT_GetBool(m_handle, L"FullAOIControl", &faoi);
890 std::cerr << "FullAOIControl: " << std::boolalpha << faoi << "\n";
891
892 //Configure ROI:
893 AT_64 xbin = m_nextROI.bin_x;
894 AT_64 ybin = m_nextROI.bin_y;
895 AT_64 left= (m_nextROI.x - 0.5*( (float) m_nextROI.w - 1.0)) + 1;
896 AT_64 top = (m_nextROI.y - 0.5*( (float) m_nextROI.h - 1.0)) + 1;
897 AT_64 width = m_nextROI.w;
898 AT_64 height = m_nextROI.h;
899
900 std::cerr << xbin << " " << ybin << " " << left << " " << top << " " << width << " " << height << " " << "\n";
901
902 rv = AT_SetInt(m_handle, L"AOIHBin", xbin);
903 if(rv != AT_SUCCESS)
904 {
905 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOIHBin>): [" + std::to_string(xbin) + "] err: " + std::to_string(rv)});
906 }
907
908 rv = AT_SetInt(m_handle, L"AOIVBin", ybin);
909 if(rv != AT_SUCCESS)
910 {
911 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOIVBin>): [" + std::to_string(ybin) + "] err: " + std::to_string(rv)});
912 }
913
914 rv = AT_SetInt(m_handle, L"AOIWidth", width);
915 if(rv != AT_SUCCESS)
916 {
917 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOIWidth>): [" + std::to_string(width) + "] err: " + std::to_string(rv)});
918 }
919
920 rv = AT_SetInt(m_handle, L"AOILeft", left);
921 if(rv != AT_SUCCESS)
922 {
923 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOILeft>): [" + std::to_string(left) + "] err: " + std::to_string(rv)});
924 }
925
926 rv = AT_SetInt(m_handle, L"AOIHeight", height);
927 if(rv != AT_SUCCESS)
928 {
929 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOIHeight>): [" + std::to_string(height) + "] err: " + std::to_string(rv)});
930 }
931
932 rv = AT_SetInt(m_handle, L"AOITop", top);
933 if(rv != AT_SUCCESS)
934 {
935 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOITop>): [" + std::to_string(top) + "] err: " + std::to_string(rv)});
936 }
937
938 //Get Detector dimensions
940
941 rv = AT_GetInt(m_handle, L"AOI Left", &left);
942 if(rv != AT_SUCCESS)
943 {
944 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Left>): " + std::to_string(rv)});
945 }
946
947 rv = AT_GetInt(m_handle, L"AOI Top", &top);
948 if(rv != AT_SUCCESS)
949 {
950 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Top>): " + std::to_string(rv)});
951 }
952
953 rv = AT_GetInt(m_handle, L"AOI Width", &width);
954 if(rv != AT_SUCCESS)
955 {
956 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Width>): " + std::to_string(rv)});
957 }
958
959 rv = AT_GetInt(m_handle, L"AOI Height", &height);
960 if(rv != AT_SUCCESS)
961 {
962 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Height>): " + std::to_string(rv)});
963 }
964
965 m_currentROI.x = left + 0.5*( (float) (width - 1.0)) ;
966 m_currentROI.y = top + 0.5*( (float) (height - 1.0)) ;
967
968 m_currentROI.w = width;
969 m_currentROI.h = height;
970
977
978 rv = AT_GetInt(m_handle, L"AOI Stride", &stride);
979 if(rv != AT_SUCCESS)
980 {
981 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Stride>): " + std::to_string(rv)});
982 }
983
984 m_width = static_cast<int>(width);
985 m_height = static_cast<int>(height);
986 m_stride = static_cast<int>(stride);
988
989 //Free the API buffer
990 for(size_t n =0; n < m_inputBuffers.size(); ++n)
991 {
992 if(m_inputBuffers[n])
993 {
995 m_inputBuffers[n] = nullptr;
996 }
998 }
999
1000 //Get the number of bytes required to store one frame
1002 rv = AT_GetInt(m_handle, L"ImageSizeBytes", &ImageSizeBytes);
1003 if(rv != AT_SUCCESS)
1004 {
1005 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<ImageSizeBytes>): " + std::to_string(rv)});
1006 }
1007
1008 m_inputBufferSize = static_cast<int>(ImageSizeBytes);
1009
1010 //Allocate a memory buffer to store one frame
1011 for(size_t n =0; n < m_inputBuffers.size(); ++n)
1012 {
1013 m_inputBuffers[n] = (unsigned char *) malloc(m_inputBufferSize * sizeof(unsigned char));
1014 }
1015
1016 rv = AT_Flush(m_handle);
1017 if(rv != AT_SUCCESS)
1018 {
1019 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_Flush " + std::to_string(rv)});
1020 }
1021
1022 //Pass this buffer to the SDK
1023 for(size_t n =0; n < m_inputBuffers.size(); ++n)
1024 {
1026 if(rv != AT_SUCCESS)
1027 {
1028 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_QueueBuffer: " + std::to_string(rv)});
1029 }
1030 }
1031 m_nextBuffer = 0;
1032
1033 AT_SetFloat(m_handle, L"ExposureTime", m_expTimeSet);
1034 if(rv != AT_SUCCESS)
1035 {
1036 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetFloat(<ExposureTime>): " + std::to_string(rv)});
1037 }
1039
1040 AT_SetFloat(m_handle, L"FrameRate", m_fpsSet);
1041 if(rv != AT_SUCCESS)
1042 {
1043 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetFloat(<FrameRate>): " + std::to_string(rv)});
1044 }
1045 m_fps = m_fpsSet;
1046
1047 int pixelEncodingIndex = 0;
1048
1049 AT_GetEnumIndex(m_handle, L"PixelEncoding", &pixelEncodingIndex);
1051
1052 std::wcout << m_pixelEncoding << "\n";
1053
1054 //Set the camera to continuously acquire frames
1055 rv = AT_SetEnumString(m_handle, L"CycleMode", L"Continuous");
1056 if(rv != AT_SUCCESS)
1057 {
1058 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetEnumString(<CycleMode-Continuous>): " + std::to_string(rv)});
1059 }
1060
1061 log<text_log>({"Camera configured for continous acquistion with " + std::to_string(m_width) + "x" + std::to_string(m_height)});
1062
1063 recordCamera(true); //Force so it is logged before starting acq.
1064
1065 return 0;
1066}
1067
1068inline
1070{
1071 //Start the Acquisition running
1072 int rv = AT_Command(m_handle, L"AcquisitionStart");
1073
1074 if(rv != AT_SUCCESS)
1075 {
1076 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_Command(<AcquisitionStart>): " + std::to_string(rv)});
1077 }
1078
1079 log<text_log>("Acqusition started");
1080
1081 return 0;
1082}
1083
1084inline
1086{
1088
1089 if(rv == AT_ERR_TIMEDOUT)
1090 {
1091 return 1;
1092 }
1093
1095
1096
1097 if(rv != AT_SUCCESS )
1098 {
1099 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_WaitBuffer: " + std::to_string(rv)});
1100 }
1101
1103 {
1104 return log<software_error,-1>({__FILE__,__LINE__, "Wrong buffer size returned"});
1105 }
1106
1107 return 0;
1108}
1109
1110inline
1112{
1113 if(m_outputBuffer == nullptr) return -1;
1114
1116
1118 {
1119 std::cerr << "buffer skip!\n";
1121 {
1122 ++m_nextBuffer;
1123 if(m_nextBuffer >= m_inputBuffers.size()) m_nextBuffer = 0;
1124 }
1125 }
1126
1128 if(rv != AT_SUCCESS)
1129 {
1130 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_QueueBuffer: " + std::to_string(rv)});
1131 }
1132
1133 //Pass the buffer to the SDK
1134 ++m_nextBuffer;
1135 if(m_nextBuffer >= m_inputBuffers.size()) m_nextBuffer = 0;
1136
1137
1138 return 0;
1139}
1140
1141inline
1143{
1144 //lock mutex
1145 std::unique_lock<std::mutex> lock(m_indiMutex);
1146
1147 recordCamera(true); //force so it is logged before stopping acq.
1148
1149 //Start the Acquisition running
1150 int rv = AT_Command(m_handle, L"AcquisitionStop");
1151 if(rv != AT_SUCCESS)
1152 {
1153 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_Command(<AcquisitionStop>): " + std::to_string(rv)});
1154 }
1155 log<text_log>("Acqusition stopped");
1156
1157 rv = AT_Flush(m_handle);
1158 if(rv != AT_SUCCESS)
1159 {
1160 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_Fluxh : " + std::to_string(rv)});
1161 }
1162
1163 return 0;//edtCamera<zylaCtrl>::pdvReconfig();
1164}
1165
1170
1172{
1173 return recordCamera(true);
1174}
1175
1176}//namespace app
1177} //namespace MagAOX
1178#endif
The base-class for XWCTk applications.
void updateIfChanged(pcf::IndiProperty &p, const std::string &el, const T &newVal, pcf::IndiProperty::PropertyStateType ipState=pcf::IndiProperty::Ok)
Update an INDI property element value if it has changed.
stateCodes::stateCodeT state()
Get the current state code.
int m_powerState
Current power state, 1=On, 0=Off, -1=Unk.
void updateSwitchIfChanged(pcf::IndiProperty &p, const std::string &el, const pcf::IndiElement::SwitchStateType &newVal, pcf::IndiProperty::PropertyStateType ipState=pcf::IndiProperty::Ok)
Update an INDI switch element value if it has changed.
static int log(const typename logT::messageT &msg, logPrioT level=logPrio::LOG_DEFAULT)
Make a log entry.
unsigned long m_powerOnWait
Default time in sec to wait for device to boot after power on.
std::mutex m_indiMutex
Mutex for locking INDI communications.
timespec m_currImageTimestamp
The timestamp of the current image.
uint32_t m_width
The width of the image, once deinterlaced etc.
int appShutdown()
Shuts down the framegrabber thread.
int loadConfig(mx::app::appConfigurator &config)
load the configuration system results
uint8_t m_dataType
The ImageStreamIO type code.
bool m_reconfig
Flag to set if a camera reconfiguration requires a framegrabber reset.
uint32_t m_height
The height of the image, once deinterlaced etc.
int setupConfig(mx::app::appConfigurator &config)
Setup the configuration system.
MagAO-X standard camera interface.
float m_fpsSet
The commanded fps, as set by user.
pcf::IndiProperty m_indiP_roi_y
Property used to set the ROI x center coordinate.
std::string m_tempControlStatusStr
Camera specific description of temperature control status.
float m_expTime
The current exposure time, in seconds.
float m_expTimeSet
The exposure time, in seconds, as set by user.
pcf::IndiProperty m_indiP_roi_h
Property used to set the ROI height.
float m_full_y
The full ROI center y coordinate.
float m_ccdTempSetpt
The desired temperature, in C.
bool m_tempControlStatus
Whether or not temperature control is active.
int setupConfig(mx::app::appConfigurator &config)
Setup the configuration system.
pcf::IndiProperty m_indiP_roi_w
Property used to set the ROI width.
pcf::IndiProperty m_indiP_roi_bin_x
Property used to set the ROI x binning.
float m_full_x
The full ROI center x coordinate.
float m_startupTemp
The temperature to set after a power-on. Set to <= -999 to not use [default].
int loadConfig(mx::app::appConfigurator &config)
load the configuration system results
float m_ccdTemp
The current temperature, in C.
bool m_tempControlOnTarget
Whether or not the temperature control system is on its target temperature.
pcf::IndiProperty m_indiP_roi_set
Property used to trigger setting the ROI.
int appShutdown()
Application shutdown.
pcf::IndiProperty m_indiP_roi_bin_y
Property used to set the ROI y binning.
pcf::IndiProperty m_indiP_roi_x
Property used to set the ROI x center coordinate.
bool m_tempControlStatusSet
Desired state of temperature control.
static constexpr bool c_stdCamera_exptimeCtrl
app::dev config to tell stdCamera to expose exposure time controls
Definition zylaCtrl.hpp:70
static constexpr bool c_stdCamera_emGain
app::dev config to tell stdCamera to expose EM gain controls
Definition zylaCtrl.hpp:68
static constexpr bool c_stdCamera_synchro
app::dev config to tell stdCamera to not expose synchro mode controls
Definition zylaCtrl.hpp:76
virtual int appShutdown()
Do any needed shutdown tasks. Currently nothing in this app.
Definition zylaCtrl.hpp:521
int checkNextROI()
Required by stdCamera, checks the next ROI [stdCamera interface].
Definition zylaCtrl.hpp:838
int recordTelem(const telem_stdcam *)
int cameraSelect()
Select the camera with the desired serial number.
Definition zylaCtrl.hpp:546
int powerOnDefaults()
Set defaults for a power on state.
Definition zylaCtrl.hpp:770
static constexpr bool c_stdCamera_readoutSpeed
app::dev config to tell stdCamera to expose readout speed controls
Definition zylaCtrl.hpp:63
static constexpr bool c_stdCamera_usesStateString
app::dev confg to tell stdCamera to expose the state string property
Definition zylaCtrl.hpp:86
static constexpr bool c_stdCamera_fanSpeed
app::dev config to tell stdCamera not to expose fan-speed control
Definition zylaCtrl.hpp:66
std::string m_serial
The camera serial number. This is a required configuration parameter.
Definition zylaCtrl.hpp:98
static constexpr bool c_stdCamera_cropMode
app:dev config to tell stdCamera to expose Crop Mode controls
Definition zylaCtrl.hpp:82
virtual void loadConfig()
load the configuration system results (called by MagAOXApp::setup())
Definition zylaCtrl.hpp:313
int setShutter(int sh)
Required by stdCamera, but this does not do anything for this camera [stdCamera interface].
Definition zylaCtrl.hpp:862
virtual void setupConfig()
Setup the configuration system (called by MagAOXApp::setup())
Definition zylaCtrl.hpp:299
virtual int appLogic()
Implementation of the FSM for the Siglent SDG.
Definition zylaCtrl.hpp:382
bool m_libInit
Flag indicating whether the AT library is initialized.
Definition zylaCtrl.hpp:104
unsigned int m_imageTimeout
Timeout for waiting on images [msec]. Default is 1000 msec.
Definition zylaCtrl.hpp:100
virtual int appStartup()
Startup functions.
Definition zylaCtrl.hpp:326
static constexpr bool c_stdCamera_fpsCtrl
app::dev config to tell stdCamera to expose FPS controls
Definition zylaCtrl.hpp:72
zylaCtrl()
Default c'tor.
Definition zylaCtrl.hpp:261
static constexpr bool c_stdCamera_temp
app::dev config to tell stdCamera to expose temperature
Definition zylaCtrl.hpp:61
int setExpTime()
Required by stdCamera, but this does not do anything for this camera [stdCamera interface].
Definition zylaCtrl.hpp:822
static constexpr bool c_stdCamera_usesModes
app:dev config to tell stdCamera not to expose mode controls
Definition zylaCtrl.hpp:78
int setTempControl()
Turn temperature control on or off.
Definition zylaCtrl.hpp:789
std::vector< unsigned char * > m_inputBuffers
Definition zylaCtrl.hpp:108
unsigned char * m_outputBuffer
Definition zylaCtrl.hpp:113
virtual int whilePowerOff()
Implementation of the while-powered-off FSM.
Definition zylaCtrl.hpp:511
static constexpr bool c_stdCamera_usesROI
app:dev config to tell stdCamera to expose ROI controls
Definition zylaCtrl.hpp:80
int loadImageIntoStream(void *dest)
int setTempSetPt()
Set the CCD temperature setpoint [stdCamera interface].
Definition zylaCtrl.hpp:815
static constexpr bool c_stdCamera_vShiftSpeed
app:dev config to tell stdCamera to expose vertical shift speed control
Definition zylaCtrl.hpp:65
static constexpr bool c_stdCamera_hasShutter
app:dev config to tell stdCamera to expose shutter controls
Definition zylaCtrl.hpp:84
AT_H m_handle
The Andor API handle to the camera.
Definition zylaCtrl.hpp:106
int setFPS()
Set the frame rate. [stdCamera interface].
Definition zylaCtrl.hpp:830
virtual int onPowerOff()
Implementation of the on-power-off FSM logic.
Definition zylaCtrl.hpp:485
int setNextROI()
Required by stdCamera, but this does not do anything for this camera [stdCamera interface].
Definition zylaCtrl.hpp:844
static constexpr bool c_stdCamera_tempControl
app::dev config to tell stdCamera to expose temperature controls
Definition zylaCtrl.hpp:59
static constexpr bool c_frameGrabber_flippable
app:dev config to tell framegrabber this camera can not be flipped
Definition zylaCtrl.hpp:88
static constexpr bool c_stdCamera_fps
app::dev config to tell stdCamera not to expose FPS status
Definition zylaCtrl.hpp:74
wchar_t m_pixelEncoding[256]
Definition zylaCtrl.hpp:117
~zylaCtrl() noexcept
Destructor.
Definition zylaCtrl.hpp:288
#define INDI_IDLE
Definition indiUtils.hpp:27
#define INDI_OK
Definition indiUtils.hpp:28
std::unique_lock< std::mutex > lock(m_indiMutex)
Definition dm.hpp:19
static constexpr logPrioT LOG_NOTICE
A normal but significant condition.
static constexpr logPrioT LOG_WARNING
A condition has occurred which may become an error, but the process continues.
A device base class which saves telemetry.
Definition telemeter.hpp:75
int loadConfig(appConfigurator &config)
Load the device section from an application configurator.
int setupConfig(appConfigurator &config)
Setup an application configurator for the device section.
@ OPERATING
The device is operating, other than homing.
@ ERROR
The application has encountered an error, from which it is recovering (with or without intervention)
@ READY
The device is ready for operation, but is not operating.
@ CONNECTED
The application has connected to the device or service.
@ NOTCONNECTED
The application is not connected to the device or service.
@ POWERON
The device power is on.
Software CRITICAL log entry.
Software ERR log entry.
Log entry recording stdcam stage specific status.