OSSIM - Open Source Software Image Map  Version 1.9.0 (20180803)
Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
ossimRS1SarModel Class Reference

#include <ossimRS1SarModel.h>

Inheritance diagram for ossimRS1SarModel:
ossimSensorModel ossimProjection ossimOptimizableProjection ossimAdjustableParameterInterface ossimObject ossimErrorStatusInterface ossimReferenced

Public Types

enum  ImagingMode {
  UNKNOWN_MODE = 0, SCN, SCW, SGC,
  SGF, SGX, SLC, SPG,
  SSG, RAW, ERS
}
 
enum  DirectionFlag { UNKNOWN_DIRECTION = 0, ASCENDING, DESCENDING }
 
- Public Types inherited from ossimSensorModel
enum  CovMatStatus { COV_INVALID = 0, COV_PARTIAL = 1, COV_FULL = 2 }
 
enum  DeriveMode {
  OBS_INIT =-99, EVALUATE =-98, P_WRT_X = -1, P_WRT_Y = -2,
  P_WRT_Z = -3
}
 

Public Member Functions

 ossimRS1SarModel ()
 
 ossimRS1SarModel (const ossimFilename &imageDir)
 
virtual ~ossimRS1SarModel ()
 
virtual bool saveState (ossimKeywordlist &kwl, const char *prefix=NULL) const
 Fulfills ossimObject base-class pure virtuals. More...
 
virtual bool loadState (const ossimKeywordlist &kwl, const char *prefix=NULL)
 Fulfills ossimObject base-class pure virtuals. More...
 
virtual void lineSampleHeightToWorld (const ossimDpt &imagePt, const double &heightAboveEllipsoid, ossimGpt &worldPt) const
 Establishes geographic 3D point given image line, sample and ellipsoid height. More...
 
virtual void imagingRay (const ossimDpt &image_point, ossimEcefRay &image_ray) const
 Given an image point, returns a ray originating at some arbitrarily high point (in this model at the sensor position) and pointing towards the target. More...
 
virtual bool useForward () const
 
virtual ossimObjectdup () const
 image to ground faster More...
 
- Public Member Functions inherited from ossimSensorModel
 ossimSensorModel ()
 
 ossimSensorModel (const ossimSensorModel &copy_this)
 
 ossimSensorModel (const ossimKeywordlist &geom_kwl)
 
const ossimSensorModeloperator= (const ossimSensorModel &rhs)
 assignment operator More...
 
virtual ossimObjectgetBaseObject ()
 
virtual const ossimObjectgetBaseObject () const
 
virtual ossimGpt origin () const
 
virtual ossimDpt getMetersPerPixel () const
 
virtual const double & getNominalPosError () const
 Returns the estimated Absolute horizontal position error (CE90) of the sensor model. More...
 
virtual const double & getRelativePosError () const
 Returns the estimated RELATIVE horizontal position error (CE90) of the sensor model. More...
 
virtual void setNominalPosError (const double &ce90)
 Assigns the absolute image position error uncertainty (abs CE90) More...
 
virtual void setRelativePosError (const double &ce90)
 Assigns the relative image position error uncertainty (rel CE90) More...
 
virtual void lineSampleToWorld (const ossimDpt &image_point, ossimGpt &world_point) const
 
virtual void worldToLineSample (const ossimGpt &world_point, ossimDpt &image_point) const
 
virtual std::ostream & print (std::ostream &out) const
 
void setRefImgPt (const ossimDpt &pt)
 Sets the center line sampe of the image. More...
 
void setRefGndPt (const ossimGpt &pt)
 Sets the center latitude, longitude, height of the image. More...
 
void setImageRect (const ossimDrect &imageRect)
 
void setGroundRect (const ossimGpt &ul, const ossimGpt &ur, const ossimGpt &lr, const ossimGpt &ll)
 
ossimDpt imageSize () const
 
void setImageSize (const ossimDpt &size)
 
virtual void adjustableParametersChanged ()
 
virtual void updateModel ()
 
virtual bool insideImage (const ossimDpt &p) const
 
virtual bool operator== (const ossimProjection &proj) const
 
const ossimStringgetImageID () const
 Access methods: More...
 
const ossimDrectgetImageClipRect () const
 
virtual ossim_uint32 degreesOfFreedom () const
 
virtual bool needsInitialState () const
 needsInitialState() More...
 
virtual double optimizeFit (const ossimTieGptSet &tieSet, double *targetVariance=0)
 
virtual ossimDpt getForwardDeriv (int parmIdx, const ossimGpt &gpos, double hdelta=1e-11)
 
virtual ossimGpt getInverseDeriv (int parmIdx, const ossimDpt &ipos, double hdelta=1e-11)
 
virtual ossimSensorModel::CovMatStatus getObsCovMat (const ossimDpt &ipos, NEWMAT::SymmetricMatrix &Cov, const ossim_float64 defPointingSigma=0.5) const
 Gives 2X2 covariance matrix of observations. More...
 
virtual bool isAffectedByElevation () const
 Implementation of pure virtual ossimProjection::isAffectedByElevation method. More...
 
void computeGsd ()
 This method computes the ground sample distance(gsd) and sets class attributes theGSD and theMeanGSD by doing a lineSampleHeightToWorld on four points and calculating the distance from them. More...
 
virtual bool getImageGeometry (const ossimString &, const ossimString &, ossimKeywordlist &) const
 Extracts geometry info from a non-ossim key,value pair to an ossim keyword list. More...
 
- Public Member Functions inherited from ossimProjection
 ossimProjection ()
 
virtual ~ossimProjection ()
 
virtual ossimDpt forward (const ossimGpt &wp) const
 
virtual ossimGpt inverse (const ossimDpt &pp) const
 
virtual void getRoundTripError (const ossimDpt &imagePoint, ossimDpt &errorResult) const
 
virtual void getRoundTripError (const ossimGpt &groundPoint, ossimDpt &errorResult) const
 
virtual void getGroundClipPoints (ossimGeoPolygon &gpts) const
 
virtual bool isEqualTo (const ossimObject &obj, ossimCompareType compareType=OSSIM_COMPARE_FULL) const
 
virtual bool operator!= (const ossimProjection &projection) const
 
- Public Member Functions inherited from ossimObject
 ossimObject ()
 
virtual ~ossimObject ()
 
virtual ossimString getShortName () const
 
virtual ossimString getLongName () const
 
virtual ossimString getDescription () const
 
virtual ossimString getClassName () const
 
virtual RTTItypeid getType () const
 
virtual bool canCastTo (ossimObject *obj) const
 
virtual bool canCastTo (const RTTItypeid &id) const
 
virtual bool canCastTo (const ossimString &parentClassName) const
 
virtual void accept (ossimVisitor &visitor)
 
- Public Member Functions inherited from ossimReferenced
 ossimReferenced ()
 
 ossimReferenced (const ossimReferenced &)
 
ossimReferencedoperator= (const ossimReferenced &)
 
void ref () const
 increment the reference count by one, indicating that this object has another pointer which is referencing it. More...
 
void unref () const
 decrement the reference count by one, indicating that a pointer to this object is referencing it. More...
 
void unref_nodelete () const
 decrement the reference count by one, indicating that a pointer to this object is referencing it. More...
 
int referenceCount () const
 
- Public Member Functions inherited from ossimErrorStatusInterface
 ossimErrorStatusInterface ()
 
virtual ~ossimErrorStatusInterface ()
 
virtual ossimErrorCode getErrorStatus () const
 
virtual ossimString getErrorStatusString () const
 
virtual void setErrorStatus (ossimErrorCode error_status) const
 
virtual void setErrorStatus () const
 
virtual void clearErrorStatus () const
 
bool hasError () const
 
- Public Member Functions inherited from ossimOptimizableProjection
 ossimOptimizableProjection ()
 
 ossimOptimizableProjection (const ossimOptimizableProjection &source)
 
virtual ~ossimOptimizableProjection ()
 
virtual ossimOptimizableProjectionoperator= (const ossimOptimizableProjection &source)
 
virtual bool setupOptimizer (const ossimString &setup)
 setupFromString() Derived classes should implement as needed. Initialize parameters needed for optimizeFit and degreesOfFreedom More...
 
- Public Member Functions inherited from ossimAdjustableParameterInterface
 ossimAdjustableParameterInterface ()
 
 ossimAdjustableParameterInterface (const ossimAdjustableParameterInterface &rhs)
 
virtual ~ossimAdjustableParameterInterface ()
 
void newAdjustment (ossim_uint32 numberOfParameters=0)
 
void setAdjustmentDescription (const ossimString &description)
 
ossimString getAdjustmentDescription () const
 
ossimString getAdjustmentDescription (ossim_uint32 adjustmentIdx) const
 Returns adjustmentDescription of specific adjustmentInfo. More...
 
void setCurrentAdjustment (ossim_uint32 adjustmentIndex, bool notify=false)
 
bool setCurrentAdjustment (const ossimString &description, bool notify=false)
 Sets the current adjustment to the adjustment with a matching description. More...
 
void eraseAdjustment (bool notify)
 
void eraseAdjustment (ossim_uint32 idx, bool notify)
 
virtual void initAdjustableParameters ()
 
void resetAdjustableParameters (bool notify=false)
 
void copyAdjustment (ossim_uint32 idx, bool notify)
 
void copyAdjustment (bool notify=false)
 
void keepAdjustment (ossim_uint32 idx, bool createCopy)
 
virtual void keepAdjustment (bool createCopy=true)
 
const ossimAdjustableParameterInterfaceoperator= (const ossimAdjustableParameterInterface &rhs)
 
void removeAllAdjustments ()
 
ossim_uint32 getNumberOfAdjustableParameters () const
 
double getAdjustableParameter (ossim_uint32 idx) const
 
virtual void setAdjustableParameter (ossim_uint32 idx, double value, bool notify=false)
 
virtual void setAdjustableParameter (ossim_uint32 idx, double value, double sigma, bool notify=false)
 
double getParameterSigma (ossim_uint32 idx) const
 
void setParameterSigma (ossim_uint32 idx, double value, bool notify=false)
 
ossimUnitType getParameterUnit (ossim_uint32 idx) const
 
void setParameterUnit (ossim_uint32 idx, ossimUnitType unit)
 
void setParameterUnit (ossim_uint32 idx, const ossimString &unit)
 
void setParameterCenter (ossim_uint32 idx, double center, bool notify=false)
 
double getParameterCenter (ossim_uint32 idx) const
 
double computeParameterOffset (ossim_uint32 idx) const
 
void setParameterOffset (ossim_uint32 idx, ossim_float64 value, bool notify=false)
 
ossimString getParameterDescription (ossim_uint32 idx) const
 
void setParameterDescription (ossim_uint32 idx, const ossimString &descrption)
 
ossim_int32 findParameterIdxGivenDescription (ossim_uint32 adjustmentIdx, const ossimString &name) const
 
ossim_int32 findParameterIdxContainingDescription (ossim_uint32 adjustmentIdx, const ossimString &name) const
 
bool isParameterLocked (ossim_uint32 idx) const
 
void setParameterLockFlag (ossim_uint32 idxParam, bool flag)
 
bool getParameterLockFlag (ossim_uint32 idx) const
 
void lockAllParametersCurrentAdjustment ()
 
void unlockAllParametersCurrentAdjustment ()
 
void lockAllParameters (ossim_uint32 idxAdjustment)
 
void unlockAllParameters (ossim_uint32 idxAdjustment)
 
void resizeAdjustableParameterArray (ossim_uint32 numberOfParameters)
 
void setAdjustment (const ossimAdjustmentInfo &adj, bool notify=false)
 
void setAdjustment (ossim_uint32 idx, const ossimAdjustmentInfo &adj, bool notify=false)
 
void addAdjustment (const ossimAdjustmentInfo &adj, bool notify)
 
void getAdjustment (ossimAdjustmentInfo &adj) const
 
void getAdjustment (ossim_uint32 idx, ossimAdjustmentInfo &adj) const
 
ossim_uint32 getNumberOfAdjustments () const
 
ossim_uint32 getCurrentAdjustmentIdx () const
 
void setDirtyFlag (bool flag=true)
 
void setAllDirtyFlag (bool flag=true)
 
bool hasDirtyAdjustments () const
 
virtual void saveCurrentAdjustmentOnly (ossimKeywordlist &kwl, const ossimString &prefix=ossimString(""))
 Saves the current active adjustment to the KWL file. More...
 
bool saveAdjustments (ossimKeywordlist &kwl, const ossimString &prefix=ossimString("")) const
 Save all adjustments to the KWL file. More...
 
bool loadAdjustments (const ossimKeywordlist &kwl, const ossimString &prefix=ossimString(""))
 
std::ostream & print (std::ostream &out) const
 Dumps the currently active adjustment to ostream. More...
 

Protected Types

enum  ADJUSTABLE_PARAM_INDEXES {
  INTRACK_OFFSET, CRTRACK_OFFSET, RADIAL_OFFSET, LINE_SCALE,
  SKEW, ORIENTATION, NUM_ADJUSTABLE_PARAMS
}
 

Protected Member Functions

void setImagingMode (char *modeStr)
 
void initFromCeos (const ossimFilename &dataDir)
 
void initAdjParms ()
 
void establishEphemeris ()
 
void eciToEcfXform (const double &julianDay, NEWMAT::Matrix &xform) const
 
void establishOrpInterp ()
 
void establishOrpGrid ()
 
void establishVehicleSpace ()
 
void interpolatedScanORP (const ossimDpt &orp, ossimEcefPoint &orp_ecf) const
 
void deallocateMemory ()
 
- Protected Member Functions inherited from ossimSensorModel
virtual ~ossimSensorModel ()
 
virtual ossimDpt extrapolate (const ossimGpt &gp) const
 
virtual ossimGpt extrapolate (const ossimDpt &ip, const double &height=ossim::nan()) const
 
void buildNormalEquation (const ossimTieGptSet &tieSet, NEWMAT::SymmetricMatrix &A, NEWMAT::ColumnVector &residue, NEWMAT::ColumnVector &projResidue, double pstep_scale)
 
NEWMAT::ColumnVector getResidue (const ossimTieGptSet &tieSet)
 
NEWMAT::ColumnVector solveLeastSquares (NEWMAT::SymmetricMatrix &A, NEWMAT::ColumnVector &r) const
 
NEWMAT::Matrix invert (const NEWMAT::Matrix &m) const
 stable invert stolen from ossimRpcSolver More...
 
- Protected Member Functions inherited from ossimReferenced
virtual ~ossimReferenced ()
 
- Protected Member Functions inherited from ossimAdjustableParameterInterface
bool paramChanged (ossim_uint32 param_idx) const
 Returns true if specified parameter has been modified since last setAllChangeFlag(false) call. More...
 
void setAllChangeFlags (bool areChanged)
 Sets all the change flags to the boolean indicated to indicate parameters are changed (TRUE) or not (FALSE). More...
 
void initChangeFlags ()
 Initializes the change flags to TRUE. More...
 

Protected Attributes

ossimRefPtr< ossimCeosDatatheCeosData
 
ossimRefPtr< ossimLagrangeInterpolatortheArpPosInterp
 
ossimRefPtr< ossimLagrangeInterpolatortheArpVelInterp
 
ossimRefPtr< ossimLagrangeInterpolatortheLocalOrpInterp
 
ImagingMode theImagingMode
 
double theIllumAzimuth
 
double theIllumElevation
 
ossimEcefPoint theORP
 
double theRefHeight
 
double theGHA
 
double theEphFirstSampTime
 
double theSinOrientation
 
double theCosOrientation
 
double theSinSkew
 
ossimLsrSpace theVehicleSpace
 
ossimEcefVector thePosCorrection
 
int theFirstLineDay
 
double theFirstLineTime
 
double theTimePerLine
 
DirectionFlag theDirectionFlag
 
double theSrGrCoeff [6]
 
ossimDpt thePixelSpacing
 
ossimDblGrid theLatGrid
 
ossimDblGrid theLonGrid
 
double theInTrackOffset
 
double theCrTrackOffset
 
double theRadialOffset
 
double theLineScale
 
double theSkew
 
double theOrientation
 
- Protected Attributes inherited from ossimSensorModel
ossimIpt theImageSize
 
ossimDpt theSubImageOffset
 
ossimString theImageID
 
ossimString theSensorID
 
ossimDpt theGSD
 
ossim_float64 theMeanGSD
 
ossimGpt theRefGndPt
 
ossimDpt theRefImgPt
 
ossimPolygon theBoundGndPolygon
 
ossimDrect theImageClipRect
 
ossim_float64 theRelPosError
 
ossim_float64 theNominalPosError
 
ossimDpt theParWRTx
 Partials for current point. More...
 
ossimDpt theParWRTy
 
ossimDpt theParWRTz
 
ossimDpt theObs
 Observations & residuals for current point. More...
 
ossimDpt theResid
 
ossimRefPtr< ossimProjectiontheSeedFunction
 Used as an initial guess for iterative solutions and a guess for points outside the support bounds. More...
 
bool theExtrapolateImageFlag
 
bool theExtrapolateGroundFlag
 
- Protected Attributes inherited from ossimErrorStatusInterface
ossimErrorCode theErrorStatus
 

Additional Inherited Members

- Static Public Member Functions inherited from ossimSensorModel
static void writeGeomTemplate (ostream &os)
 

Detailed Description

Definition at line 37 of file ossimRS1SarModel.h.

Member Enumeration Documentation

◆ ADJUSTABLE_PARAM_INDEXES

Enumerator
INTRACK_OFFSET 
CRTRACK_OFFSET 
RADIAL_OFFSET 
LINE_SCALE 
SKEW 
ORIENTATION 
NUM_ADJUSTABLE_PARAMS 

Definition at line 142 of file ossimRS1SarModel.h.

◆ DirectionFlag

Enumerator
UNKNOWN_DIRECTION 
ASCENDING 
DESCENDING 

Definition at line 60 of file ossimRS1SarModel.h.

◆ ImagingMode

Enumerator
UNKNOWN_MODE 
SCN 
SCW 
SGC 
SGF 
SGX 
SLC 
SPG 
SSG 
RAW 
ERS 

Definition at line 45 of file ossimRS1SarModel.h.

46  {
47  UNKNOWN_MODE = 0,
48  SCN, // ScanSAR Narrow Beam
49  SCW, // ScanSAR Wide Beam
50  SGC, // SAR Georeferenced Coarse Resolution
51  SGF, // SAR Georeferenced Fine Resolution
52  SGX, // SAR Georeferenced Extra Fine Resolution
53  SLC, // Single Look Complex
54  SPG, // SAR Precision Geocoded
55  SSG, // SAR Systematically Geocoded
56  RAW,
57  ERS
58  };

Constructor & Destructor Documentation

◆ ossimRS1SarModel() [1/2]

ossimRS1SarModel::ossimRS1SarModel ( )

Definition at line 48 of file ossimRS1SarModel.cpp.

References ossimErrorStatusInterface::setErrorStatus().

49 : theCeosData (0),
51 {
53 }
ImagingMode theImagingMode
ossimRefPtr< ossimCeosData > theCeosData

◆ ossimRS1SarModel() [2/2]

ossimRS1SarModel::ossimRS1SarModel ( const ossimFilename imageDir)

Definition at line 59 of file ossimRS1SarModel.cpp.

60  :
61  theCeosData (0),
63 {
64  static const char MODULE[] = "Constructor ossimRS1SarModel(ossimFilename)";
65  if (traceDebug()) CLOG << "entering..." << endl;
66 
68 
69  // Parse the CEOS data files:
70  ossimFilename dataDirName (imageFile.path());
71  initFromCeos(dataDirName);
73  {
74  return;
75  }
77  return;
78 
79  // Parse the image data file for the local ORPs interpolator:
80  if ((theImagingMode == SCN) || (theImagingMode == SCW))
82  else
84 
85  // Establish the ephemeris interpolator:
87 
88  initAdjParms();
90 
91  if (traceDebug()) CLOG << "returning..." << endl;
92  return;
93 }
#define CLOG
Definition: ossimTrace.h:23
static const ossimErrorCode OSSIM_OK
ImagingMode theImagingMode
virtual ossimErrorCode getErrorStatus() const
void initFromCeos(const ossimFilename &dataDir)
ossimRefPtr< ossimCeosData > theCeosData

◆ ~ossimRS1SarModel()

ossimRS1SarModel::~ossimRS1SarModel ( )
virtual

Definition at line 99 of file ossimRS1SarModel.cpp.

References deallocateMemory().

100 {
102 }

Member Function Documentation

◆ deallocateMemory()

void ossimRS1SarModel::deallocateMemory ( )
protected

Definition at line 1072 of file ossimRS1SarModel.cpp.

Referenced by ~ossimRS1SarModel().

1073 {
1074  static const char MODULE[] = "ossimRS1SarModel::deallocateMemory()";
1075  if (traceDebug()) CLOG << "entering..." << endl;
1076 
1077  theArpPosInterp = 0;
1078  theArpVelInterp = 0;
1079  theLocalOrpInterp = 0;
1080  theCeosData = 0;
1081  theLatGrid.clear();
1082  theLonGrid.clear();
1083 
1084  if (traceDebug()) CLOG << "returning..." << endl;
1085 }
ossimRefPtr< ossimLagrangeInterpolator > theArpPosInterp
ossimRefPtr< ossimLagrangeInterpolator > theLocalOrpInterp
#define CLOG
Definition: ossimTrace.h:23
ossimRefPtr< ossimLagrangeInterpolator > theArpVelInterp
ossimDblGrid theLonGrid
ossimDblGrid theLatGrid
ossimRefPtr< ossimCeosData > theCeosData

◆ dup()

virtual ossimObject* ossimRS1SarModel::dup ( ) const
inlinevirtual

image to ground faster

Returns pointer to a new instance, copy of this.

Implements ossimProjection.

Definition at line 87 of file ossimRS1SarModel.h.

87 { return 0; } // TBR

◆ eciToEcfXform()

void ossimRS1SarModel::eciToEcfXform ( const double &  julianDay,
NEWMAT::Matrix &  xform 
) const
protected

Definition at line 672 of file ossimRS1SarModel.cpp.

673 {
674  static const char MODULE[] = "ossimRS1SarModel::eciToEcfXform(acq_time)";
675  if (traceDebug()) CLOG << "entering..." << endl;
676 
677  // Determine time elapsed since ephemeris first sample time:
678  double delta_t = acq_time - theEphFirstSampTime;
679 
680  // Compute GHA at time of this image line (in degrees):
681  double gha = theGHA + delta_t*DEG_PER_SEC;
682  if (gha >= 360.0)
683  gha -=360.0;
684  else if (gha < 0.0)
685  gha += 360.0;
686 
687  // Establish rotation:
688  double cos_gha = ossim::cosd(gha);
689  double sin_gha = ossim::sind(gha);
690 
691  // Establish rotation matrix:
692  xform = ossimMatrix3x3::create(cos_gha, sin_gha, 0.0,
693  -sin_gha, cos_gha, 0.0,
694  0.0, 0.0, 1.0);
695  if (traceDebug())
696  {
697  CLOG << "DEBUG -- "
698  << "\n\t acq_time = " << acq_time
699  << "\n\t delta_t = " << delta_t
700  << "\n\t gha = " << gha << endl;
701  }
702 
703  if (traceDebug()) CLOG << "returning..." << endl;
704 }
#define CLOG
Definition: ossimTrace.h:23
double sind(double x)
Definition: ossimCommon.h:260
static NEWMAT::Matrix create()
double cosd(double x)
Definition: ossimCommon.h:259

◆ establishEphemeris()

void ossimRS1SarModel::establishEphemeris ( )
protected

Definition at line 579 of file ossimRS1SarModel.cpp.

580 {
581  static const char MODULE[] = "ossimRS1SarModel::establishEphemeris()";
582  if (traceDebug()) CLOG << "entering..." << endl;
583 
584  char buf[23];
585 
586  // Establish pointer to platform position data record:
587  const pos_data_rec* pdr = theCeosData->posDataRec();
588 
589  // Establish the Greenwich mean hour angle at time of first sample:
590  char gha_str [23];
591  strncpy(gha_str, pdr->hr_angle, 22);
592  gha_str[22] = '\0';
593  theGHA = atof(gha_str);
594 
595  // Fetch number of points in record and allocate memory:
596  strncpy(buf, pdr->ndata, 4);
597  buf[4] = '\0';
598  int numPoints = atoi(buf);
599 
600  // Fetch sampling period:
601  strncpy(buf, pdr->data_int, 22);
602  buf[22] = '\0';
603  double sampling_period = atof(buf);
604 
605  // Establish the first sample time's day:
606  strncpy(buf, pdr->gmt_day, 4);
607  buf[4] = '\0';
608  int first_day = atoi(buf);
609  double time_offset = (double) (first_day - theFirstLineDay)*SEC_PER_DAY;
610 
611  // Establish the first sample time in seconds from beginning of day:
612  strncpy(buf, pdr->gmt_sec, 22);
613  buf[22] = '\0';
614  theEphFirstSampTime = atof(buf) + time_offset;
615 
616  int i, j;
617  double sample_time = theEphFirstSampTime;
618  buf[22] = '\0';
619  NEWMAT::ColumnVector eciArpPos(3);
620  NEWMAT::ColumnVector eciArpVel(3);
621  NEWMAT::ColumnVector ecfArpPos(3);
622  NEWMAT::ColumnVector ecfArpVel(3);
623  NEWMAT::ColumnVector earthVel(3);
624  NEWMAT::Matrix xform;
627 
628  // Loop over each point, converting them to vectors:
629  for (i=0; i<numPoints; i++)
630  {
631  for (j=0; j<3; j++)
632  {
633  strncpy(buf, pdr->pos_vect[i].pos[j], 22);
634  eciArpPos[j] = atof(buf);
635  strncpy(buf, pdr->pos_vect[i].vel[j], 22);
636  eciArpVel[j] = atof(buf)/1000.0;
637  }
638 
639  // Convert pos and vel vectors from ECI to ECF:
640  eciToEcfXform(sample_time, xform);
641  ecfArpPos = xform*eciArpPos;
642  ecfArpVel = xform*eciArpVel;
643  theArpPosInterp->addData(sample_time, ecfArpPos);
644 
645  // Correct velocity for earth rotation:
646  earthVel[0] = -ecfArpPos[1]*EARTH_ANGULAR_VELOCITY;
647  earthVel[1] = ecfArpPos[0]*EARTH_ANGULAR_VELOCITY;
648  earthVel[2] = 0.0;
649  ecfArpVel = ecfArpVel - earthVel;
650  theArpVelInterp->addData(sample_time, ecfArpVel);
651 
652  sample_time += sampling_period;
653  }
654 
655  if (traceDebug())
656  {
657  CLOG << "DEBUG -- "
658  << "\n\t theGHA: " << theGHA
659  << "\n\t numPoints: " << numPoints
660  << "\n\t sampling_period: " << sampling_period
661  << "\n\t theEphFirstSampTime: " << theEphFirstSampTime << endl;
662  }
663 
664  if (traceDebug()) CLOG << "returning..." << endl;
665 }
ossimRefPtr< ossimLagrangeInterpolator > theArpPosInterp
char pos[3][22]
#define CLOG
Definition: ossimTrace.h:23
char gmt_sec[22]
struct pos_vect_rec pos_vect[64]
void addData(const double &t, const NEWMAT::ColumnVector &data)
char gmt_day[4]
ossimRefPtr< ossimLagrangeInterpolator > theArpVelInterp
const pos_data_rec * posDataRec() const
char hr_angle[22]
char vel[3][22]
void eciToEcfXform(const double &julianDay, NEWMAT::Matrix &xform) const
char data_int[22]
ossimRefPtr< ossimCeosData > theCeosData

◆ establishOrpGrid()

void ossimRS1SarModel::establishOrpGrid ( )
protected

Definition at line 928 of file ossimRS1SarModel.cpp.

929 {
930  static const char MODULE[] = "ossimRS1SarModel::establishOrpGrid()";
931  if (traceDebug()) CLOG << "entering..." << endl;
932 
933  if (traceDebug())
934  {
935  CLOG << "DEBUG -- " << endl;
936  }
937 
938  static const int NUM_GRID_POINTS_U = 11;
939 
940  desc_rec descRec;
941  pdr_prefix_rec prefix;
942  int sizeOfDescRec = sizeof(descRec);
943  int sizeOfPrefRec = sizeof(prefix);
944  int headerSize = sizeOfDescRec + sizeOfPrefRec;
945  char buf[] = "123456";
946  ossimDpt gridSize ((double) NUM_GRID_POINTS_U, 3.0);
947  ossimDpt cellSize (theImageSize.line/gridSize.u, theImageSize.samp/gridSize.v);
948 
949  // Because we are doing integer arithmetic, it will be necessary to
950  // consider the last grid cells as being of a slightly different size:
951  //theLastGridCellSize.line = theImageSize.line - 1.0 -
952  // (theGridSize.u-2.0)*theGridCellSize.u;
953  //theLastGridCellSize.samp = theImageSize.samp - 1.0 -
954  // (theGridSize.v-2.0)*theGridCellSize.v;
955 
956  // Open the image data file given the image directory name and seek to first
957  // SAR data record:
958  FILE* fptr = fopen(theCeosData->imageFile().chars(), "r");
959  if (!fptr)
960  {
961  CLOG << "ERROR: Could not open data file <" << theCeosData->imageFile()
962  << ">" << endl;
963  setErrorStatus();
964  return;
965  }
966  fseek(fptr, theCeosData->imopDescRec()->desc.length, SEEK_SET);
967 
968  // Declare some constants and variables used in loop:
969  int last_line = (int) theImageSize.line - 1;
970  int delta_line = (int) cellSize.u;
971  int line_number = 0;
972 
973  // Allocate memory for coarse grid:
974  theLatGrid.initialize(gridSize, ossimDpt(0,0), ossimDpt(1,1));
975  theLonGrid.initialize(gridSize, ossimDpt(0,0), ossimDpt(1,1));
976 
977  // Compute the number of SAR data bytes to skip to reach prefix of next
978  // record of interest:
979  strncpy(buf, theCeosData->imopDescRec()->l_dataset, 6);
980  int record_size = atoi(buf);
981  int test_line = (int) gridSize.u - 2;
982 
983  // Loop over each imaging line:
984  for (int u=0; u<(int)gridSize.u; u++)
985  {
986  if (traceDebug())
987  {
988  clog << "\t Processing grid line number " << u << endl;
989  }
990 
991  // Read the image line prefix info:
992  fread(&descRec, sizeOfDescRec, 1, fptr);
993  fread(&prefix, sizeOfPrefRec, 1, fptr);
994 
995  // Verify correct line number being read:
996  if ((prefix.line_num-1) != line_number)
997  {
998  CLOG << "\n\tERROR: Synchronization error reading image file. "
999  << "Expected line number " << line_number+1
1000  << " but read line number " << prefix.line_num << "." << endl;
1001  setErrorStatus();
1002  fclose(fptr);
1003  fptr = 0;
1004  return;
1005  }
1006 
1007  // Latch the imaging time for the first line collected:
1008  if (u == 0)
1009  {
1010  theFirstLineDay = prefix.acq_date.acq_day;
1011  theFirstLineTime = (double) prefix.acq_date.acq_msec/1000.0;
1012  }
1013 
1014  // Read the ground points for this line:
1015  theLatGrid.setNode(u, 0, (double) prefix.lat_first /1.0e6);
1016  theLatGrid.setNode(u, 1, (double) prefix.lat_mid /1.0e6);
1017  theLatGrid.setNode(u, 2, (double) prefix.lat_last /1.0e6);
1018  theLonGrid.setNode(u, 0, (double) prefix.long_first/1.0e6);
1019  theLonGrid.setNode(u, 1, (double) prefix.long_mid /1.0e6);
1020  theLonGrid.setNode(u, 2, (double) prefix.long_last /1.0e6);
1021 
1022  // Update the line number for next record, insuring we don't go passed
1023  // the last line:
1024  if (u == test_line)
1025  {
1026  delta_line = last_line - line_number;
1027  line_number = last_line;
1028  }
1029  else
1030  {
1031  line_number += delta_line;
1032  }
1033 
1034  //***
1035  // Advance to read the next prefix record of interest:
1036  //***
1037  fseek(fptr, (delta_line)*record_size-headerSize, SEEK_CUR);
1038  }
1039 
1040  // Compute time interval between each line, handle possible day rollover:
1041  double lastLineTime = (double) prefix.acq_date.acq_msec/1000.0;
1042  if ((lastLineTime-theFirstLineTime) > (SEC_PER_DAY/2.0))
1043  {
1044  lastLineTime -= SEC_PER_DAY;
1045  }
1046  else if ((theFirstLineTime-lastLineTime) > (SEC_PER_DAY/2.0))
1047  {
1048  lastLineTime += SEC_PER_DAY;
1049  }
1050  theTimePerLine = (lastLineTime - theFirstLineTime)/line_number;
1051 
1052  if (traceDebug())
1053  {
1054  clog << "\n\t line_number (last) = " << line_number
1055  << "\n\t last_line (in image) = " << last_line
1056  << "\n\t theFirstLineTime = " << theFirstLineTime
1057  << "\n\t lastLineTime = " << lastLineTime
1058  << "\n\t theTimePerLine = " << theTimePerLine
1059  << endl;
1060  }
1061 
1062  if (traceDebug()) CLOG << "returning..." << endl;
1063 }
RTTI_DEF1_INST(ossimGeneralRasterTileSource, "ossimGeneralRasterTileSource", ossimImageHandler) static ossimTrace traceDebug("ossimGeneralRasterTileSource for(ossim_uint32 i=0;i< aList.size();++i)
#define CLOG
Definition: ossimTrace.h:23
ossim_int32 long_first
const imop_desc_rec * imopDescRec() const
ossim_int32 line_num
void initialize(const ossimIpt &size, const ossimDpt &origin, const ossimDpt &spacing, double null_value=OSSIM_DEFAULT_NULL_PIX_DOUBLE)
ossim_int32 acq_msec
struct acq_date_rec acq_date
const ossimFilename & imageFile() const
ossim_int32 long_last
ossim_int32 lat_last
const char * chars() const
For backward compatibility.
Definition: ossimString.h:77
ossim_int32 lat_mid
ossim_int32 acq_day
ossimDblGrid theLonGrid
if(yy_init)
ossimDblGrid theLatGrid
ossim_int32 samp
Definition: ossimIpt.h:141
ossim_int32 lat_first
ossim_int32 line
Definition: ossimIpt.h:142
char l_dataset[6]
ossim_int32 long_mid
void setNode(const ossimIpt &p, const double &value)
Definition: ossimDblGrid.h:107
ossim_int32 length
Definition: ossimCeosData.h:29
ossimRefPtr< ossimCeosData > theCeosData
struct desc_rec desc

◆ establishOrpInterp()

void ossimRS1SarModel::establishOrpInterp ( )
protected

Definition at line 727 of file ossimRS1SarModel.cpp.

728 {
729  static const char MODULE[] = "ossimRS1SarModel::establishOrpInterp()";
730  if (traceDebug()) CLOG << "entering..." << endl;
731 
732  if (traceDebug())
733  CLOG << "DEBUG -- " << endl;
734 
735  static const int NUM_DATA_POINTS = 11;
736 
737  desc_rec descRec;
738  pdr_prefix_rec prefix;
739  int sizeOfDescRec = sizeof(descRec);
740  int sizeOfPrefRec = sizeof(prefix);
741  int headerSize = sizeOfDescRec + sizeOfPrefRec;
742  char buf[] = "123456";
743  ossimGpt localOrp (0.0, 0.0, theRefHeight);
744  std::vector<double> line_numbers_list;
745  std::vector<NEWMAT::ColumnVector> orpVectorList; // X, Y, Z
746 
747  if (traceDebug())
748  {
749  CLOG << "DEBUG:"
750  << "\nsizeOfDescRec: " << sizeOfDescRec
751  << "\nsizeOfPrefRec: " << sizeOfPrefRec << endl;
752  }
753 
754  // Open the image data file given the image directory name and seek to first
755  // SAR data record:
756  FILE* fptr = fopen(theCeosData->imageFile().chars(), "r");
757  if (!fptr)
758  {
759  CLOG << "ERROR: Could not open data file <" << theCeosData->imageFile()
760  << ">" << endl;
761  setErrorStatus();
762  return;
763  }
764  fseek(fptr, theCeosData->imopDescRec()->desc.length, SEEK_SET);
765 
766  // Declare some constants and variables used in loop:
767  int last_line = (int) theImageSize.line - 1;
768  int delta_line = (int)ceil(last_line/((double)NUM_DATA_POINTS-1.0));
769  int line_number = 0;
770 
771  // Compute the number of SAR data bytes to skip to reach prefix of next
772  // record of interest:
773  strncpy(buf, theCeosData->imopDescRec()->l_dataset, 6);
774  int record_size = atoi(buf);
775 
776  // Loop over each imaging line:
777  int index;
779  for (index=0; index<NUM_DATA_POINTS; index++)
780  {
781  if (traceDebug())
782  clog << "\t Processing ORP for line number " << line_number << endl;
783 
784  // Read the image line prefix info:
785  fread(&descRec, sizeOfDescRec, 1, fptr);
786  fread(&prefix, sizeOfPrefRec, 1, fptr);
787 
788  // Verify correct line number being read:
789  if ((prefix.line_num-1) != line_number)
790  {
791  CLOG << "\n\tERROR: Synchronization error reading image file. "
792  << "Expected line number " << line_number+1
793  << " but read line number " << prefix.line_num << "." << endl;
794  setErrorStatus();
795  fclose(fptr);
796  fptr = 0;
797  return;
798  }
799 
800  // Latch the imaging time for the first line collected:
801  if (index == 0)
802  {
804  theFirstLineTime = (double) prefix.acq_date.acq_msec/1000.0;
805  }
806 
807  // Read the local ORP for this line and convert to ECF:
809  {
810  localOrp.lat = (double) prefix.lat_first / 1.0e6;
811  localOrp.lon = (double) prefix.long_first / 1.0e6;
812  }
813  else
814  {
815  localOrp.lat = (double) prefix.lat_last / 1.0e6;
816  localOrp.lon = (double) prefix.long_last / 1.0e6;
817  }
818 
819  theLocalOrpInterp->addData(line_number, ossimEcefPoint(localOrp).toVector());
820 
821  // Update the line number for next record, insuring we don't go passed
822  // the last line:
823  line_number += delta_line;
824  if (line_number > last_line)
825  {
826  delta_line -= line_number - last_line; // adjust for fseek below
827  line_number = last_line;
828  }
829 
830  // Advance to read the next prefix record of interest:
831  fseek(fptr, (delta_line)*record_size-headerSize, SEEK_CUR);
832  }
833 
834  // Compute time interval between each line, handle possible day rollover:
835  double lastLineTime = (double) prefix.acq_date.acq_msec/1000.0;
836  if ((lastLineTime-theFirstLineTime) > (SEC_PER_DAY/2.0))
837  lastLineTime -= SEC_PER_DAY;
838  else if ((theFirstLineTime-lastLineTime) > (SEC_PER_DAY/2.0))
839  lastLineTime += SEC_PER_DAY;
840  theTimePerLine = (lastLineTime - theFirstLineTime)/line_number;
841 
842  if (traceDebug())
843  {
844  clog << "\n\t line_number (last) = " << line_number
845  << "\n\t last_line (in image) = " << last_line
846  << "\n\t theFirstLineTime = " << theFirstLineTime
847  << "\n\t lastLineTime = " << lastLineTime
848  << "\n\t theTimePerLine = " << theTimePerLine
849  << endl;
850  }
851 
852  if (traceDebug()) CLOG << "returning..." << endl;
853 }
ossimRefPtr< ossimLagrangeInterpolator > theLocalOrpInterp
#define CLOG
Definition: ossimTrace.h:23
void addData(const double &t, const NEWMAT::ColumnVector &data)
ossim_int32 long_first
const imop_desc_rec * imopDescRec() const
ossim_int32 line_num
ossim_int32 acq_msec
struct acq_date_rec acq_date
const ossimFilename & imageFile() const
DirectionFlag theDirectionFlag
ossim_int32 long_last
ossim_int32 lat_last
OSSIM_DLL void toVector(std::vector< ossimDpt > &result, const ossimString &stringOfPoints)
Will take a string list separated by spaces and convert to a vector of ossimDpts. ...
const char * chars() const
For backward compatibility.
Definition: ossimString.h:77
ossim_int32 acq_day
if(yy_init)
ossim_int32 lat_first
ossim_int32 line
Definition: ossimIpt.h:142
char l_dataset[6]
ossim_int32 length
Definition: ossimCeosData.h:29
ossimRefPtr< ossimCeosData > theCeosData
struct desc_rec desc

◆ establishVehicleSpace()

void ossimRS1SarModel::establishVehicleSpace ( )
protected

Definition at line 859 of file ossimRS1SarModel.cpp.

860 {
861  static const char MODULE[] = "ossimRS1SarModel::establishVehicleSpace()";
862  if (traceDebug()) CLOG << "entering..." << endl;
863 
864  // Obtain the imaging time when the vehicle is at the ARP:
865  double line = theImageSize.line/2.0;
866  double arpTime = theFirstLineTime + line*theTimePerLine;
867 
868  // Obtain the ephemeris at this time:
869  NEWMAT::ColumnVector arpPos(3);
870  theArpPosInterp->interpolate(arpTime, arpPos);
871  NEWMAT::ColumnVector arpVel(3);
872  theArpVelInterp->interpolate(arpTime, arpVel);
873 
874  // Convert ephemeris to ECF:
875  NEWMAT::Matrix xform;
876  eciToEcfXform(arpTime, xform);
877  ossimEcefPoint ecfArpPos (xform * arpPos);
878  ossimEcefVector ecfArpVel (xform * arpVel);
879 
880  // Need to correct the velocity vector by the earth rotational velocity:
881  ossimEcefVector earthVel(-ecfArpPos.y()*EARTH_ANGULAR_VELOCITY,
882  ecfArpPos.x()*EARTH_ANGULAR_VELOCITY,
883  0.0);
884  ecfArpVel = ecfArpVel - earthVel;
885 
886  // Establish LSR space for intrack-crosstrack-radial at vehicle:
887  ossimEcefVector intrackDir (ecfArpVel);
888  ossimEcefVector crtrackDir (ecfArpPos.data().cross(intrackDir.data()));
889  theVehicleSpace = ossimLsrSpace (ecfArpPos, intrackDir, crtrackDir, 0);
890 
891  if (traceDebug())
892  {
893  CLOG << "DEBUG -- "
894  << "\n\t theVehicleSpace: " << theVehicleSpace << endl;
895  }
896 
897  if (traceDebug()) CLOG << "returning..." << endl;
898 }
ossimRefPtr< ossimLagrangeInterpolator > theArpPosInterp
bool interpolate(const double &t, NEWMAT::ColumnVector &result) const
#define CLOG
Definition: ossimTrace.h:23
ossimRefPtr< ossimLagrangeInterpolator > theArpVelInterp
void eciToEcfXform(const double &julianDay, NEWMAT::Matrix &xform) const
ossimLsrSpace theVehicleSpace
ossim_int32 line
Definition: ossimIpt.h:142

◆ imagingRay()

void ossimRS1SarModel::imagingRay ( const ossimDpt image_point,
ossimEcefRay image_ray 
) const
virtual

Given an image point, returns a ray originating at some arbitrarily high point (in this model at the sensor position) and pointing towards the target.

Reimplemented from ossimSensorModel.

Definition at line 128 of file ossimRS1SarModel.cpp.

References ossimLagrangeInterpolator::interpolate(), ossimIpt::line, ossimDpt::line, ossimIpt::samp, ossimDpt::samp, SCN, SCW, theArpPosInterp, theArpVelInterp, theCosOrientation, theFirstLineTime, ossimSensorModel::theImageSize, theImagingMode, theLatGrid, theLineScale, theLocalOrpInterp, theLonGrid, theRefHeight, theSinOrientation, theSinSkew, theTimePerLine, ossimDpt::x, ossimEcefPoint::y(), and ossimDpt::y.

129 {
130  const char* MODULE = "ossimRS1SarModel::imagingRay()";
131 
132  // Apply offset, scale, skew, and rotation to image point:
133  ossimDpt offset (theImageSize.line/2.0, theImageSize.samp/2.0);
134  ossimDpt ip1 = image_point - offset;
135  ossimDpt ip2;
140 
141  // Offset point back to origin of image:
142  ip1 = ip2 + offset;
143 
144  // Given new line number, obtain the interpolated ORP:
145  ossimEcefPoint localORP;
146  if ((theImagingMode == SCN) || (theImagingMode == SCW))
147  {
148  ossimGpt gpt (theLatGrid(ip1.x, ip1.y), theLonGrid(ip1.x, ip1.y), theRefHeight);
149  localORP = ossimEcefPoint(gpt);
150  }
151  else
152  {
153  NEWMAT::ColumnVector orpPos(3);
154  theLocalOrpInterp->interpolate(ip1.line, orpPos);
155  localORP = ossimEcefPoint(orpPos[0], orpPos[1], orpPos[2]);
156  }
157 
158  // Establish imaging line time (zero-Doppler time):
159  double arpTime = theFirstLineTime + ip1.line*theTimePerLine;
160 
161  NEWMAT::ColumnVector arpEph(3);
162  theArpPosInterp->interpolate(arpTime, arpEph);
163  ossimEcefPoint ecfArpPos (arpEph[0], arpEph[1], arpEph[2]);
164 
165  theArpVelInterp->interpolate(arpTime, arpEph);
166  ossimEcefVector ecfArpVel (arpEph[0], arpEph[1], arpEph[2]);
167 
168  // Need to correct the velocity vector by the earth rotational velocity:
169  ossimEcefVector earthVel
170  (-ecfArpPos.y()*EARTH_ANGULAR_VELOCITY, ecfArpPos.x()*EARTH_ANGULAR_VELOCITY, 0.0);
171  ecfArpVel = ecfArpVel - earthVel;
172 
173  // Compute a vehicle space with Z near intrack, X normal to Z and range
174  // vector to ORP (slant range normal), and Y in range direction.
175  // Note the application of the position adjustable parameter to the space's
176  // origin (after the range vector was established):
177  ossimEcefVector rangeVector = localORP - ecfArpPos;
178  ossimEcefVector rangeNormal = rangeVector.cross(ecfArpVel);
179  // ossimEcefVector zDirection = rangeNormal.cross(rangeVector);
180  ossimLsrSpace localVehicleSpace (ossimEcefPoint(ecfArpPos + thePosCorrection), // origin
181  rangeNormal, // X-direction
182  rangeVector, 0); // Y-direction (Z not specified
183  double local_orp_range = rangeVector.length();
184 
185  // Compute slant range distance to pixel in question:
186  double slant_range = local_orp_range;
187  switch (theImagingMode)
188  {
189  case SLC:
191  slant_range += thePixelSpacing.samp*ip1.samp;
192  else
193  slant_range += (theImageSize.samp-1.0-ip1.samp) * thePixelSpacing.samp;
194  break;
195 
196  case SGC:
197  case SGF:
198  case SGX:
199  case ERS:
200  {
201  // Compute the slant range as a polynomial expansion given ground range
202  double ground_range;
204  ground_range = ip1.samp * thePixelSpacing.samp;
205  else
206  ground_range = (theImageSize.samp - 1.0 - ip1.samp) *
208  // double delta_g_i = 1.0;
209  // for (int 0=1; i<6; i++)
210  double delta_g_i = ground_range;
211  for (int i=1; i<6; i++) // NOTE: not using offset (i=0) term
212  {
213  slant_range += theSrGrCoeff[i] * delta_g_i;
214  delta_g_i *= ground_range;
215  }
216  }
217  break;
218 
219  case SCN:
220  case SCW:
221  slant_range = local_orp_range;
222  break;
223 
224  default:
225  CLOG << "ERROR: Invalid imaging mode encountered." << endl;
226  setErrorStatus();
227  }
228 }
ossimRefPtr< ossimLagrangeInterpolator > theArpPosInterp
ossimRefPtr< ossimLagrangeInterpolator > theLocalOrpInterp
bool interpolate(const double &t, NEWMAT::ColumnVector &result) const
RTTI_DEF1_INST(ossimGeneralRasterTileSource, "ossimGeneralRasterTileSource", ossimImageHandler) static ossimTrace traceDebug("ossimGeneralRasterTileSource for(ossim_uint32 i=0;i< aList.size();++i)
#define CLOG
Definition: ossimTrace.h:23
ossimEcefVector cross(const ossimEcefVector &) const
double samp
Definition: ossimDpt.h:164
double y
Definition: ossimDpt.h:165
DirectionFlag theDirectionFlag
double line
Definition: ossimDpt.h:165
ossimRefPtr< ossimLagrangeInterpolator > theArpVelInterp
ossimEcefVector thePosCorrection
ImagingMode theImagingMode
double length() const
ossimDblGrid theLonGrid
if(yy_init)
ossimDblGrid theLatGrid
ossim_int32 samp
Definition: ossimIpt.h:141
double x
Definition: ossimDpt.h:164
ossim_int32 line
Definition: ossimIpt.h:142

◆ initAdjParms()

void ossimRS1SarModel::initAdjParms ( )
protected

Definition at line 523 of file ossimRS1SarModel.cpp.

524 {
525  // Adjustable model not yet implemented
526 #if 0
527 
528  static const char* MODULE = "ossimRS1SarModel::initAdjParms()";
529  if (traceDebug()) CLOG << "entering..." << endl;
530 
531  theInTrackOffset = (init_adj_parm[INTRACK_OFFSET]+adj_parm[INTRACK_OFFSET])
532  * adj_sigma[INTRACK_OFFSET];
533 
534  theCrTrackOffset = (init_adj_parm[CRTRACK_OFFSET]+adj_parm[CRTRACK_OFFSET])
535  * adj_sigma[CRTRACK_OFFSET];
536 
537  theRadialOffset = (init_adj_parm[RADIAL_OFFSET]+adj_parm[RADIAL_OFFSET])
538  * adj_sigma[RADIAL_OFFSET];
539 
540  theLineScale = (init_adj_parm[LINE_SCALE]+adj_parm[LINE_SCALE])
541  * adj_sigma[LINE_SCALE];
542 
543  theSkew = (init_adj_parm[SKEW]+adj_parm[SKEW])
544  * adj_sigma[SKEW];
545 
546  theOrientation = (init_adj_parm[ORIENTATION]+adj_parm[ORIENTATION]);
547 
548  // Initialize base-class initial adjustable parameter array:
549  init_adj_parm[INTRACK_OFFSET] = theInTrackOffset/adj_sigma[INTRACK_OFFSET];
550  init_adj_parm[CRTRACK_OFFSET] = theCrTrackOffset/adj_sigma[CRTRACK_OFFSET];
551  init_adj_parm[RADIAL_OFFSET] = theRadialOffset/adj_sigma[RADIAL_OFFSET];
552  init_adj_parm[LINE_SCALE] = theLineScale/adj_sigma[LINE_SCALE];
553  init_adj_parm[SKEW] = theSkew/adj_sigma[SKEW];
554  init_adj_parm[ORIENTATION] = theOrientation/adj_sigma[ORIENTATION];
555 
556  // Initialize sensor adjustable parameter description strings:
557  strncpy (adj_desc[INTRACK_OFFSET], "intrack_offset", MAX_DESC_CHARS);
558  strncpy (adj_desc[CRTRACK_OFFSET], "crtrack_offset", MAX_DESC_CHARS);
559  strncpy (adj_desc[RADIAL_OFFSET], "radial_offset", MAX_DESC_CHARS);
560 // strncpy (adj_desc[SAMP_SCALE], "samp_scale", MAX_DESC_CHARS);
561  strncpy (adj_desc[LINE_SCALE], "line_scale", MAX_DESC_CHARS);
562  strncpy (adj_desc[SKEW], "image_skew", MAX_DESC_CHARS);
563  strncpy (adj_desc[ORIENTATION], "image_orientation",MAX_DESC_CHARS);
564 
565  // Initialize the adj_parms (parameter corrections) to 0:
566  for (int i=0; i<num_adj_parm; i++)
567  adj_parm[i] = 0.0;
568 
569  if (traceDebug()) CLOG << "returning..." << endl;
570 #endif
571 }
#define CLOG
Definition: ossimTrace.h:23

◆ initFromCeos()

void ossimRS1SarModel::initFromCeos ( const ossimFilename dataDir)
protected

Definition at line 340 of file ossimRS1SarModel.cpp.

341 {
342  static const char MODULE[] = "ossimRS1SarModel::initFromCeos()";
343  if (traceDebug()) CLOG << "entering..." << endl;
344 
345  // Instantiate a CeosData object:
346  theCeosData = new ossimCeosData(fname);
347 
349  const dataset_sum_rec* dsr = theCeosData->dataSetSumRec();
350  const proc_parm_rec* ppr = theCeosData->procParmRec();
351  char buf[1024];
352 
353  // Set imaging mode:
354  strncpy(buf, &(theCeosData->volDescRec()->logvol_id[11]), 3);
355  buf[3] = '\0';
356  setImagingMode(buf);
357 
358  // Determine whether ascending or descending path acquisition. This flag
359  // dictates whether the first or last pixel of a line is of shorter range:
360  if (theImagingMode == ERS)
361  {
363  }
364  else
365  {
366  if (dsr->asc_des[0] == 'A')
368  else if (dsr->asc_des[0] == 'D')
370  else
371  {
372  CLOG << "ERROR: Direction Flag: " << dsr->asc_des << " not supported"
373  << endl;
375  setErrorStatus();
376  if (traceDebug()) CLOG << "returning with error..." << endl;
377  return;
378  }
379  }
380 
381  // Image (Product) ID:
382  buf[8] = '\0';
383  strncpy(buf, theCeosData->volDescRec()->product_id, 8);
384  theImageID = buf;
385 
386  // pixel spacing in range:
387  buf[16] = '\0';
388  strncpy(buf, dsr->pix_spacing, 16);
389  thePixelSpacing.samp = atof(buf);
390 
391  // pixel spacing in azimuth:
392  strncpy(buf, dsr->line_spacing, 16);
393  buf[16] = '\0';
394  thePixelSpacing.line = atof(buf);
395 
396  // The ground reference point (ORP) latitude:
397  ossimGpt grp;
398  strncpy(buf, dsr->pro_lat, 16);
399  buf[16] = '\0';
400  grp.lat = atof(buf);
401 
402  // The ground reference point (ORP) longitude:
403  strncpy(buf, dsr->pro_long, 16);
404  buf[16] = '\0';
405  grp.lon = atof(buf);
406 
407  // The ground reference point (ORP) elevation:
408  strncpy(buf, dsr->terrain_h, 16);
409  buf[16] = '\0';
410  grp.hgt = atof(buf);
411  theORP = ossimEcefPoint(grp);
412  theRefHeight = grp.hgt;
413 
414  // Illumination elevation:
415  strncpy(buf, dsr->incident_ang, 8);
416  buf[8] = '\0';
417  double incidence = atof(buf);
418  theIllumElevation = 90.0 - incidence;
419 
420  // Illumination azimuth -- need to determine whether sensor is in normal
421  // right-looking mode or "antarctic" (left-looking) mode:
422  strncpy(buf, dsr->plat_head, 8);
423  theIllumAzimuth = atof(buf);
424  char sensor_orientation[] = "123456789";
425  strncpy(sensor_orientation, ppr->sens_orient, 9);
426  if (strcmp(sensor_orientation, "ANTARCTIC") == 0)
427  {
428  theIllumAzimuth -= 90.0;
429  if (theIllumAzimuth < 0.0) theIllumAzimuth += 360.0;
430  }
431  else
432  {
433  theIllumAzimuth += 90.0;
434  if (theIllumAzimuth >= 360.0) theIllumAzimuth -= 360.0;
435  }
436 
437  // Determine the number of lines per image and pixels per line. NOTE: if
438  // image is scan mode, the number of lines must be computed indirectly.
439  if ((theImagingMode == SCN) || (theImagingMode == SCW))
440  {
441  FILE* fptr = fopen(theCeosData->imageFile().chars(), "r");
442  if (!fptr)
443  {
444  CLOG << " ERROR:\n\tCannot open CEOS image file: "
445  << theCeosData->imageFile() << endl;
446  setErrorStatus();
447  return;
448  }
449  fseek(fptr, 0, SEEK_END);
450  long byte_count = ftell(fptr);
451  buf[6] = '\0';
452  strncpy(buf, theCeosData->imopDescRec()->l_dataset, 6);
453  int lengthOfRec = atoi(buf);
454  theImageSize.line = (byte_count - sizeof(*theCeosData->imopDescRec()))
455  /lengthOfRec;
456  fclose(fptr);
457  }
458  else
459  {
460  strncpy(buf, theCeosData->imopDescRec()->n_dataset, 6);
461  buf[6] = '\0';
462  theImageSize.line = atoi(buf);
463  }
464  strncpy(buf, theCeosData->imopDescRec()->nleft, 4);
465  buf[4] = '\0';
466  int left_pixels = atoi(buf);
467  strncpy(buf, theCeosData->imopDescRec()->ngrp, 8);
468  buf[8] = '\0';
469  int data_pixels = atoi(buf);
470  strncpy(buf, theCeosData->imopDescRec()->nright, 4);
471  buf[4] = '\0';
472  int right_pixels = atoi(buf);
473  theImageSize.samp = left_pixels + data_pixels + right_pixels;
474 
475  // If ground range product, need to read the ground-to-slant range
476  // conversion coefficients from the proc_parm_rec. NOTE: only single-look
477  // products handled properly. ScanSAR requires reading multiple coefficient
478  // sets. See MDA Detailed Processing Parameter Record Description sec.3.84.
479  if ((theImagingMode==SGC) ||
480  (theImagingMode==SGF) ||
481  (theImagingMode==SGX) ||
482  (theImagingMode==ERS))
483  {
484  buf[16] = '\0';
485  for (int i=0; i<6; i++)
486  {
487  strncpy(buf, ppr->srgr_coefset[0].srgr_coef[i], 16);
488  theSrGrCoeff[i] = atof(buf);
489  }
490  }
491  else
492  {
493  theSrGrCoeff[0] = 0.0;
494  theSrGrCoeff[1] = 1.0; // note 1.0 here (should never be accessed)
495  theSrGrCoeff[2] = 0.0;
496  theSrGrCoeff[3] = 0.0;
497  theSrGrCoeff[4] = 0.0;
498  theSrGrCoeff[5] = 0.0;
499  }
500 
501  if (traceDebug())
502  {
503  CLOG << "DEBUG -- "
504  << "\n\t theDirectionFlag = " << theDirectionFlag
505  << "\n\t thePixelSpacing = " << thePixelSpacing
506  << "\n\t theORP = " << theORP
507  << "\n\t theRefHeight = " << theRefHeight
508  << "\n\t theImageSize = " << theImageSize
509  << "\n\t sensor_orientation = " << sensor_orientation
510  << "\n\t theIllumElevation = " << theIllumElevation
511  << "\n\t theIllumAzimuth = " << theIllumAzimuth
512  << endl;
513  }
514 
515  if (traceDebug()) CLOG << "returning..." << endl;
516 }
#define CLOG
Definition: ossimTrace.h:23
static const ossimErrorCode OSSIM_OK
ossimString theImageID
double samp
Definition: ossimDpt.h:164
ossimEcefPoint theORP
const imop_desc_rec * imopDescRec() const
char incident_ang[8]
char srgr_coef[6][16]
ossim_float64 hgt
Height in meters above the ellipsiod.
Definition: ossimGpt.h:274
char sens_orient[9]
struct srgr_coefset_rec srgr_coefset[20]
const ossimFilename & imageFile() const
DirectionFlag theDirectionFlag
char n_dataset[6]
char terrain_h[16]
double line
Definition: ossimDpt.h:165
bool errorStatus() const
ossim_float64 lon
Definition: ossimGpt.h:266
const char * chars() const
For backward compatibility.
Definition: ossimString.h:77
char pix_spacing[16]
ImagingMode theImagingMode
char product_id[8]
Definition: ossimCeosData.h:60
char line_spacing[16]
ossim_int32 samp
Definition: ossimIpt.h:141
void setImagingMode(char *modeStr)
const proc_parm_rec * procParmRec() const
ossim_int32 line
Definition: ossimIpt.h:142
char l_dataset[6]
ossim_float64 lat
Definition: ossimGpt.h:265
const dataset_sum_rec * dataSetSumRec() const
char logvol_id[16]
Definition: ossimCeosData.h:43
ossimRefPtr< ossimCeosData > theCeosData
const vol_desc_rec * volDescRec() const

◆ interpolatedScanORP()

void ossimRS1SarModel::interpolatedScanORP ( const ossimDpt orp,
ossimEcefPoint orp_ecf 
) const
protected

Definition at line 904 of file ossimRS1SarModel.cpp.

905 {
906  static const char MODULE[] = "ossimRS1SarModel::interpolatedScanORP(gDblPoint)";
907  if (traceDebug()) CLOG << "entering..." << endl;
908 
909  ossimGpt gpt;
910  gpt.lat = theLatGrid(orp);
911  gpt.lon = theLonGrid(orp);
912 
913  // Convert to ECF:
914  orp_ecf = ossimEcefPoint(gpt);
915 
916  if (traceDebug()) CLOG << "returning..." << endl;
917 }
#define CLOG
Definition: ossimTrace.h:23
ossim_float64 lon
Definition: ossimGpt.h:266
ossimDblGrid theLonGrid
ossimDblGrid theLatGrid
ossim_float64 lat
Definition: ossimGpt.h:265

◆ lineSampleHeightToWorld()

void ossimRS1SarModel::lineSampleHeightToWorld ( const ossimDpt imagePt,
const double &  heightAboveEllipsoid,
ossimGpt worldPt 
) const
virtual

Establishes geographic 3D point given image line, sample and ellipsoid height.

Implements ossimSensorModel.

Definition at line 235 of file ossimRS1SarModel.cpp.

238 {
239  static const char MODULE[] = "ossimRS1SarModel::lineSampleHeightToWorld()";
240  if (traceDebug()) CLOG << "entering..." << endl;
241 
242  // static const int MAX_NUM_ITERS = 50;
243  // static const double MAX_ELEV_DIFF = 0.001;
244 
245  ossimEcefRay imaging_ray;
246  imagingRay(image_point, imaging_ray);
247  worldPt = imaging_ray.intersectAboveEarthEllipsoid(height_ellip);
248 
249  if (traceDebug()) CLOG << "returning..." << endl;
250 }
#define CLOG
Definition: ossimTrace.h:23
ossimEcefPoint intersectAboveEarthEllipsoid(const double &heightAboveEllipsoid, const ossimDatum *aDatum=ossimDatumFactory::instance() ->wgs84()) const
virtual void imagingRay(const ossimDpt &image_point, ossimEcefRay &image_ray) const
Given an image point, returns a ray originating at some arbitrarily high point (in this model at the ...

◆ loadState()

bool ossimRS1SarModel::loadState ( const ossimKeywordlist kwl,
const char *  prefix = NULL 
)
virtual

Fulfills ossimObject base-class pure virtuals.

Reads modeling info from KWL. Returns true if successful.

Reimplemented from ossimSensorModel.

Definition at line 107 of file ossimRS1SarModel.cpp.

References ossimErrorStatusInterface::setErrorStatus().

108 {
109  // NOT YET IMPLEMENTED
110  setErrorStatus();
111  return false;
112 }

◆ saveState()

bool ossimRS1SarModel::saveState ( ossimKeywordlist kwl,
const char *  prefix = NULL 
) const
virtual

Fulfills ossimObject base-class pure virtuals.

Saves modeling info to KWL. Returns true if successful.

Reimplemented from ossimSensorModel.

Definition at line 117 of file ossimRS1SarModel.cpp.

References ossimErrorStatusInterface::setErrorStatus().

118 {
119  // NOT YET IMPLEMENTED
120  setErrorStatus();
121  return false;
122 }

◆ setImagingMode()

void ossimRS1SarModel::setImagingMode ( char *  modeStr)
protected

Definition at line 256 of file ossimRS1SarModel.cpp.

257 {
258  static const char MODULE[] = "ossimRS1SarModel::setImagingMode(modeStr)";
259  if (traceDebug()) CLOG << "entering..." << endl;
260 
261  bool illegal_mode = false;
262 
263  if (strcmp(modeStr, "SCN") == 0)
264  {
266  }
267  else if (strcmp(modeStr, "SCW") == 0)
268  {
270  }
271  else if (strcmp(modeStr, "SGC") == 0)
272  {
274  }
275  else if (strcmp(modeStr, "SGF") == 0)
276  {
278  }
279  else if (strcmp(modeStr, "SGX") == 0)
280  {
282  }
283  else if (strcmp(modeStr, "SLC") == 0)
284  {
286  }
287  else if (strcmp(modeStr, "SPG") == 0)
288  {
290  illegal_mode = true;
291  }
292  else if (strcmp(modeStr, "SSG") == 0)
293  {
295  illegal_mode = true;
296  }
297  else if (strcmp(modeStr, "RAW") == 0)
298  {
300  illegal_mode = true;
301  }
302  else if (strcmp(modeStr, "ERS") == 0)
303  {
305  }
306  else
307  {
309  illegal_mode = true;
310  }
311 
312  // Test for ERS product:
314  {
315  char buf[] = "xxx";
316  strncpy(buf, &(theCeosData->textRec()->product_type[8]), 3);
317  if (strcmp(buf, "ERS") == 0)
318  {
320  illegal_mode = false;
321  }
322  }
323 
324  // Filter the imaging modes that are not handled:
325  if (illegal_mode)
326  {
327  CLOG << "\n\t ERROR: The imaging mode <"
328  << IMAGING_MODE_ID[(int) theImagingMode]
329  << "> is currently not supported. \n" << endl;
331  }
332 
333  if (traceDebug()) CLOG << "returning..." << endl;
334 }
#define CLOG
Definition: ossimTrace.h:23
bool valid() const
Definition: ossimRefPtr.h:75
const text_rec * textRec() const
ImagingMode theImagingMode
char product_type[40]
Definition: ossimCeosData.h:95
ossimRefPtr< ossimCeosData > theCeosData

◆ useForward()

virtual bool ossimRS1SarModel::useForward ( ) const
inlinevirtual

useForward() return true when it's better (more accurate / fast) to use forward (from ground to image) than inverse(from image to ground)

Implements ossimOptimizableProjection.

Definition at line 84 of file ossimRS1SarModel.h.

84 { return false; }

Member Data Documentation

◆ theArpPosInterp

ossimRefPtr<ossimLagrangeInterpolator> ossimRS1SarModel::theArpPosInterp
protected

Definition at line 102 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theArpVelInterp

ossimRefPtr<ossimLagrangeInterpolator> ossimRS1SarModel::theArpVelInterp
protected

Definition at line 103 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theCeosData

ossimRefPtr<ossimCeosData> ossimRS1SarModel::theCeosData
protected

Definition at line 101 of file ossimRS1SarModel.h.

◆ theCosOrientation

double ossimRS1SarModel::theCosOrientation
protected

Definition at line 113 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theCrTrackOffset

double ossimRS1SarModel::theCrTrackOffset
protected

Definition at line 133 of file ossimRS1SarModel.h.

◆ theDirectionFlag

DirectionFlag ossimRS1SarModel::theDirectionFlag
protected

Definition at line 120 of file ossimRS1SarModel.h.

◆ theEphFirstSampTime

double ossimRS1SarModel::theEphFirstSampTime
protected

Definition at line 111 of file ossimRS1SarModel.h.

◆ theFirstLineDay

int ossimRS1SarModel::theFirstLineDay
protected

Definition at line 117 of file ossimRS1SarModel.h.

◆ theFirstLineTime

double ossimRS1SarModel::theFirstLineTime
protected

Definition at line 118 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theGHA

double ossimRS1SarModel::theGHA
protected

Definition at line 110 of file ossimRS1SarModel.h.

◆ theIllumAzimuth

double ossimRS1SarModel::theIllumAzimuth
protected

Definition at line 106 of file ossimRS1SarModel.h.

◆ theIllumElevation

double ossimRS1SarModel::theIllumElevation
protected

Definition at line 107 of file ossimRS1SarModel.h.

◆ theImagingMode

ImagingMode ossimRS1SarModel::theImagingMode
protected

Definition at line 105 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theInTrackOffset

double ossimRS1SarModel::theInTrackOffset
protected

Definition at line 132 of file ossimRS1SarModel.h.

◆ theLatGrid

ossimDblGrid ossimRS1SarModel::theLatGrid
protected

Definition at line 126 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theLineScale

double ossimRS1SarModel::theLineScale
protected

Definition at line 135 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theLocalOrpInterp

ossimRefPtr<ossimLagrangeInterpolator> ossimRS1SarModel::theLocalOrpInterp
protected

Definition at line 104 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theLonGrid

ossimDblGrid ossimRS1SarModel::theLonGrid
protected

Definition at line 127 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theOrientation

double ossimRS1SarModel::theOrientation
protected

Definition at line 137 of file ossimRS1SarModel.h.

◆ theORP

ossimEcefPoint ossimRS1SarModel::theORP
protected

Definition at line 108 of file ossimRS1SarModel.h.

◆ thePixelSpacing

ossimDpt ossimRS1SarModel::thePixelSpacing
protected

Definition at line 122 of file ossimRS1SarModel.h.

◆ thePosCorrection

ossimEcefVector ossimRS1SarModel::thePosCorrection
protected

Definition at line 116 of file ossimRS1SarModel.h.

◆ theRadialOffset

double ossimRS1SarModel::theRadialOffset
protected

Definition at line 134 of file ossimRS1SarModel.h.

◆ theRefHeight

double ossimRS1SarModel::theRefHeight
protected

Definition at line 109 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theSinOrientation

double ossimRS1SarModel::theSinOrientation
protected

Definition at line 112 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theSinSkew

double ossimRS1SarModel::theSinSkew
protected

Definition at line 114 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theSkew

double ossimRS1SarModel::theSkew
protected

Definition at line 136 of file ossimRS1SarModel.h.

◆ theSrGrCoeff

double ossimRS1SarModel::theSrGrCoeff[6]
protected

Definition at line 121 of file ossimRS1SarModel.h.

◆ theTimePerLine

double ossimRS1SarModel::theTimePerLine
protected

Definition at line 119 of file ossimRS1SarModel.h.

Referenced by imagingRay().

◆ theVehicleSpace

ossimLsrSpace ossimRS1SarModel::theVehicleSpace
protected

Definition at line 115 of file ossimRS1SarModel.h.


The documentation for this class was generated from the following files: