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
67 static constexpr bool c_stdCamera_emGain = false; ///< app::dev config to tell stdCamera to expose EM gain controls
68
69 static constexpr bool c_stdCamera_exptimeCtrl = true; ///< app::dev config to tell stdCamera to expose exposure time controls
70
71 static constexpr bool c_stdCamera_fpsCtrl = true; ///< app::dev config to tell stdCamera to expose FPS controls
72
73 static constexpr bool c_stdCamera_fps = true; ///< app::dev config to tell stdCamera not to expose FPS status
74
75 static constexpr bool c_stdCamera_synchro = false; ///< app::dev config to tell stdCamera to not expose synchro mode controls
76
77 static constexpr bool c_stdCamera_usesModes = false; ///< app:dev config to tell stdCamera not to expose mode controls
78
79 static constexpr bool c_stdCamera_usesROI = true; ///< app:dev config to tell stdCamera to expose ROI controls
80
81 static constexpr bool c_stdCamera_cropMode = false; ///< app:dev config to tell stdCamera to expose Crop Mode controls
82
83 static constexpr bool c_stdCamera_hasShutter = false; ///< app:dev config to tell stdCamera to expose shutter controls
84
85 static constexpr bool c_stdCamera_usesStateString = false; ///< app::dev confg to tell stdCamera to expose the state string property
86
87 static constexpr bool c_frameGrabber_flippable = false; ///< app:dev config to tell framegrabber this camera can not be flipped
88
89 ///@}
90
91protected:
92
93 /** \name configurable parameters
94 *@{
95 */
96
97 std::string m_serial; ///< The camera serial number. This is a required configuration parameter.
98
99 unsigned int m_imageTimeout {1000}; ///< Timeout for waiting on images [msec]. Default is 1000 msec.
100
101 ///@}
102
103 bool m_libInit {false}; ///< Flag indicating whether the AT library is initialized.
104
105 AT_H m_handle {AT_HANDLE_UNINITIALISED}; ///< The Andor API handle to the camera
106
107 std::vector<unsigned char*> m_inputBuffers;
108 size_t m_nextBuffer {0};
109
111
112 unsigned char* m_outputBuffer {nullptr};
113
115
116 wchar_t m_pixelEncoding[256];
117
119
120public:
121
122 ///Default c'tor
123 zylaCtrl();
124
125 ///Destructor
127
128 /// Setup the configuration system (called by MagAOXApp::setup())
129 virtual void setupConfig();
130
131 /// load the configuration system results (called by MagAOXApp::setup())
132 virtual void loadConfig();
133
134 /// Startup functions
135 /** Sets up the INDI vars.
136 *
137 */
138 virtual int appStartup();
139
140 /// Implementation of the FSM for the Siglent SDG
141 virtual int appLogic();
142
143 /// Implementation of the on-power-off FSM logic
144 virtual int onPowerOff();
145
146 /// Implementation of the while-powered-off FSM
148
149 /// Do any needed shutdown tasks. Currently nothing in this app.
150 virtual int appShutdown();
151
152
153 /// Select the camera with the desired serial number.
154 int cameraSelect();
155
156
157 int getTemp();
158
159 int getExpTime();
160
161 int getFPS();
162
163
164 /** \name stdCamera Interface
165 *
166 * @{
167 */
168
169 /// Set defaults for a power on state.
170 /**
171 * \returns 0 on success
172 * \returns -1 on error
173 */
174 int powerOnDefaults();
175
176 /// Turn temperature control on or off.
177 /** Sets temperature control on or off based on the current value of m_tempControlStatus
178 * \returns 0 on success
179 * \returns -1 on error
180 */
181 int setTempControl();
182
183 /// Set the CCD temperature setpoint [stdCamera interface].
184 /** Sets the temperature to m_ccdTempSetpt.
185 * \returns 0 on success
186 * \returns -1 on error
187 */
188 int setTempSetPt();
189
190 /// Set the frame rate. [stdCamera interface]
191 /** Sets the frame rate to m_fpsSet.
192 *
193 * \returns 0 on success
194 * \returns -1 on error
195 */
196 int setFPS();
197
198 /// Required by stdCamera, but this does not do anything for this camera [stdCamera interface]
199 /**
200 * \returns 0 always
201 */
202 int setExpTime();
203
204 /// Required by stdCamera, checks the next ROI [stdCamera interface]
205 /** Checks if the target values are valid and adjusts them to the closest valid values if needed.
206 *
207 * \returns 0 if successful
208 * \returns -1 on error
209 */
210 int checkNextROI();
211
212 /// Required by stdCamera, but this does not do anything for this camera [stdCamera interface]
213 /**
214 * \returns 0 always
215 */
216 int setNextROI();
217
218 /// Required by stdCamera, but this does not do anything for this camera [stdCamera interface]
219 /**
220 * \returns 0 always
221 */
222 int setShutter(int sh);
223
224 ///@}
225
226
227
228 /** \name framegrabber Interface
229 *
230 * @{
231 */
232
234 float fps()
235 {
236 return m_fps;
237 }
238
239 int startAcquisition();
241 int loadImageIntoStream(void * dest);
242 int reconfig();
243
244 ///@}
245
246 /** \name Telemeter Interface
247 *
248 * @{
249 */
250 int checkRecordTimes();
251
252 int recordTelem( const telem_stdcam * );
253
254
255 ///@}
256
257};
258
259inline
260zylaCtrl::zylaCtrl() : MagAOXApp(MAGAOX_CURRENT_SHA1, MAGAOX_REPO_MODIFIED)
261{
262 m_powerMgtEnabled = true;
263 m_powerOnWait = 10;
264
265
266 m_startupTemp = 20;
267
268 m_expTimeSet = 0.05; //Set default for startup
269 m_fpsSet = 20; //Set default for startup
270
271 m_startup_x = 1075;
272 m_startup_y = 975;
273 m_startup_w = 128;
274 m_startup_h = 128;
275 m_startup_bin_x = 1;
276 m_startup_bin_y = 1;
277
278 m_full_x = 1023.5;
279 m_full_y = 1023.5;
280 m_full_w = 2048;
281 m_full_h = 2048;
282
283 return;
284}
285
286inline
288{
289 for(size_t n=0; n < m_inputBuffers.size(); ++n)
290 {
292 }
293
294 return;
295}
296
297inline
299{
301
302 config.add("camera.serial", "", "camera.serial", argType::Required, "camera", "serial", false, "string", "The camera serial number.");
303
306
307}
308
309
310
311inline
313{
315
316 config(m_serial, "camera.serial");
317
320}
321
322
323
324inline
326{
327 m_minROIx = 0;
328 m_maxROIx = 2047;
329 m_stepROIx = 0;
330
331 m_minROIy = 0;
332 m_maxROIy = 2047;
333 m_stepROIy = 0;
334
335 m_minROIWidth = 1;
336 m_maxROIWidth = 2048;
337 m_stepROIWidth = 4;
338
339 m_minROIHeight = 1;
340 m_maxROIHeight = 2048;
341 m_stepROIHeight = 1;
342
346
348 m_maxROIBinning_y = 1024;
350
352 {
354 }
355
357 {
359 }
360
362 {
363 return log<software_error,-1>({__FILE__,__LINE__});
364 }
365
366 m_inputBuffers.resize(3);
367 for(size_t n =0; n < m_inputBuffers.size(); ++n)
368 {
369 m_inputBuffers[n] = nullptr;
370 }
371 m_nextBuffer = 0;
372
374
375 return 0;
376
377}
378
379
380inline
382{
383 //and run stdCamera's appLogic
385 {
386 return log<software_error, -1>({__FILE__, __LINE__});
387 }
388
389 //first run frameGrabber's appLogic to see if the f.g. thread has exited.
391 {
392 return log<software_error, -1>({__FILE__, __LINE__});
393 }
394
395 if( state() == stateCodes::POWERON) return 0;
396
398 {
399 //Might have gotten here because of a power off.
400 if(m_powerState == 0) return 0;
401
402 int ret = cameraSelect();
403
404 if( ret != 0) //Probably not powered on yet.
405 {
406 sleep(1);
407 return 0;
408 }
409
411
412
413 }
414
416 {
417 //Get a lock
418 std::unique_lock<std::mutex> lock(m_indiMutex);
419
421
424
425 }
426
428 {
429 //Get a lock if we can
430 std::unique_lock<std::mutex> lock(m_indiMutex, std::try_to_lock);
431
432 //but don't wait for it, just go back around.
433 if(!lock.owns_lock()) return 0;
434
435 if(getTemp() < 0)
436 {
437 if(m_powerState == 0) return 0;
438
440 return 0;
441 }
442
443 if(getExpTime() < 0)
444 {
445 if(m_powerState == 0) return 0;
446
448 return 0;
449 }
450
451 if(getFPS() < 0)
452 {
453 if(m_powerState == 0) return 0;
454
456 return 0;
457 }
458
460 {
462 }
463
465 {
467 }
468
470 {
472 return 0;
473 }
474
475 }
476
477 //Fall through check?
478
479 return 0;
480
481}
482
483inline
485{
487
489 {
492 }
493
494 if(m_libInit)
495 {
498
499 m_libInit = false;
500 }
501
502 std::lock_guard<std::mutex> lock(m_indiMutex);
503
505
506 return 0;
507}
508
509inline
511{
512 std::lock_guard<std::mutex> lock(m_indiMutex);
513
515
516 return 0;
517}
518
519inline
521{
524
526 {
529 }
530
531 if(m_libInit)
532 {
535
536 m_libInit = false;
537 }
538
539
540
541 return 0;
542}
543
544inline
546{
547 int iErr;
548
550 {
551 log<software_warning>({__FILE__, __LINE__, "handle initialized on call to cameraSelect. Attempting to close and go on."});
552
554 if(iErr != AT_SUCCESS)
555 {
556 log<software_error>({__FILE__, __LINE__, "Error from AT_Close: " + std::to_string(iErr) + ". Attempting to go on." });
558 }
559 }
560
561 if(m_libInit)
562 {
564 if(iErr != AT_SUCCESS )
565 {
566 return log<software_critical,-1>({__FILE__, __LINE__, "Error from AT_FinaliseLibrary: " + std::to_string(iErr)});
567 }
569 if(iErr != AT_SUCCESS )
570 {
571 return log<software_critical,-1>({__FILE__, __LINE__, "Error from AT_FinaliseUtilityLibrary: " + std::to_string(iErr)});
572 }
573
574 m_libInit = false;
575 }
576
578 if( iErr != AT_SUCCESS )
579 {
580 return log<software_critical,-1>({__FILE__, __LINE__, "Error from AT_InitialiseLibrary: " + std::to_string(iErr)});
581 }
582
584 if( iErr != AT_SUCCESS )
585 {
586 return log<software_critical,-1>({__FILE__, __LINE__, "Error from AT_InitialiseUtilityLibrary: " + std::to_string(iErr)});
587 }
588
589 m_libInit = true;
590
591 long long DeviceCount = 0;
592
593 iErr = AT_GetInt(AT_HANDLE_SYSTEM, L"Device Count", &DeviceCount);
594
595 if (iErr != AT_SUCCESS)
596 {
597 return log<software_critical,-1>({__FILE__,__LINE__, "Error from AT_GetInt('Device Count'): " + std::to_string(iErr)});
598 }
599
600 std::cout << "Found " << DeviceCount << " Devices." << std::endl;
601
602 for (long long i=0; i<DeviceCount; i++)
603 {
605
606 iErr = AT_Open(static_cast<int>(i), &Hndl);
607
608 if (iErr != AT_SUCCESS)
609 {
610 return log<software_critical,-1>({__FILE__,__LINE__, "Error from AT_Open(): " + std::to_string(iErr)});
611 }
612
613 AT_WC CameraSerial[128];
614
615 iErr = AT_GetString(Hndl, L"SerialNumber", CameraSerial, 128);
616
617 if (iErr != AT_SUCCESS)
618 {
619 return log<software_critical,-1>({__FILE__,__LINE__, "Error from AT_GetString('SerialNumber'): " + std::to_string(iErr)});
620 }
621
622 char camSerial[128];
624
625 if(m_serial != camSerial)
626 {
627 iErr = AT_Close(Hndl);
628 if (iErr != AT_SUCCESS)
629 {
630 log<software_error>({__FILE__,__LINE__, "Error from AT_Close(): " + std::to_string(iErr)});
631 }
632
633 continue;
634 }
635
636 AT_WC CameraModel[128];
637
638 iErr = AT_GetString(Hndl, L"Camera Model", CameraModel, 128);
639
640 if (iErr != AT_SUCCESS)
641 {
642 return log<software_critical,-1>({__FILE__,__LINE__, "Error from AT_GetString('Camera Model'): " + std::to_string(iErr)});
643 }
644
645 char camModel[128];
647
648 log<text_log>({std::string("Found ") + camModel + " serial number " + m_serial}, logPrio::LOG_NOTICE);
649
650 m_handle = Hndl;
651 return 0;
652 }
653
654 log<text_log>({"Camera with serial number " + m_serial + " not found in " + std::to_string(DeviceCount) + "devices."}, logPrio::LOG_WARNING);
655
659
660 m_libInit = false;
661
662 return -1;
663
664}
665
666inline
668{
670 wchar_t temperatureStatus[256];
671 int rv = AT_GetEnumIndex(m_handle, L"TemperatureStatus", &temperatureStatusIndex);
672 if (rv != AT_SUCCESS)
673 {
674 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_EnumIndex('TemperatureStatus'): " + std::to_string(rv)});
675 }
676
678 if (rv != AT_SUCCESS)
679 {
680 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_EnumStringByIndex('TemperatureStatus'): " + std::to_string(rv)});
681 }
682
683 if(wcscmp(L"Stabilised",temperatureStatus) == 0)
684 {
685 m_tempControlStatusStr="Stabilised";
686 m_tempControlStatus = true;
688 }
689 else if(wcscmp(L"Cooler Off",temperatureStatus) == 0)
690 {
691 m_tempControlStatusStr="Cooler Off";
692 m_tempControlStatus = false;
693 m_tempControlOnTarget = false;
694 }
695 else if(wcscmp(L"Cooling",temperatureStatus) == 0)
696 {
697 m_tempControlStatusStr="Cooling";
698 m_tempControlStatus = true;
699 m_tempControlOnTarget = false;
700 }
701 else if(wcscmp(L"Drift",temperatureStatus) == 0)
702 {
704 m_tempControlStatus = true;
705 m_tempControlOnTarget = false;
706 }
707 else if(wcscmp(L"Not Stabilised",temperatureStatus) == 0)
708 {
709 m_tempControlStatusStr="Not Stabilised";
710 m_tempControlStatus = true;
711 m_tempControlOnTarget = false;
712 }
713 else if(wcscmp(L"Fault",temperatureStatus) == 0)
714 {
716 m_tempControlStatus = false;
717 m_tempControlOnTarget = false;
718 }
719 else
720 {
721 m_tempControlStatusStr="Unknown";
722 m_tempControlStatus = false;
723 m_tempControlOnTarget = false;
724 }
725
726 double val;
727 rv = AT_GetFloat(m_handle, L"SensorTemperature", &val);
728 if (rv != AT_SUCCESS)
729 {
730 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetFloat('SensorTemperature'): " + std::to_string(rv)});
731 }
732
733 m_ccdTemp = val;
734
735 //Check if we have the right target, and set it if not.
736 rv = AT_GetFloat(m_handle, L"TargetSensorTemperature", &val);
737 if (rv != AT_SUCCESS)
738 {
739 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetFloat('TargetSensorTemperature'): " + std::to_string(rv)});
740 }
741
743
744 recordCamera();
745
746 return 0;
747}
748
749inline
751{
752 return 0;
753
754}
755
756inline
758{
759 return 0;
760
761}
762
763
764//------------------------------------------------------------------------
765//----------------------- stdCamera interface ---------------------------
766//------------------------------------------------------------------------
767
768inline
770{
771 //Camera boots up with this true in most cases.
773 m_tempControlStatus =false;
774
775 m_ccdTempSetpt = 0; //This is the power on setpoint
776
783
784 return 0;
785}
786
787inline
789{
790 if(m_tempControlStatusSet == true)
791 {
792 int rv = AT_SetBool(m_handle, L"SensorCooling", AT_TRUE);
793 if(rv != AT_SUCCESS)
794 {
795 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetBool(<SensorCooling>): " + std::to_string(rv)});
796 }
797 log<text_log>({"cooling on"}, logPrio::LOG_NOTICE);
798 }
799 else
800 {
801 int rv = AT_SetBool(m_handle, L"SensorCooling", AT_FALSE);
802 if(rv != AT_SUCCESS)
803 {
804 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetBool(<SensorCooling>): " + std::to_string(rv)});
805 log<text_log>({"cooling off"}, logPrio::LOG_NOTICE);
806 }
807 }
808
809 recordCamera();
810 return 0;
811}
812
813inline
815{
816 std::cerr << "setTempSetPt is not implemented\n";
817 return 0;
818}
819
820inline
822{
823 std::cerr << "Set exposure time\n";
824 m_reconfig = true;
825 return 0;
826}
827
828inline
830{
831 std::cerr << "setFPS\n";
832 m_reconfig = true;
833 return 0;
834}
835
836inline
838{
839 return 0;
840}
841
842inline
844{
845 std::cerr << "setNextROI:\n";
846 std::cerr << " m_nextROI.x = " << m_nextROI.x << "\n";
847 std::cerr << " m_nextROI.y = " << m_nextROI.y << "\n";
848 std::cerr << " m_nextROI.w = " << m_nextROI.w << "\n";
849 std::cerr << " m_nextROI.h = " << m_nextROI.h << "\n";
850 std::cerr << " m_nextROI.bin_x = " << m_nextROI.bin_x << "\n";
851 std::cerr << " m_nextROI.bin_y = " << m_nextROI.bin_y << "\n";
852
853 m_reconfig = true;
854
855 updateSwitchIfChanged(m_indiP_roi_set, "request", pcf::IndiElement::Off, INDI_IDLE);
856
857 return 0;
858}
859
860inline
862{
863 static_cast<void>(sh);
864
865 return 0;
866}
867
868//------------------------------------------------------------------------
869//------------------- framegrabber interface ---------------------------
870//------------------------------------------------------------------------
871
872inline
874{
875 int rv;
876
878 {
879 log<software_error>({__FILE__, __LINE__, "camer or AT not initialized on configureAcquisition()."});
880 return -1;
881 }
882
883 //lock mutex
884 std::unique_lock<std::mutex> lock(m_indiMutex);
885
886
888 AT_GetBool(m_handle, L"FullAOIControl", &faoi);
889 std::cerr << "FullAOIControl: " << std::boolalpha << faoi << "\n";
890
891 //Configure ROI:
892 AT_64 xbin = m_nextROI.bin_x;
893 AT_64 ybin = m_nextROI.bin_y;
894 AT_64 left= (m_nextROI.x - 0.5*( (float) m_nextROI.w - 1.0)) + 1;
895 AT_64 top = (m_nextROI.y - 0.5*( (float) m_nextROI.h - 1.0)) + 1;
896 AT_64 width = m_nextROI.w;
897 AT_64 height = m_nextROI.h;
898
899 std::cerr << xbin << " " << ybin << " " << left << " " << top << " " << width << " " << height << " " << "\n";
900
901 rv = AT_SetInt(m_handle, L"AOIHBin", xbin);
902 if(rv != AT_SUCCESS)
903 {
904 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOIHBin>): [" + std::to_string(xbin) + "] err: " + std::to_string(rv)});
905 }
906
907 rv = AT_SetInt(m_handle, L"AOIVBin", ybin);
908 if(rv != AT_SUCCESS)
909 {
910 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOIVBin>): [" + std::to_string(ybin) + "] err: " + std::to_string(rv)});
911 }
912
913 rv = AT_SetInt(m_handle, L"AOIWidth", width);
914 if(rv != AT_SUCCESS)
915 {
916 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOIWidth>): [" + std::to_string(width) + "] err: " + std::to_string(rv)});
917 }
918
919 rv = AT_SetInt(m_handle, L"AOILeft", left);
920 if(rv != AT_SUCCESS)
921 {
922 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOILeft>): [" + std::to_string(left) + "] err: " + std::to_string(rv)});
923 }
924
925 rv = AT_SetInt(m_handle, L"AOIHeight", height);
926 if(rv != AT_SUCCESS)
927 {
928 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOIHeight>): [" + std::to_string(height) + "] err: " + std::to_string(rv)});
929 }
930
931 rv = AT_SetInt(m_handle, L"AOITop", top);
932 if(rv != AT_SUCCESS)
933 {
934 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetInt(<AOITop>): [" + std::to_string(top) + "] err: " + std::to_string(rv)});
935 }
936
937 //Get Detector dimensions
939
940 rv = AT_GetInt(m_handle, L"AOI Left", &left);
941 if(rv != AT_SUCCESS)
942 {
943 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Left>): " + std::to_string(rv)});
944 }
945
946 rv = AT_GetInt(m_handle, L"AOI Top", &top);
947 if(rv != AT_SUCCESS)
948 {
949 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Top>): " + std::to_string(rv)});
950 }
951
952 rv = AT_GetInt(m_handle, L"AOI Width", &width);
953 if(rv != AT_SUCCESS)
954 {
955 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Width>): " + std::to_string(rv)});
956 }
957
958 rv = AT_GetInt(m_handle, L"AOI Height", &height);
959 if(rv != AT_SUCCESS)
960 {
961 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Height>): " + std::to_string(rv)});
962 }
963
964 m_currentROI.x = left + 0.5*( (float) (width - 1.0)) ;
965 m_currentROI.y = top + 0.5*( (float) (height - 1.0)) ;
966
967 m_currentROI.w = width;
968 m_currentROI.h = height;
969
976
977 rv = AT_GetInt(m_handle, L"AOI Stride", &stride);
978 if(rv != AT_SUCCESS)
979 {
980 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<AOI Stride>): " + std::to_string(rv)});
981 }
982
983 m_width = static_cast<int>(width);
984 m_height = static_cast<int>(height);
985 m_stride = static_cast<int>(stride);
987
988 //Free the API buffer
989 for(size_t n =0; n < m_inputBuffers.size(); ++n)
990 {
991 if(m_inputBuffers[n])
992 {
994 m_inputBuffers[n] = nullptr;
995 }
997 }
998
999 //Get the number of bytes required to store one frame
1001 rv = AT_GetInt(m_handle, L"ImageSizeBytes", &ImageSizeBytes);
1002 if(rv != AT_SUCCESS)
1003 {
1004 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_GetInt(<ImageSizeBytes>): " + std::to_string(rv)});
1005 }
1006
1007 m_inputBufferSize = static_cast<int>(ImageSizeBytes);
1008
1009 //Allocate a memory buffer to store one frame
1010 for(size_t n =0; n < m_inputBuffers.size(); ++n)
1011 {
1012 m_inputBuffers[n] = (unsigned char *) malloc(m_inputBufferSize * sizeof(unsigned char));
1013 }
1014
1015 rv = AT_Flush(m_handle);
1016 if(rv != AT_SUCCESS)
1017 {
1018 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_Flush " + std::to_string(rv)});
1019 }
1020
1021 //Pass this buffer to the SDK
1022 for(size_t n =0; n < m_inputBuffers.size(); ++n)
1023 {
1025 if(rv != AT_SUCCESS)
1026 {
1027 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_QueueBuffer: " + std::to_string(rv)});
1028 }
1029 }
1030 m_nextBuffer = 0;
1031
1032 AT_SetFloat(m_handle, L"ExposureTime", m_expTimeSet);
1033 if(rv != AT_SUCCESS)
1034 {
1035 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetFloat(<ExposureTime>): " + std::to_string(rv)});
1036 }
1038
1039 AT_SetFloat(m_handle, L"FrameRate", m_fpsSet);
1040 if(rv != AT_SUCCESS)
1041 {
1042 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetFloat(<FrameRate>): " + std::to_string(rv)});
1043 }
1044 m_fps = m_fpsSet;
1045
1046 int pixelEncodingIndex = 0;
1047
1048 AT_GetEnumIndex(m_handle, L"PixelEncoding", &pixelEncodingIndex);
1050
1051 std::wcout << m_pixelEncoding << "\n";
1052
1053 //Set the camera to continuously acquire frames
1054 rv = AT_SetEnumString(m_handle, L"CycleMode", L"Continuous");
1055 if(rv != AT_SUCCESS)
1056 {
1057 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_SetEnumString(<CycleMode-Continuous>): " + std::to_string(rv)});
1058 }
1059
1060 log<text_log>({"Camera configured for continous acquistion with " + std::to_string(m_width) + "x" + std::to_string(m_height)});
1061
1062 recordCamera(true); //Force so it is logged before starting acq.
1063
1064 return 0;
1065}
1066
1067inline
1069{
1070 //Start the Acquisition running
1071 int rv = AT_Command(m_handle, L"AcquisitionStart");
1072
1073 if(rv != AT_SUCCESS)
1074 {
1075 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_Command(<AcquisitionStart>): " + std::to_string(rv)});
1076 }
1077
1078 log<text_log>("Acqusition started");
1079
1080 return 0;
1081}
1082
1083inline
1085{
1087
1088 if(rv == AT_ERR_TIMEDOUT)
1089 {
1090 return 1;
1091 }
1092
1094
1095
1096 if(rv != AT_SUCCESS )
1097 {
1098 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_WaitBuffer: " + std::to_string(rv)});
1099 }
1100
1102 {
1103 return log<software_error,-1>({__FILE__,__LINE__, "Wrong buffer size returned"});
1104 }
1105
1106 return 0;
1107}
1108
1109inline
1111{
1112 if(m_outputBuffer == nullptr) return -1;
1113
1115
1117 {
1118 std::cerr << "buffer skip!\n";
1120 {
1121 ++m_nextBuffer;
1122 if(m_nextBuffer >= m_inputBuffers.size()) m_nextBuffer = 0;
1123 }
1124 }
1125
1127 if(rv != AT_SUCCESS)
1128 {
1129 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_QueueBuffer: " + std::to_string(rv)});
1130 }
1131
1132 //Pass the buffer to the SDK
1133 ++m_nextBuffer;
1134 if(m_nextBuffer >= m_inputBuffers.size()) m_nextBuffer = 0;
1135
1136
1137 return 0;
1138}
1139
1140inline
1142{
1143 //lock mutex
1144 std::unique_lock<std::mutex> lock(m_indiMutex);
1145
1146 recordCamera(true); //force so it is logged before stopping acq.
1147
1148 //Start the Acquisition running
1149 int rv = AT_Command(m_handle, L"AcquisitionStop");
1150 if(rv != AT_SUCCESS)
1151 {
1152 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_Command(<AcquisitionStop>): " + std::to_string(rv)});
1153 }
1154 log<text_log>("Acqusition stopped");
1155
1156 rv = AT_Flush(m_handle);
1157 if(rv != AT_SUCCESS)
1158 {
1159 return log<software_error,-1>({__FILE__,__LINE__, "Error from AT_Fluxh : " + std::to_string(rv)});
1160 }
1161
1162 return 0;//edtCamera<zylaCtrl>::pdvReconfig();
1163}
1164
1169
1171{
1172 return recordCamera(true);
1173}
1174
1175}//namespace app
1176} //namespace MagAOX
1177#endif
The base-class for MagAO-X applications.
Definition MagAOXApp.hpp:73
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
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.
void setupConfig(mx::app::appConfigurator &config)
Setup the configuration system.
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.
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].
float m_ccdTemp
The current temperature, in C.
bool m_tempControlOnTarget
Whether or not the temperature control system is on its target temperature.
void loadConfig(mx::app::appConfigurator &config)
load the configuration system results
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:69
static constexpr bool c_stdCamera_emGain
app::dev config to tell stdCamera to expose EM gain controls
Definition zylaCtrl.hpp:67
static constexpr bool c_stdCamera_synchro
app::dev config to tell stdCamera to not expose synchro mode controls
Definition zylaCtrl.hpp:75
virtual int appShutdown()
Do any needed shutdown tasks. Currently nothing in this app.
Definition zylaCtrl.hpp:520
int checkNextROI()
Required by stdCamera, checks the next ROI [stdCamera interface].
Definition zylaCtrl.hpp:837
int recordTelem(const telem_stdcam *)
int cameraSelect()
Select the camera with the desired serial number.
Definition zylaCtrl.hpp:545
int powerOnDefaults()
Set defaults for a power on state.
Definition zylaCtrl.hpp:769
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:85
std::string m_serial
The camera serial number. This is a required configuration parameter.
Definition zylaCtrl.hpp:97
static constexpr bool c_stdCamera_cropMode
app:dev config to tell stdCamera to expose Crop Mode controls
Definition zylaCtrl.hpp:81
virtual void loadConfig()
load the configuration system results (called by MagAOXApp::setup())
Definition zylaCtrl.hpp:312
int setShutter(int sh)
Required by stdCamera, but this does not do anything for this camera [stdCamera interface].
Definition zylaCtrl.hpp:861
virtual void setupConfig()
Setup the configuration system (called by MagAOXApp::setup())
Definition zylaCtrl.hpp:298
virtual int appLogic()
Implementation of the FSM for the Siglent SDG.
Definition zylaCtrl.hpp:381
bool m_libInit
Flag indicating whether the AT library is initialized.
Definition zylaCtrl.hpp:103
unsigned int m_imageTimeout
Timeout for waiting on images [msec]. Default is 1000 msec.
Definition zylaCtrl.hpp:99
virtual int appStartup()
Startup functions.
Definition zylaCtrl.hpp:325
static constexpr bool c_stdCamera_fpsCtrl
app::dev config to tell stdCamera to expose FPS controls
Definition zylaCtrl.hpp:71
zylaCtrl()
Default c'tor.
Definition zylaCtrl.hpp:260
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:821
static constexpr bool c_stdCamera_usesModes
app:dev config to tell stdCamera not to expose mode controls
Definition zylaCtrl.hpp:77
int setTempControl()
Turn temperature control on or off.
Definition zylaCtrl.hpp:788
std::vector< unsigned char * > m_inputBuffers
Definition zylaCtrl.hpp:107
unsigned char * m_outputBuffer
Definition zylaCtrl.hpp:112
virtual int whilePowerOff()
Implementation of the while-powered-off FSM.
Definition zylaCtrl.hpp:510
static constexpr bool c_stdCamera_usesROI
app:dev config to tell stdCamera to expose ROI controls
Definition zylaCtrl.hpp:79
int loadImageIntoStream(void *dest)
int setTempSetPt()
Set the CCD temperature setpoint [stdCamera interface].
Definition zylaCtrl.hpp:814
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:83
AT_H m_handle
The Andor API handle to the camera.
Definition zylaCtrl.hpp:105
int setFPS()
Set the frame rate. [stdCamera interface].
Definition zylaCtrl.hpp:829
virtual int onPowerOff()
Implementation of the on-power-off FSM logic.
Definition zylaCtrl.hpp:484
int setNextROI()
Required by stdCamera, but this does not do anything for this camera [stdCamera interface].
Definition zylaCtrl.hpp:843
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:87
static constexpr bool c_stdCamera_fps
app::dev config to tell stdCamera not to expose FPS status
Definition zylaCtrl.hpp:73
wchar_t m_pixelEncoding[256]
Definition zylaCtrl.hpp:116
~zylaCtrl() noexcept
Destructor.
Definition zylaCtrl.hpp:287
@ 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.
#define INDI_IDLE
Definition indiUtils.hpp:28
#define INDI_OK
Definition indiUtils.hpp:29
std::unique_lock< std::mutex > lock(m_indiMutex)
Definition dm.hpp:24
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:69
int loadConfig(appConfigurator &config)
Load the device section from an application configurator.
int setupConfig(appConfigurator &config)
Setup an application configurator for the device section.
Software CRITICAL log entry.
Software ERR log entry.
Log entry recording stdcam stage specific status.