API
cameraSim.hpp
Go to the documentation of this file.
1 /** \file cameraSim.hpp
2  * \brief The MagAO-X camera simulator.
3  *
4  * \author Jared R. Males (jaredmales@gmail.com)
5  *
6  * \ingroup cameraSim_files
7  */
8 
9 #ifndef cameraSim_hpp
10 #define cameraSim_hpp
11 
12 // #include <ImageStruct.h>
13 #include <ImageStreamIO/ImageStreamIO.h>
14 
15 #include <mx/math/func/gaussian.hpp>
16 #include <mx/math/randomT.hpp>
17 
18 #include "../../libMagAOX/libMagAOX.hpp" //Note this is included on command line to trigger pch
19 #include "../../magaox_git_version.h"
20 
21 namespace MagAOX
22 {
23 namespace app
24 {
25 
26 /** \defgroup cameraSim Camera Simulator
27  * \brief A camera simulator
28  *
29  * <a href="../handbook/operating/software/apps/cameraSim.html">Application Documentation</a>
30  *
31  * \ingroup apps
32  *
33  */
34 
35 /** \defgroup cameraSim_files Camera Simulator Files
36  * \ingroup cameraSim
37  */
38 
39 /** MagAO-X application to simulate a camera
40  *
41  * \ingroup cameraSim
42  *
43  */
44 class cameraSim : public MagAOXApp<>,
45  public dev::stdCamera<cameraSim>,
46  public dev::frameGrabber<cameraSim>,
47  public dev::telemeter<cameraSim>
48 {
49 
50  friend class dev::stdCamera<cameraSim>;
51  friend class dev::frameGrabber<cameraSim>;
52  friend class dev::telemeter<cameraSim>;
53 
54  public:
58 
59  /** \name app::dev Configurations
60  *@{
61  */
62  static constexpr bool c_stdCamera_tempControl =
63  true; ///< app::dev config to tell stdCamera to not expose temperature controls
64 
65  static constexpr bool c_stdCamera_temp = true; ///< app::dev config to tell stdCamera to expose temperature
66 
67  static constexpr bool c_stdCamera_readoutSpeed =
68  true; ///< app::dev config to tell stdCamera not to expose readout speed controls
69 
70  static constexpr bool c_stdCamera_vShiftSpeed =
71  true; ///< app:dev config to tell stdCamera not to expose vertical shift speed control
72 
73  static constexpr bool c_stdCamera_emGain =
74  true; ///< app::dev config to tell stdCamera to not expose EM gain controls
75 
76  static constexpr bool c_stdCamera_exptimeCtrl =
77  true; ///< app::dev config to tell stdCamera to expose exposure time controls
78 
79  static constexpr bool c_stdCamera_fpsCtrl = true; ///< app::dev config to tell stdCamera to expose FPS controls
80 
81  static constexpr bool c_stdCamera_fps =
82  true; ///< app::dev config to tell stdCamera not to expose FPS status (ignored since fpsCtrl=true)
83 
84  static constexpr bool c_stdCamera_synchro =
85  true; ///< app::dev config to tell stdCamera to not expose synchro mode controls
86 
87  static constexpr bool c_stdCamera_usesModes =
88  false; ///< app:dev config to tell stdCamera not to expose mode controls
89 
90  static constexpr bool c_stdCamera_usesROI = true; ///< app:dev config to tell stdCamera to expose ROI controls
91 
92  static constexpr bool c_stdCamera_cropMode =
93  true; ///< app:dev config to tell stdCamera not to expose Crop Mode controls
94 
95  static constexpr bool c_stdCamera_hasShutter =
96  true; ///< app:dev config to tell stdCamera to expose shutter controls
97 
98  static constexpr bool c_stdCamera_usesStateString =
99  true; ///< app::dev confg to tell stdCamera to expose the state string property
100 
101  static constexpr bool c_frameGrabber_flippable =
102  true; ///< app:dev config to tell framegrabber that this camera can be flipped
103 
104  ///@}
105 
106  protected:
107  mx::improc::eigenImage<int16_t> m_fgimage;
108 
109  double m_lastTime{ 0 };
110  double m_offset = { 0 };
111 
112  float m_bias{ 500 }; ///< the simulated bias level. default 500.
113  float m_ron{ 5 }; ///< the simulated readout noise, in counts/read. default 5.
114 
115  std::vector<float> m_xcen{ 0 }; /**< the simulated star x center coordinate, relative to image center.
116  one per star. default 0*/
117  std::vector<float> m_ycen{ 0 }; /**< the simulated star y center coordinate, relative to image center.
118  one per star. default 0.*/
119  std::vector<float> m_peak{ 2000 }; ///< the simulated star peak, in counts/second. one per star. default 2000.
120  float m_fwhm{ 2 }; ///< the simulated star FWHM in pixels. the same for all stars. default 2.
121 
122  float m_jitter{ 0.1 }; ///< the simulated jitter, in pixels/read. the same for all stars. default 0.1.
123 
124  mx::math::normDistT<float> m_norm;
125 
126  public:
127  /// Default c'tor
128  cameraSim();
129 
130  /// Destructor
131  ~cameraSim() noexcept;
132 
133  /// Setup the configuration system (called by MagAOXApp::setup())
134  virtual void setupConfig();
135 
136  /// load the configuration system results (called by MagAOXApp::setup())
137  virtual int loadConfigImpl( mx::app::appConfigurator &cfg );
138 
139  /// load the configuration system results (called by MagAOXApp::setup())
140  virtual void loadConfig();
141 
142  /// Startup functions
143  /** Sets up the INDI vars.
144  *
145  */
146  virtual int appStartup();
147 
148  /// Implementation of the FSM for the Siglent SDG
149  virtual int appLogic();
150 
151  /// Do any needed shutdown tasks. Currently nothing in this app.
152  virtual int appShutdown();
153 
154  int configureAcquisition();
155  int startAcquisition();
156  int acquireAndCheckValid();
157  int loadImageIntoStream( void *dest );
158  int reconfig();
159 
160  protected:
161  float fps();
162 
163  /** \name stdCamera Interface
164  *
165  * @{
166  */
167 
168  /// Set defaults for a power on state.
169  /**
170  * \returns 0 on success
171  * \returns -1 on error
172  */
173  int powerOnDefaults();
174 
175  int setTempControl();
176 
177  int setTempSetPt();
178 
179  int setReadoutSpeed();
180 
181  int setVShiftSpeed();
182 
183  /// Set the Exposure Time. [stdCamera interface]
184  /** Sets the frame rate to m_expTimeSet.
185  *
186  * \returns 0 on success
187  * \returns -1 on error
188  */
189  int setExpTime();
190 
191  /// Set the framerate.
192  /**
193  * \returns 0 always
194  */
195  int setFPS();
196 
197  int setSynchro();
198 
199  int setEMGain();
200 
201  /// Check the next ROI
202  /** Checks if the target values are valid and adjusts them to the closest valid values if needed.
203  *
204  * \returns 0 always
205  */
206  int checkNextROI();
207 
208  int setCropMode();
209 
210  /// Set the next ROI
211  /**
212  * \returns 0 always
213  */
214  int setNextROI();
215 
216  int setShutter( int ss );
217 
218  std::string stateString();
219 
220  bool stateStringValid();
221 
222  ///@}
223 
224  /** \name Telemeter Interface
225  *
226  * @{
227  */
228 
229  int checkRecordTimes();
230 
231  int recordTelem( const telem_stdcam * );
232 
233  ///@}
234 };
235 
236 inline cameraSim::cameraSim() : MagAOXApp( MAGAOX_CURRENT_SHA1, MAGAOX_REPO_MODIFIED )
237 {
238  m_powerMgtEnabled = true;
239 
240  m_defaultReadoutSpeed = "1";
241  m_defaultVShiftSpeed = "1";
242 
243  m_default_x = 511.5;
244  m_default_y = 511.5;
245  m_default_w = 1024;
246  m_default_h = 1024;
247 
252  m_nextROI.bin_x = 1;
253  m_nextROI.bin_y = 1;
254 
255  m_full_x = 511.5;
256  m_full_y = 511.5;
257  m_full_w = 1024;
258  m_full_h = 1024;
259 
260  return;
261 }
262 
263 inline cameraSim::~cameraSim() noexcept
264 {
265  return;
266 }
267 
269 {
271 
272  FRAMEGRABBER_SETUP_CONFIG( config );
273 
274  TELEMETER_SETUP_CONFIG( config );
275 
276  config.add( "camsim.fullW",
277  "",
278  "camsim.fullW",
279  argType::Required,
280  "camsim",
281  "fullW",
282  false,
283  "int",
284  "Full (maximum) width of the simulated detector" );
285 
286  config.add( "camsim.fullH",
287  "",
288  "camsim.fullH",
289  argType::Required,
290  "camsim",
291  "fullH",
292  false,
293  "int",
294  "Full (maximum) height of the simulated detector" );
295 
296  config.add( "camsim.defaultFPS",
297  "",
298  "camsim.defaultFPS",
299  argType::Required,
300  "camsim",
301  "defaultFPS",
302  false,
303  "float",
304  "the camera default FPS, set at startup. Default is 10" );
305 
306  config.add( "camsim.bias",
307  "",
308  "camsim.bias",
309  argType::Required,
310  "camsim",
311  "bias",
312  false,
313  "float",
314  "the simulated bias level. default 500." );
315 
316  config.add( "camsim.ron",
317  "",
318  "camsim.ron",
319  argType::Required,
320  "camsim",
321  "ron",
322  false,
323  "float",
324  "the simulated readout noise, in counts/read. default 5." );
325 
326  config.add( "camsim.xcen",
327  "",
328  "camsim.xcen",
329  argType::Required,
330  "camsim",
331  "xcen",
332  false,
333  "vector<float>",
334  "the simulated star x center coordinate, relative to image center. one per star. default 0." );
335 
336  config.add( "camsim.ycen",
337  "",
338  "camsim.ycen",
339  argType::Required,
340  "camsim",
341  "ycen",
342  false,
343  "vector<float>",
344  "the simulated star y center coordinate, relative to image center. one per star. default 0." );
345 
346  config.add( "camsim.peak",
347  "",
348  "camsim.peak",
349  argType::Required,
350  "camsim",
351  "peak",
352  false,
353  "vector<float>",
354  "the simulated star peak, in counts/second. one per star. default 2000." );
355 
356  config.add( "camsim.fwhm",
357  "",
358  "camsim.fwhm",
359  argType::Required,
360  "camsim",
361  "fwhm",
362  false,
363  "float",
364  "the simulated star FWHM in pixels. the same for all stars. default 2." );
365 
366  config.add( "camsim.jitter",
367  "",
368  "camsim.jitter",
369  argType::Required,
370  "camsim",
371  "jitter",
372  false,
373  "float",
374  "the simulated jitter, in pixels/read. the same for all stars. default 0.1." );
375 }
376 
377 inline int cameraSim::loadConfigImpl( mx::app::appConfigurator &cfg )
378 {
380 
382 
383  TELEMETER_LOAD_CONFIG( cfg );
384 
385  cfg( m_full_w, "camsim.fullW" );
386  cfg( m_full_h, "camsim.fullH" );
387 
388  m_full_x = 0.5 * ( m_full_w - 1.0 );
389  m_full_y = 0.5 * ( m_full_h - 1.0 );
390 
392  {
395  }
396 
398  {
401  }
402 
403  m_fps = 10;
404  cfg( m_fps, "camsim.defaultFPS" );
405  m_fpsSet = m_fps;
406 
407  config( m_bias, "camsim.bias" );
408  config( m_ron, "camsim.ron" );
409 
410  config( m_xcen, "camsim.xcen" );
411  config( m_ycen, "camsim.ycen" );
412  config( m_peak, "camsim.peak" );
413 
414  if( m_xcen.size() != m_ycen.size() || m_xcen.size() != m_peak.size() )
415  {
416  log<software_error>( { __FILE__, __LINE__, "cameraSim: xcen, ycen, and peak must be the same size." } );
417  }
418 
419  config( m_fwhm, "camsim.fwhm" );
420 
421  config( m_jitter, "camsim.jitter" );
422  return 0;
423 }
424 
426 {
427  if( loadConfigImpl( config ) < 0 )
428  {
429  m_shutdown = 1;
430  }
431 }
432 
434 {
435 
436  //=================================
437  // Do camera configuration here
438 
439  m_ccdTemp = -40;
440  m_ccdTempSetpt = -40;
441 
442  m_readoutSpeedNames = { "one", "two", "three" };
443  m_readoutSpeedNameLabels = { "One", "Two", "Three" };
445 
446  m_vShiftSpeedNames = { "0.1", "0.2", "0.3" };
447  m_vShiftSpeedNameLabels = { "0.1 Hz", "0.2 kHz", "0.4 MhZ" };
449 
450  m_shutterStatus = "READY";
451  m_shutterState = 0;
452 
454  {
455  return log<software_critical, -1>( { __FILE__, __LINE__ } );
456  }
457 
459 
461 
466  m_currentROI.bin_x = 1;
467  m_currentROI.bin_y = 1;
469 
470  m_expTime = 1.0 / m_fps;
472 
473  m_lastTime = mx::sys::get_curr_time();
474  m_offset = 0;
475 
477 
478  return 0;
479 }
480 
482 {
484 
485  // and run stdCamera's appLogic
487  {
488  return log<software_error, -1>( { __FILE__, __LINE__ } );
489  }
490 
491  // and run frameGrabber's appLogic to see if the f.g. thread has exited.
493 
495 
497  {
498  // Get a lock if we can
499  std::unique_lock<std::mutex> lock( m_indiMutex, std::try_to_lock );
500 
501  // but don't wait for it, just go back around.
502  if( !lock.owns_lock() )
503  return 0;
504 
506  {
507  log<software_error>( { __FILE__, __LINE__ } );
509  return 0;
510  }
511 
513  }
514 
515  ///\todo Fall through check?
516 
517  return 0;
518 }
519 
521 {
522 
524 
526 
528 
529  return 0;
530 }
531 
533 {
534  try
535  {
536  recordCamera( true );
537 
538  m_currentROI.x = m_nextROI.x;
539  m_currentROI.y = m_nextROI.y;
540  m_currentROI.w = m_nextROI.w;
541  m_currentROI.h = m_nextROI.h;
542  m_currentROI.bin_x = m_nextROI.bin_x;
543  m_currentROI.bin_y = m_nextROI.bin_y;
544 
545  m_width = m_currentROI.w / m_currentROI.bin_x;
546  m_height = m_currentROI.h / m_currentROI.bin_y;
547  m_xbinning = m_currentROI.bin_x;
548  m_ybinning = m_currentROI.bin_y;
549 
550  m_fgimage.resize( m_width, m_height );
551 
554 
555  recordCamera( true );
556  }
557  catch( ... )
558  {
559  log<software_error>( { __FILE__, __LINE__, "invalid ROI specifications" } );
561  return -1;
562  }
563 
564  return 0;
565 }
566 
568 {
569 
570  m_offset = 0;
571  m_lastTime = mx::sys::get_curr_time();
572 
574 
575  return 0;
576 }
577 
579 {
580  double et = mx::sys::get_curr_time() - m_lastTime;
581  while( et <= m_expTime - m_offset )
582  {
583  mx::sys::nanoSleep( et * 1e6 );
584  et = mx::sys::get_curr_time() - m_lastTime;
585  }
586 
587  double dt = mx::sys::get_curr_time( m_currImageTimestamp );
588 
589  m_offset += 0.1 * ( ( dt - m_lastTime ) - m_expTime );
590 
591  m_lastTime = dt;
592 
593  for( uint32_t cc = 0; cc < m_height; ++cc )
594  {
595  float y = ( cc - 0.5 * ( 1.0 * m_height - 1.0 ) ) +
596  ( m_currentROI.y - 0.5 * ( 1.0 * m_full_h - 1.0 ) ); // Y position relative to the full array
597 
598  for( uint32_t rr = 0; rr < m_width; ++rr )
599  {
600  float x = ( rr - 0.5 * ( 1.0 * m_width - 1.0 ) ) +
601  ( m_currentROI.x - 0.5 * ( 1.0 * m_full_w - 1.0 ) ); // X position realtive to the full array
602 
603  m_fgimage( rr, cc ) = m_bias + m_norm * m_ron;
604 
605  if( m_shutterState == 1 )
606  {
607  for( size_t s = 0; s < m_xcen.size(); ++s )
608  {
609  if( ( fabs( y - m_ycen[s] ) < 4 * m_fwhm ) && ( fabs( x - m_xcen[s] ) < 4 * m_fwhm ) )
610  {
611  float xcen = m_xcen[s] + m_norm * m_jitter;
612  float ycen = m_ycen[s] + m_norm * m_jitter;
613 
614  float flux = mx::math::func::gaussian2D<float>(
615  x, y, 0.0, m_peak[s] * m_expTime, xcen, ycen, mx::math::func::fwhm2sigma( m_fwhm ) );
616  flux += m_norm * sqrt( flux );
617 
618  m_fgimage( rr, cc ) += flux;
619  }
620  }
621  }
622  }
623  }
624 
625  return 0;
626 }
627 
629 {
630 
632  dest, m_fgimage.data(), m_width, m_height, sizeof( uint16_t ) ) == nullptr )
633  {
634  return -1;
635  }
636 
637  m_imageStream->md->atime = m_imageStream->md->writetime;
638 
639  return 0;
640 }
641 
643 {
644 
645  return 0;
646 }
647 
648 inline float cameraSim::fps()
649 {
650  return m_fps;
651 }
652 
654 {
659  m_nextROI.bin_x = m_default_bin_x;
660  m_nextROI.bin_y = m_default_bin_y;
661 
662  return 0;
663 }
664 
666 {
668  return 0;
669 }
670 
672 {
674  return 0;
675 }
676 
678 {
680  return 0;
681 }
682 
684 {
686  return 0;
687 }
688 
690 {
691 
693  m_fps = 1. / m_fps;
694  m_fpsSet = m_fps;
695 
696  log<text_log>( "Set exposure time: " + std::to_string( m_expTimeSet ) + " sec" );
697 
698  m_reconfig = true;
699 
700  return 0;
701 }
702 
703 inline int cameraSim::setFPS()
704 {
705  recordCamera( true );
706 
707  m_fps = m_fpsSet;
708  m_expTime = 1.0 / m_fps;
710 
711  log<text_log>( "Set frame rate: " + std::to_string( m_fps ) + " fps" );
712 
713  m_reconfig = true;
714 
715  return 0;
716 }
717 
719 {
721  return 0;
722 }
723 
725 {
727  return 0;
728 }
729 
731 {
732 
737  updateIfChanged( m_indiP_roi_bin_x, "target", m_nextROI.bin_x, INDI_OK );
738  updateIfChanged( m_indiP_roi_bin_y, "target", m_nextROI.bin_y, INDI_OK );
739 
740  return 0;
741 }
742 
744 {
745  m_reconfig = true;
746 
747  updateSwitchIfChanged( m_indiP_roi_set, "request", pcf::IndiElement::Off, INDI_IDLE );
748  updateSwitchIfChanged( m_indiP_roi_full, "request", pcf::IndiElement::Off, INDI_IDLE );
749  updateSwitchIfChanged( m_indiP_roi_last, "request", pcf::IndiElement::Off, INDI_IDLE );
750  updateSwitchIfChanged( m_indiP_roi_default, "request", pcf::IndiElement::Off, INDI_IDLE );
751  return 0;
752 }
753 
755 {
757  return 0;
758 }
759 
760 inline int cameraSim::setShutter( int ss )
761 {
762  m_shutterState = ss;
763 
764  return 0;
765 }
766 
767 inline std::string cameraSim::stateString()
768 {
769  return "stateString";
770 }
771 
773 {
774  return true;
775 }
776 
778 {
780 }
781 
783 {
784  return recordCamera( true );
785 }
786 
787 } // namespace app
788 } // namespace MagAOX
789 #endif
#define IMAGESTRUCT_UINT16
Definition: ImageStruct.hpp:16
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.
Definition: MagAOXApp.hpp:3120
stateCodes::stateCodeT state()
Get the current state code.
Definition: MagAOXApp.hpp:2297
int m_shutdown
Flag to signal it's time to shutdown. When not 0, the main loop exits.
Definition: MagAOXApp.hpp:100
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.
Definition: MagAOXApp.hpp:3144
static int log(const typename logT::messageT &msg, logPrioT level=logPrio::LOG_DEFAULT)
Make a log entry.
Definition: MagAOXApp.hpp:1804
std::mutex m_indiMutex
Mutex for locking INDI communications.
Definition: MagAOXApp.hpp:545
static constexpr bool c_stdCamera_usesStateString
app::dev confg to tell stdCamera to expose the state string property
Definition: cameraSim.hpp:98
int setFPS()
Set the framerate.
Definition: cameraSim.hpp:703
static constexpr bool c_stdCamera_fps
app::dev config to tell stdCamera not to expose FPS status (ignored since fpsCtrl=true)
Definition: cameraSim.hpp:81
dev::stdCamera< cameraSim > stdCameraT
Definition: cameraSim.hpp:55
std::vector< float > m_xcen
Definition: cameraSim.hpp:115
int setShutter(int ss)
Definition: cameraSim.hpp:760
static constexpr bool c_stdCamera_usesROI
app:dev config to tell stdCamera to expose ROI controls
Definition: cameraSim.hpp:90
std::string stateString()
Definition: cameraSim.hpp:767
static constexpr bool c_stdCamera_fpsCtrl
app::dev config to tell stdCamera to expose FPS controls
Definition: cameraSim.hpp:79
int powerOnDefaults()
Set defaults for a power on state.
Definition: cameraSim.hpp:653
virtual void loadConfig()
load the configuration system results (called by MagAOXApp::setup())
Definition: cameraSim.hpp:425
static constexpr bool c_stdCamera_exptimeCtrl
app::dev config to tell stdCamera to expose exposure time controls
Definition: cameraSim.hpp:76
float m_jitter
the simulated jitter, in pixels/read. the same for all stars. default 0.1.
Definition: cameraSim.hpp:122
static constexpr bool c_stdCamera_hasShutter
app:dev config to tell stdCamera to expose shutter controls
Definition: cameraSim.hpp:95
mx::improc::eigenImage< int16_t > m_fgimage
Definition: cameraSim.hpp:107
int recordTelem(const telem_stdcam *)
Definition: cameraSim.hpp:782
dev::telemeter< cameraSim > telemeterT
Definition: cameraSim.hpp:57
float m_ron
the simulated readout noise, in counts/read. default 5.
Definition: cameraSim.hpp:113
virtual int loadConfigImpl(mx::app::appConfigurator &cfg)
load the configuration system results (called by MagAOXApp::setup())
Definition: cameraSim.hpp:377
std::vector< float > m_peak
the simulated star peak, in counts/second. one per star. default 2000.
Definition: cameraSim.hpp:119
static constexpr bool c_stdCamera_readoutSpeed
app::dev config to tell stdCamera not to expose readout speed controls
Definition: cameraSim.hpp:67
int setNextROI()
Set the next ROI.
Definition: cameraSim.hpp:743
static constexpr bool c_stdCamera_synchro
app::dev config to tell stdCamera to not expose synchro mode controls
Definition: cameraSim.hpp:84
~cameraSim() noexcept
Destructor.
Definition: cameraSim.hpp:263
virtual int appShutdown()
Do any needed shutdown tasks. Currently nothing in this app.
Definition: cameraSim.hpp:520
static constexpr bool c_stdCamera_vShiftSpeed
app:dev config to tell stdCamera not to expose vertical shift speed control
Definition: cameraSim.hpp:70
std::vector< float > m_ycen
Definition: cameraSim.hpp:117
cameraSim()
Default c'tor.
Definition: cameraSim.hpp:236
static constexpr bool c_stdCamera_cropMode
app:dev config to tell stdCamera not to expose Crop Mode controls
Definition: cameraSim.hpp:92
static constexpr bool c_stdCamera_tempControl
app::dev config to tell stdCamera to not expose temperature controls
Definition: cameraSim.hpp:62
static constexpr bool c_stdCamera_temp
app::dev config to tell stdCamera to expose temperature
Definition: cameraSim.hpp:65
mx::math::normDistT< float > m_norm
Definition: cameraSim.hpp:124
static constexpr bool c_frameGrabber_flippable
app:dev config to tell framegrabber that this camera can be flipped
Definition: cameraSim.hpp:101
int setExpTime()
Set the Exposure Time. [stdCamera interface].
Definition: cameraSim.hpp:689
float m_fwhm
the simulated star FWHM in pixels. the same for all stars. default 2.
Definition: cameraSim.hpp:120
int loadImageIntoStream(void *dest)
Definition: cameraSim.hpp:628
static constexpr bool c_stdCamera_emGain
app::dev config to tell stdCamera to not expose EM gain controls
Definition: cameraSim.hpp:73
virtual int appLogic()
Implementation of the FSM for the Siglent SDG.
Definition: cameraSim.hpp:481
dev::frameGrabber< cameraSim > frameGrabberT
Definition: cameraSim.hpp:56
int checkNextROI()
Check the next ROI.
Definition: cameraSim.hpp:730
virtual void setupConfig()
Setup the configuration system (called by MagAOXApp::setup())
Definition: cameraSim.hpp:268
static constexpr bool c_stdCamera_usesModes
app:dev config to tell stdCamera not to expose mode controls
Definition: cameraSim.hpp:87
float m_bias
the simulated bias level. default 500.
Definition: cameraSim.hpp:112
virtual int appStartup()
Startup functions.
Definition: cameraSim.hpp:433
int m_xbinning
The x-binning according to the framegrabber.
timespec m_currImageTimestamp
The timestamp of the current image.
uint32_t m_width
The width of the image, once deinterlaced etc.
void * loadImageIntoStreamCopy(void *dest, void *src, size_t width, size_t height, size_t szof)
int m_ybinning
The y-binning according to the framegrabber.
size_t m_typeSize
The size of the type, in bytes. Result of sizeof.
uint8_t m_dataType
The ImageStreamIO type code.
bool m_reconfig
Flag to set if a camera reconfiguration requires a framegrabber reset.
IMAGE * m_imageStream
The ImageStreamIO shared memory buffer.
uint32_t m_height
The height of the image, once deinterlaced etc.
MagAO-X standard camera interface.
Definition: stdCamera.hpp:287
std::vector< std::string > m_readoutSpeedNames
Definition: stdCamera.hpp:334
float m_fpsSet
The commanded fps, as set by user.
Definition: stdCamera.hpp:375
bool m_synchroSet
Target status of m_synchro.
Definition: stdCamera.hpp:386
pcf::IndiProperty m_indiP_roi_y
Property used to set the ROI x center coordinate.
Definition: stdCamera.hpp:470
float m_default_x
Power-on ROI center x coordinate.
Definition: stdCamera.hpp:450
float m_emGain
The camera's current EM gain (if available).
Definition: stdCamera.hpp:349
std::vector< std::string > m_readoutSpeedNameLabels
Definition: stdCamera.hpp:335
float m_emGainSet
The camera's EM gain, as set by the user.
Definition: stdCamera.hpp:350
std::string m_vShiftSpeedNameSet
The user requested vshift speed name, to be set by derived()
Definition: stdCamera.hpp:344
bool m_cropModeSet
Desired status of crop mode ROIs, if enabled for this camera.
Definition: stdCamera.hpp:495
std::string m_defaultReadoutSpeed
The default readout speed of the camera.
Definition: stdCamera.hpp:300
float m_expTime
The current exposure time, in seconds.
Definition: stdCamera.hpp:367
int m_default_bin_x
Power-on ROI x binning.
Definition: stdCamera.hpp:454
bool m_cropMode
Status of crop mode ROIs, if enabled for this camera.
Definition: stdCamera.hpp:494
int m_default_h
Power-on ROI height.
Definition: stdCamera.hpp:453
pcf::IndiProperty m_indiP_roi_last
Property used to trigger setting the last ROI.
Definition: stdCamera.hpp:485
float m_expTimeSet
The exposure time, in seconds, as set by user.
Definition: stdCamera.hpp:368
pcf::IndiProperty m_indiP_roi_h
Property used to set the ROI height.
Definition: stdCamera.hpp:472
void setupConfig(mx::app::appConfigurator &config)
Setup the configuration system.
Definition: stdCamera.hpp:1035
float m_full_y
The full ROI center y coordinate.
Definition: stdCamera.hpp:458
std::string m_readoutSpeedName
The current readout speed name.
Definition: stdCamera.hpp:337
float m_ccdTempSetpt
The desired temperature, in C.
Definition: stdCamera.hpp:315
bool m_tempControlStatus
Whether or not temperature control is active.
Definition: stdCamera.hpp:317
pcf::IndiProperty m_indiP_roi_w
Property used to set the ROI width.
Definition: stdCamera.hpp:471
pcf::IndiProperty m_indiP_roi_default
Property used to trigger setting the default and startup ROI.
Definition: stdCamera.hpp:486
pcf::IndiProperty m_indiP_roi_bin_x
Property used to set the ROI x binning.
Definition: stdCamera.hpp:473
float m_full_x
The full ROI center x coordinate.
Definition: stdCamera.hpp:457
bool m_synchro
Status of synchronization, true is on, false is off.
Definition: stdCamera.hpp:388
std::string m_vShiftSpeedName
The current vshift speed name.
Definition: stdCamera.hpp:343
float m_ccdTemp
The current temperature, in C.
Definition: stdCamera.hpp:313
int updateINDI()
Update the INDI properties for this device controller.
Definition: stdCamera.hpp:2794
std::vector< std::string > m_vShiftSpeedNames
Definition: stdCamera.hpp:340
std::string m_defaultVShiftSpeed
The default readout speed of the camera.
Definition: stdCamera.hpp:301
void loadConfig(mx::app::appConfigurator &config)
load the configuration system results
Definition: stdCamera.hpp:1074
std::vector< std::string > m_vShiftSpeedNameLabels
Definition: stdCamera.hpp:341
pcf::IndiProperty m_indiP_roi_full
Property used to trigger setting the full ROI.
Definition: stdCamera.hpp:482
pcf::IndiProperty m_indiP_roi_set
Property used to trigger setting the ROI.
Definition: stdCamera.hpp:480
int appShutdown()
Application shutdown.
Definition: stdCamera.hpp:1742
float m_default_y
Power-on ROI center y coordinate.
Definition: stdCamera.hpp:451
pcf::IndiProperty m_indiP_roi_bin_y
Property used to set the ROI y binning.
Definition: stdCamera.hpp:474
pcf::IndiProperty m_indiP_roi_x
Property used to set the ROI x center coordinate.
Definition: stdCamera.hpp:469
int m_default_bin_y
Power-on ROI y binning.
Definition: stdCamera.hpp:455
bool m_tempControlStatusSet
Desired state of temperature control.
Definition: stdCamera.hpp:318
std::string m_readoutSpeedNameSet
The user requested readout speed name, to be set by derived()
Definition: stdCamera.hpp:338
#define FRAMEGRABBER_SETUP_CONFIG(cfig)
Call frameGrabberT::setupConfig with error checking for frameGrabber.
#define FRAMEGRABBER_APP_LOGIC
Call frameGrabberT::appLogic with error checking for frameGrabber.
#define FRAMEGRABBER_APP_SHUTDOWN
Call frameGrabberT::appShutdown with error checking for frameGrabber.
#define FRAMEGRABBER_UPDATE_INDI
Call frameGrabberT::updateINDI with error checking for frameGrabber.
#define FRAMEGRABBER_LOAD_CONFIG(cfig)
Call frameGrabberT::loadConfig with error checking for frameGrabber.
#define FRAMEGRABBER_APP_STARTUP
Call frameGrabberT::appStartup with error checking for frameGrabber.
@ OPERATING
The device is operating, other than homing.
Definition: stateCodes.hpp:55
@ ERROR
The application has encountered an error, from which it is recovering (with or without intervention)
Definition: stateCodes.hpp:43
@ READY
The device is ready for operation, but is not operating.
Definition: stateCodes.hpp:56
@ NOTCONNECTED
The application is not connected to the device or service.
Definition: stateCodes.hpp:49
#define INDI_IDLE
Definition: indiUtils.hpp:28
#define INDI_OK
Definition: indiUtils.hpp:29
void nanoSleep(unsigned long nsec)
std::unique_lock< std::mutex > lock(m_indiMutex)
Definition: dm.hpp:24
A device base class which saves telemetry.
Definition: telemeter.hpp:69
int checkRecordTimes(const telT &tel, telTs... tels)
Check the time of the last record for each telemetry type and make an entry if needed.
Definition: telemeter.hpp:281
Software CRITICAL log entry.
Software ERR log entry.
Log entry recording stdcam stage specific status.
#define TELEMETER_APP_LOGIC
Call telemeter::appLogic with error checking.
Definition: telemeter.hpp:339
#define TELEMETER_LOAD_CONFIG(cfig)
Call telemeter::loadConfig with error checking.
Definition: telemeter.hpp:325
#define TELEMETER_APP_STARTUP
Call telemeter::appStartup with error checking.
Definition: telemeter.hpp:332
#define TELEMETER_SETUP_CONFIG(cfig)
Call telemeter::setupConfig with error checking.
Definition: telemeter.hpp:314
#define TELEMETER_APP_SHUTDOWN
Call telemeter::appShutdown with error checking.
Definition: telemeter.hpp:346