neclib.simulators.dome#

Emulator for telescope dome motion and corresponding encoder reading.

Aliases#

AzElData

AzElData(az: Any = None, el: Any = None)

InitialPosition

AzElData(az: Any = None, el: Any = None)

ParameterList

List, specialized in parameter storing.

class DomeEncoderEmulator(device_moment_of_inertia=(<function <lambda>>, <Quantity 3000. m2 kg>), motor_torque=(<Quantity 11.5 N m>, <Quantity 11.5 N m>), angular_resolution=(<Quantity 0.13728814 arcsec>, <Quantity 0.13728814 arcsec>))[source]#

Bases: object

Emulator of dome response for simulator.

Parameters:
  • device_moment_of_inertia (Tuple[Union[Quantity, Callable[[Quantity, Quantity], Quantity]], Union[Quantity, Callable[[Quantity, Quantity], Quantity]]]) – Moment of inertia of dome.

  • motor_torque (Tuple[Quantity, Quantity]) – Maximum torque the motor can exert.

  • angular_resolution (Tuple[Quantity, Quantity]) – Angular resolution of the encoder.

Notes

To support coordinate-dependent moment of inertia, Az. and El. axes cannot independently be implemented.

Warning

API may change, as API of encoder driver module isn’t fixed yet.

Example

>>> enc = neclib.simulators.DomeEncoderEmulator()
>>> pid_az = neclib.controllers.PIDController()
>>> speed = pid_az.get_speed(30, enc.read.az)
>>> enc.command(speed, "az")
ANGLE_UNIT: ClassVar[Literal['deg', 'rad', 'arcmin', 'arcsec']] = 'deg'#
property abs_acceleration: AzElData#

Absolute value of angular acceleration at the moment.

property dt: float#

Time interval between last two call for encoder reading.

read()[source]#

Get current encoder reading.

Notes

Acceleration during consecutive calls are approximated to be constant.

Examples

>>> v = enc.read()
>>> v.az
12.3
Return type:

AzElData

command(speed, axis)[source]#

Set angular speed of intention with angular unit ANGLE_UNIT.

Parameters:
  • speed (float) – Angular speed, which may be calculated by PID controller.

  • axis (Literal['az', 'el']) – Controlling altazimuth axis.

Return type:

None