Definitions

  • if only one side has authorized instrument and the other one is authorized for none the telescope is in the monocular mode The telescope is in binocular mode, if both sides are authorized for an instrument
  • both sides can be authorized for none. This state does not have a name.
  • asynchronous operations are executed on one side only
  • synchronous operations are executed on both sides, albeit with a different value of parameters (e.g. different offset values). PCS code waits for the second pair command before starting calculations for synchronous operation
  • PCS, pointing control system, calculates telescope trajectories and optics tip/tilts from RA/Dec pairs of target values
  • OT, observation tool, software where observations are planned

Co-pointing checks

LBT has two optics on a single mount. The optics can tip and tilt from a point on the sky where the telescope is pointed. There are software limits, set currently to 40 arcseconds from midpoint (where telescope is pointed). PCS checks for those and rejects any co-pointings above the limit (and issue warning before limits are hit, when tip/tilt adjustments are above the warning threshold, set to 30 arcseconds). There isn't anything else at PMC/PSF software to reject pointings above the limit. The system is safe for violations of the limits - M1 mirror will panic and go down if actuators forces are over the limit, and M2 hexapod will fail to perform required change if its limits are violated. Co-pointing limits checks can be turned on/off at PCSGUI.

Limit violations costs time (to recover panicked M1). To keep observatory downtime low, it is better to avoid hitting the limits and paying the time penalty for doing so. That's the purpose of the co-pointing check. Detecting co-pointing violations at PCS level is fine, but even better is to limit observers at planning tools (so wrong co-pointing does not make it to PCS). Due to various factors (different side pointing model,..), calculating precise point where M1 or M2 will cause troubles is nearly impossible. Keeping co-pointing limits conservatively low is a good practice.

Performing pointings with great angular separations between sides position should be avoided, as optics performance degrades with increases in tip/tilt corrections needed to fulfil requested pointings.

Due to different performance of the side optics, it is sometimes better to point telescope slightly off midpoint between two synchronous target values. For this, leftWeight parameter is specified (with rightWeigh = 1 - leftWeight). When leftWeight is 0.5, the telescope is pointed to middle points between side target. When leftWeight is 1, the telescope is pointed to the left side coordinates. When leftWeight is 0, the telescope is pointed to the right side coordinates. Any real value between 0 and 1 adjust proportion where the telescope will be pointed as can be deduced from the given examples.

Limits and left side weight are set at pcs/etc/pcs.conf: %CODE{"python" num="49"}% # BINOCULAR # warning (arcseconds) separation of each telescope side from midpoint SXWarningSeparation float 30.0 DXWarningSeparation float 30.0 # error (arcseconds) separation of each telescope side from midpoint SXErrorSeparation float 40.0 DXErrorSeparation float 40.0 # telescope weighting, must add to 1 so only specify one side leftWeight float 0.53 %ENDCODE%

Initial co-poinitng

Assume you place SX and DX as depicted below. MP, telescope midpoint, is calculated as the weighted midpoint between where you place your sides. This is depicted in the following graphics, assuming leftWeight=0.5:

MP DX SX

Both SX and DX are well inside limits, so this pointing is legal.

Offsets

Now you initiate asynchronous offsets on DX side. DX side optics moves a bit, but MP and SX stay where you put them. Warning for DX side is issued, but telescope DX side optics performs the required pointing.

You can then apply offset to SX side, which will be out of limit:

If co-pointing checks are enabled, PCS reject the SX offset command. If checks are disabled at PCSGUI, PCS will try to point SX optics to fulfil required pointing (with observer/telescope operator assuming risks of hitting the M1/M2 limits).

When synchronous offsets are issued, mount position will change. Please note synchronous offsets are currently not supported by OT, as the same can be achieved by issuing new synchronous preset.:

Workflow

The following rules have to be observed when checking for co-pointing limits:
  1. In the monocular mode, any preset changes telescope midpoint
  2. In the binocular mode, only synchronous preset changes telescope midpoint
  3. In the binocular mode, any asynchronous (run only at one side) offset does not change telescope midpoint
  4. In the binocular mode, synchronous offsets can result in a change of telescope midpoint
  5. Absorbing offsets does not change telescope midpoint
  6. If offsets are sent with preset to be applied, the offsets have to be included in midpoint calculation

TCS implementation

As of ~April 2018, the TCS implementation uses optics tips and tilts calculated in the TrajectoryCalculator class. Those tip/tilts are calculated for two telescopes running with zero (effectively without) pointing model. Tip/tilts aren't affected by PSF offloads. Calculating the estimated distance of two sides from telescope midpoint is then equal to a simple task of calculating the length of tip/tilts vectors. TrajectoryCalculator class is extended in TrajectoryGenerator child class to provide mechanisms needed for proper telescope demands calculations and integrations with MCSPU.

TrajectoryCalculator::sideSeparation calculates both sides separations. Please keep in mind dmdTip_ and dmdTilt_ values are used as input for TPK's MountVt::track method, and shall be zeroed for new presets. Calculated SXSeparation and DXSeparation are then used for checks agains configured warning and error limits.

%CODE{lang="cpp" num="666"}% /** * Calculates separation from the mountpoint. Calls calculatePolynomials to calculate new trajectories, then uses DX and SX mirror tip/tilt to caculate DX and SX separation. * * @param side side allowed to move. Can be se to BOTH for both sides (on preset). Should be either SX or DX on asynchronous (one side only) offsets. * @param SXSeparation SX separation from mountpoint, in arcseconds * @param DXSeparation DX separation from mountpoint, in arcseconds * */ void TrajectoryCalculator::sideSeparation (int side, double &SXSeparation, double &DXSeparation) { long long endTime; int unlockedInFastLoop = 0; int status = 0;

bool locking[NUM_SIDE] = { !(side = BOTH || side = SX), !(side = BOTH || side = DX) }; calculatePolynomials(endTime, unlockedInFastLoop, status, locking[SX], locking[DX], NULL);

tpk::xycoord ttSX(dmdTip_[SX], dmdTilt_[SX]); SXSeparation = ttSX.len() * tpk::TcsLib::r2as;

tpk::xycoord ttDX(dmdTip_[DX], dmdTilt_[DX]); DXSeparation = ttDX.len() * tpk::TcsLib::r2as;

SYSLOG << "calculated side separation: SX " << SXSeparation << " DX " << DXSeparation << " locks " << locking[SX] << " " << locking[DX] << " dmd SX " << dmdTip_[SX] * tpk::TcsLib::r2as << " " << dmdTilt_[SX] * tpk::TcsLib::r2as << " DX " << dmdTip_[DX] * tpk::TcsLib::r2as << " " << dmdTilt_[DX] * tpk::TcsLib::r2as << " (all arcsec)" << endl; } %ENDCODE%

Old (wrong) TCS implementation

This section describes prior implementation. As the combination of DETXY and RADEC offsets (particularly when offset absorption was performed) was a bit more challenging than initially estimated, this is not used as of April 2018. The section is kept there only for a reference.

PCS keeps preseted side coordinates and uses those to calculate telescope midpoint. Then distance of sides is checked from this midpoint. Sides coordinates used for midpoint calculation are updated only for monocular operations, or for binocular operations if preset/offsets are synchronous. When a synchronous offset is to be executed, sides coordinates are updated and used for this and any following midpoint calculations. By keeping sides coordinates separate from the pointing origin, absorb etc. operations executed on pointing origin do not affect midpoint calculations.

Standard code to calculate midpoint looks like this:

%CODE{ lang="cpp" num="5438" }% // Compute the refPoint between the second Offset of a SYNCOFFSET sequence // and the first processed Offset if (wait4PairOffsets && (firstSideOfOffsetPair = side)) { if ((side = SX) && (tempObjDX NULL)) refPoint = computeMidpoint (obj, tempObjDX); else if ((side = DX) && (tempObjSX NULL)) refPoint = computeMidpoint (obj, tempObjSX); // Otherwise do the test for an async Offset } else { if ((side = SX) && (firstSideOfOffsetPair side)) { refPoint = computeMidpoint (midSX_, midDX_); } else if ((side = DX) && (firstSideOfOffsetPair side)) { refPoint = computeMidpoint (midDX_, midSX_); } } %ENDCODE%

where:

  • tempObj<SIDE> is object sided coordinate calculated in other pair of an synchronous offset
  • obj is object coordinate calculated for current side
  • mid<SIDE>_ is coordinate of side

Those two functions, defined at pcs/Utility.cpp, are used to calculate midpoint:

%CODE{ lang="cpp" num="97"}% // Compute the midpoint on-sky between the targets on the two sides of the telescope // using ObjectBuffer objects (done in PCSSubsystem class) tpk::xycoord computeMidpoint (ObjectBuffer *obj1, ObjectBuffer *obj2) { double raMid = 0.0; double decMid = 0.0;

tpk::spherical raDec1 = obj1->getCorrectedCoordinates(); tpk::spherical raDec2 = obj2->getCorrectedCoordinates();

// These values are in radians double ra1 = raDec1.a; double dec1 = raDec1.b; double ra2 = raDec2.a; double dec2 = raDec2.b;

// This is the midpoint calculation - this computation // works properly even if the two coordinates are the same double deltaRa = ra2 - ra1; double Bx = cos(dec2) * cos (deltaRa); double By = cos(dec2) * sin (deltaRa); double decTerm1 = sin(dec1) + sin(dec2); double decTerm2 = sqrt(pow((cos(dec1) + Bx),2) + pow(By,2)); decMid = atan2(decTerm1, decTerm2); raMid = ra1 + atan2(By, cos(dec1)+Bx);

ostringstream raStr, decStr, ra1Str, dec1Str, ra2Str, dec2Str; convertEqCoords (raMid, decMid, raStr, decStr); convertEqCoords (ra1, dec1, ra1Str, dec1Str); convertEqCoords (ra2, dec2, ra2Str, dec2Str); SYSLOG << "Co-point check MIDPOINT RA: " << raStr.str() << " MIDPOINT Dec: " << decStr.str() << " Obj1: " << ra1Str.str() << " " << dec1Str.str() << " Obj2: " << ra2Str.str() << " " << dec2Str.str() << endl;

tpk::xycoord midPoint(raMid, decMid); return (midPoint); }

// Compute the midpoint on-sky between the targets on the two sides of the telescope // using spherical coordinates (done in TrajectoryGenerator class) tpk::spherical computeMidpoint (tpk::spherical raDec1, tpk::spherical raDec2) { double raMid = 0.0; double decMid = 0.0;

// These values are in radians double ra1 = raDec1.a; double dec1 = raDec1.b; double ra2 = raDec2.a; double dec2 = raDec2.b;

// This is the midpoint calculation - this computation // works properly even if the two coordinates are the same double deltaRa = ra2 - ra1; double Bx = cos(dec2) * cos (deltaRa); double By = cos(dec2) * sin (deltaRa); double decTerm1 = sin(dec1) + sin(dec2); double decTerm2 = sqrt(pow((cos(dec1) + Bx),2) + pow(By,2)); decMid = atan2(decTerm1, decTerm2); raMid = ra1 + atan2(By, cos(dec1)+Bx);

/* // Do not print this unless debugging as it is in a 20Hz loop ostringstream raStr, decStr; convertEqCoords (raMid, decMid, raStr, decStr); SYSLOG << "Mount Midpoint RA: " << raStr.str() << " Midpoint Dec: " << decStr.str() << endl; */

tpk::spherical midPoint(raMid, decMid); return (midPoint); } %ENDCODE%
Topic revision: r11 - 07 Dec 2018, PetrKubanek
This site is powered by FoswikiCopyright © by the contributing authors. All material on this collaboration platform is the property of the contributing authors.
Ideas, requests, problems regarding Foswiki? Send feedback