Showing preview only (498K chars total). Download the full file or copy to clipboard to get everything.
Repository: UBNanosatLab/openstartracker
Branch: master
Commit: a72f51903d93
Files: 30
Total size: 481.2 KB
Directory structure:
gitextract_orpqwhda/
├── .gitignore
├── Dockerfile
├── LICENSE
├── README.md
├── beast/
│ ├── Makefile
│ ├── beast.h
│ ├── beast.i
│ ├── config.h
│ ├── constellations.h
│ ├── go
│ ├── kdhash.h
│ └── stars.h
├── build_production.sh
├── doc/
│ ├── gen_interleave.py
│ ├── ost_comm_test.c
│ └── viz_q.m
├── setup.sh
├── starsToStruc.py
├── startracker.py
└── tests/
├── Makefile
├── calibrate.py
├── science_cam_may8_0.05sec_gain40/
│ ├── calibration.txt
│ ├── calibration_data/
│ │ └── .gitignore
│ ├── input.csv
│ ├── result.csv
│ └── result_real.csv
├── score.py
├── simulator.py
├── test.c
└── unit_test.sh
================================================
FILE CONTENTS
================================================
================================================
FILE: .gitignore
================================================
# ignore files generated by beast
beast/__pycache__
beast/_beast.so
beast/beast.py
beast/beast_wrap.cxx
beast/beast_wrap.o
# ignore test executables
tests/gmon.out
tests/test
================================================
FILE: Dockerfile
================================================
FROM ubuntu:20.04
# deal with timezones (change to what suits your use case)
ENV TZ=America/New_York
ENV DEBIAN_FRONTEND=noninteractive
WORKDIR home
# need all of this to work (was missing some packages)
RUN apt-get update \
&& apt-get -y install software-properties-common \
&& add-apt-repository ppa:deadsnakes/ppa \
&& apt-get install -y python3-scipy libopencv-dev python3-opencv \
swig python3-systemd git astrometry.net \
python3-astropy python3-pkgconfig \
python3-dev libpython3.7-dev libpython3.8-dev \
build-essential python3.6 libpython3.6-dev \
python3-pandas \
graphviz \
bc \
netcat \
tzdata \
&& rm -rf /var/lib/apt/lists/*
ADD http://data.astrometry.net/4100/index-4112.fits /usr/share/astrometry/
ADD http://data.astrometry.net/4100/index-4113.fits /usr/share/astrometry/
ADD http://data.astrometry.net/4100/index-4114.fits /usr/share/astrometry/
ADD http://data.astrometry.net/4100/index-4115.fits /usr/share/astrometry/
ADD http://data.astrometry.net/4100/index-4116.fits /usr/share/astrometry/
ADD http://data.astrometry.net/4100/index-4117.fits /usr/share/astrometry/
ADD http://data.astrometry.net/4100/index-4118.fits /usr/share/astrometry/
ADD http://data.astrometry.net/4100/index-4119.fits /usr/share/astrometry/
================================================
FILE: LICENSE
================================================
MIT License
Copyright (c) 2018 UB Nanosatellite Laboratory
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
================================================
FILE: README.md
================================================
# openstartracker
A fast, robust, open source startracker based on a new class of baysian startracker algorithms
Features:
* Fast lost in space identification
* Image to image matching
* Collect and store size, shape and color information of unknown objects
* Tracks unknown objects between images
* Programable python frontend / reusable C++ backend (BEAST-2) with no external dependencies
* Uses astrometry.net for calibration (check if your camera is good enough by uploading your star images to nova.astrometry.net)
* Supports python 2 and 3 (see bottom)
### Basic setup:
##### From a fresh ubuntu linux install
```
sudo apt-get install python3-scipy libopencv-dev python3-opencv swig python3-systemd
```
Additional packages needed for calibration and unit testing:
~~~~
sudo apt-get install git astrometry.net python3-astropy
cd /usr/share/astrometry
Download fits files corresponding to your camera fov size (see astrometry.net for details
sudo wget http://data.astrometry.net/4100/index-4112.fits
sudo wget http://data.astrometry.net/4100/index-4113.fits
sudo wget http://data.astrometry.net/4100/index-4114.fits
sudo wget http://data.astrometry.net/4100/index-4115.fits
sudo wget http://data.astrometry.net/4100/index-4116.fits
sudo wget http://data.astrometry.net/4100/index-4117.fits
sudo wget http://data.astrometry.net/4100/index-4118.fits
sudo wget http://data.astrometry.net/4100/index-4119.fits
git clone https://github.com/UBNanosatLab/openstartracker.git
cd openstartracker/tests
./unit_test.sh -crei science_cam_may8_0.05sec_gain40
~~~~
#### Using Docker
The included Dockerfile allows the build and test environment to be configured in a reproducible way with all the dependencies.
According to their website,
> Docker is an open platform for developing, shipping, and running applications. Docker enables you to separate your applications from your infrastructure so you can deliver software quickly.
In practice, it's a nice way to ensure you always have the same dependencies installed, independent of the rest of your system.
**Note:** the Docker environment here is best used for development purposed. When running openstartracker on a flight computer, it is most
likely better to run the program directly, without the Docker container. Docker is used here just to create a standard, reproducible dev and testing environment.
To use the Docker environment to run openstartracker,
0. Install [Docker](https://docs.docker.com/get-docker/).
1. Run `source setup.sh`. This will execute a `docker build ...` command to create the Docker environment from the Dockerfile, copy
in all the code config files from this repo,
and create a command alias called `dstart` that can be run to start the Docker environment and access the pre-built Docker environment.
- This may take awhile to run the first time as the Docker image is built, but will run much more quickly in subsequent builds
2. Run `dstart` to start and enter the Docker environment.
3. Proceed with the following instructions.
**Important note:** Any code and file changes should be made **outside** the Docker environment -- consider it a 'run only' space.
Any time you make a change to the code in this repo, you'll want to re-run the `source setup.sh` command so that your changes are
included in the Docker build.
### Run on example imagery:
You can use the included `science_cam_may8_0.05sec_gain40` images to test out the calibration process:
```
# if using docker, run `source setup.sh` and then `dstart` to enter the Docker shell
cd tests/
./unit_test.sh -crei science_cam_may8_0.05sec_gain40/
```
This command will **c**alibrate your image sensor, **r** regenerate the test data, run an **E**SA test, and finally run the **i**mage test where images are fed to the calibrated star tracker program to produce an attitude fix.
The usage message for `unit_test.py` is here:
```
./unit_test.sh -h
Usage: ./unit_test.sh [options] testdir [cmd]
-c Calibrate based on images in testdir/samples/
-r Regenerate ESA test
-e Run ESA test
-i Run image test
```
### To calibrate a new camera:
1. Create directories for you camera's imagery:
~~~~
cd openstartracker/tests/
mkdir yourcamera
mkdir yourcamera/samples
mkdir yourcamera/calibration_data
~~~~
2. Add 3-10 star images of different parts of the sky taken with your camera to `tests/yourcamera/samples`
3. Edit `APERTURE` and `EXPOSURE_TIME` in `calibrate.py` (you want to take images with the lowest exposure time that consistently solves)
4. (if using docker, run `dstart` to enter the Docker environment)
5. Run
```
cd tests/
./unit_test.sh -crei yourcamera
```
to calibrate and test
The ESA test should have a score of >70. If its worse than this, play around with exposure time (50ms is a good starting point)
##### Reference frames used:
For RA,DEC,Ori, openstartracker uses the same convention as astrometry.net, where RA and DEC are in the same frame as the star positions specified in the hipparcos catalogue (updated to the current year). Orientation is degrees east of north (ie orientation 0 means that up and down aligns with north-south)
NOTE: RA, DEC & Ori are provided for debugging purposes only. For spacecraft attitude determination, the star reference vectors should be used, either directly, or converted to a quaternion via one of the many algorithms that have been developed for this purpose (see: https://en.wikipedia.org/wiki/Wahba%27s_problem)
================================================
FILE: beast/Makefile
================================================
CC = g++
PYTHONHEADERS=/usr/include/python3.10
#PYTHONHEADERS=/usr/include/python2.7
all: $(OBJ)
swig -python -c++ beast.i
$(CC) -g -std=c++11 -Ofast -fPIC -c beast_wrap.cxx -o beast_wrap.o -lstdc++ -I$(PYTHONHEADERS)
$(CC) -g -shared -fPIC beast_wrap.o -o _beast.so
clean:
rm beast.so beast.o beast.py beast.pyc beast_wrap.cxx beast_wrap.o
================================================
FILE: beast/beast.h
================================================
#ifndef BEAST_H
#define BEAST_H
#include "constellations.h"
#include <float.h>
struct match_result {
//TODO: private:
constellation_pair match;
//eci to body (body=R*eci)
float R11,R12,R13;
float R21,R22,R23;
float R31,R32,R33;
private:
star_fov *img_mask;
int *map; /* Usage: map[imgstar]=dbstar */
size_t map_size;
constellation* db_const;
constellation_db *db,*img;
public:
/**
* @brief TODO
* @param db_
* @param img_
* @param img_mask_
*/
match_result(constellation_db *db_, constellation_db *img_, star_fov *img_mask_) {
DBG_MATCH_RESULT_COUNT++;
DBG_PRINT("DBG_MATCH_RESULT_COUNT++ %d\n",DBG_MATCH_RESULT_COUNT);
db=db_;
img=img_;
img_mask=img_mask_;
map_size=img->stars->size();
map=(int *)malloc(sizeof(map[0])*map_size);
match.totalscore=-FLT_MAX;
}
~match_result() {
DBG_MATCH_RESULT_COUNT--;
DBG_PRINT("DBG_MATCH_RESULT_COUNT-- %d\n",DBG_MATCH_RESULT_COUNT);
free(map);
}
size_t size() {return map_size;};
/**
* @brief TODO
* @param db_const_
* @param img_const_
*/
void init(constellation &db_const_, constellation &img_const_) {
db_const=&db_const_;
match.img_s1=img_const_.s1;
match.img_s2=img_const_.s2;
match.db_s1=db_const_.s1;
match.db_s2=db_const_.s2;
}
/**
* @brief TODO
* @param c
*/
void copy_over(match_result *c) {
assert(c->db==db);
assert(c->img==img);
assert(c->img_mask==img_mask);
c->match=match;
c->db_const=db_const;
c->R11=R11,c->R12=R12,c->R13=R13;
c->R21=R21,c->R22=R22,c->R23=R23;
c->R31=R31,c->R32=R32,c->R33=R33;
memcpy(c->map, map, sizeof(map[0])*map_size);
}
/**
* @brief TODO
* @param m
* @return
*/
int related(constellation_pair &m) {
if (match.totalscore==-FLT_MAX || m.totalscore==-FLT_MAX) return 0;
return (map[m.img_s1]==m.db_s1 && map[m.img_s2]==m.db_s2)?1:0;
}
/**
* @brief TODO
*/
void search() {if (db->results->is_kdsorted()) db->results->kdsearch(R11,R21,R31,MAXFOV/2,THRESH_FACTOR*IMAGE_VARIANCE);}
/**
* @brief TODO
*/
void clear_search() {if (db->results->is_kdsorted()) db->results->clear_kdresults();}
/**
* @brief TODO
*/
void compute_score() {
//TODO: figure out where 2*map_size came from
match.totalscore=log(1.0/(IMG_X*IMG_Y))*(2*map_size);
float* scores=(float *)malloc(sizeof(float)*map_size);
for (size_t i=0;i<map_size;i++) {
map[i]=-1;
scores[i]=0.0;
}
for(size_t i=0;i<db->results->r_size();i++) {
star *s=&(db->results->map[db->results->kdresults[i]]);
int o=s->star_idx;
float x=s->x*R11+s->y*R21+s->z*R31;
float y=s->x*R12+s->y*R22+s->z*R32;
float z=s->x*R13+s->y*R23+s->z*R33;
float px=y/(x*PIXX_TANGENT);
float py=z/(x*PIXY_TANGENT);
int n=img_mask->get_id(px,py);
if (n>=0) {
float score = img_mask->get_score(n,px,py);
if (score>scores[n]){/* only match the closest star */
map[n]=o;
scores[n]=score;
}
}
}
for(size_t n=0;n<map_size;n++) {
match.totalscore+=scores[n];
}
free(scores);
}
/**
* @return matching stars from db, in order of star_idx
*/
star_db* from_match() {
if (match.totalscore==-FLT_MAX) return NULL;
star_db* s = img->stars->copy();
s->max_variance=db->stars->max_variance;
for(size_t n=0;n<map_size;n++) {
//catalog matching
if (map[n]!=-1) {
s->get_star(img->stars->get_star(n)->star_idx)[0]=db->stars->get_star(map[n])[0];
} else {
s->get_star(img->stars->get_star(n)->star_idx)->id=-1;
}
}
return s;
}
/**
* @brief weighted_triad results
* see https://en.wikipedia.org/wiki/Triad_method
* and http://nghiaho.com/?page_id=846
*
* when compiled, this section contains roughly 430 floating point operations
* according to https://www.karlrupp.net/2016/02/gemm-and-stream-results-on-intel-edison
* we can perform >250 MFLOPS with doubles, and >500 MFLOPS with floats
*/
void weighted_triad() {
star *db_s1=db->stars->get_star(match.db_s1);
star *db_s2=db->stars->get_star(match.db_s2);
star *img_s1=img->stars->get_star(match.img_s1);
star *img_s2=img->stars->get_star(match.img_s2);
/* v=A*w */
float wa1=db_s1->x,wa2=db_s1->y,wa3=db_s1->z;
float wb1=db_s2->x,wb2=db_s2->y,wb3=db_s2->z;
float va1=img_s1->x,va2=img_s1->y,va3=img_s1->z;
float vb1=img_s2->x,vb2=img_s2->y,vb3=img_s2->z;
float wc1=wa2*wb3 - wa3*wb2;
float wc2=wa3*wb1 - wa1*wb3;
float wc3=wa1*wb2 - wa2*wb1;
float wcnorm=sqrt(wc1*wc1+wc2*wc2+wc3*wc3);
wc1/=wcnorm;
wc2/=wcnorm;
wc3/=wcnorm;
float vc1=va2*vb3 - va3*vb2;
float vc2=va3*vb1 - va1*vb3;
float vc3=va1*vb2 - va2*vb1;
float vcnorm=sqrt(vc1*vc1+vc2*vc2+vc3*vc3);
vc1/=vcnorm;
vc2/=vcnorm;
vc3/=vcnorm;
float vaXvc1=va2*vc3 - va3*vc2;
float vaXvc2=va3*vc1 - va1*vc3;
float vaXvc3=va1*vc2 - va2*vc1;
float waXwc1=wa2*wc3 - wa3*wc2;
float waXwc2=wa3*wc1 - wa1*wc3;
float waXwc3=wa1*wc2 - wa2*wc1;
/* some of these are unused */
float A11=va1*wa1 + vaXvc1*waXwc1 + vc1*wc1;
/* float A12=va1*wa2 + vaXvc1*waXwc2 + vc1*wc2; */
/* float A13=va1*wa3 + vaXvc1*waXwc3 + vc1*wc3; */
float A21=va2*wa1 + vaXvc2*waXwc1 + vc2*wc1;
/* float A22=va2*wa2 + vaXvc2*waXwc2 + vc2*wc2; */
/* float A23=va2*wa3 + vaXvc2*waXwc3 + vc2*wc3; */
float A31=va3*wa1 + vaXvc3*waXwc1 + vc3*wc1;
float A32=va3*wa2 + vaXvc3*waXwc2 + vc3*wc2;
float A33=va3*wa3 + vaXvc3*waXwc3 + vc3*wc3;
wc1=-wc1;
wc2=-wc2;
wc3=-wc3;
vc1=-vc1;
vc2=-vc2;
vc3=-vc3;
float vbXvc1=vb2*vc3 - vb3*vc2;
float vbXvc2=vb3*vc1 - vb1*vc3;
float vbXvc3=vb1*vc2 - vb2*vc1;
float wbXwc1=wb2*wc3 - wb3*wc2;
float wbXwc2=wb3*wc1 - wb1*wc3;
float wbXwc3=wb1*wc2 - wb2*wc1;
/* some of these are unused */
float B11=vb1*wb1 + vbXvc1*wbXwc1 + vc1*wc1;
/* float B12=vb1*wb2 + vbXvc1*wbXwc2 + vc1*wc2; */
/* float B13=vb1*wb3 + vbXvc1*wbXwc3 + vc1*wc3; */
float B21=vb2*wb1 + vbXvc2*wbXwc1 + vc2*wc1;
/* float B22=vb2*wb2 + vbXvc2*wbXwc2 + vc2*wc2; */
/* float B23=vb2*wb3 + vbXvc2*wbXwc3 + vc2*wc3; */
float B31=vb3*wb1 + vbXvc3*wbXwc1 + vc3*wc1;
float B32=vb3*wb2 + vbXvc3*wbXwc2 + vc3*wc2;
float B33=vb3*wb3 + vbXvc3*wbXwc3 + vc3*wc3;
/* use weights based on magnitude */
/* weighted triad */
float weightA=1.0/(db_s1->sigma_sq+img_s1->sigma_sq);
float weightB=1.0/(db_s2->sigma_sq+img_s2->sigma_sq);
float sumAB=weightA+weightB;
weightA/=sumAB;
weightB/=sumAB;
float cz,sz,mz;
float cy,sy,my;
float cx,sx,mx;
cz=weightA*A11+weightB*B11;
sz=weightA*A21+weightB*B21;
mz=sqrt(cz*cz+sz*sz);
cz=cz/mz;
sz=sz/mz;
cy=weightA*sqrt(A32*A32+A33*A33)+weightB*sqrt(B32*B32+B33*B33);
sy=-weightA*A31-weightB*B31;
my=sqrt(cy*cy+sy*sy);
cy=cy/my;
sy=sy/my;
cx=weightA*A33+weightB*B33;
sx=weightA*A32+weightB*B32;
mx=sqrt(cx*cx+sx*sx);
cx=cx/mx;
sx=sx/mx;
R11=cy*cz;
R21=cz*sx*sy - cx*sz;
R31=sx*sz + cx*cz*sy;
R12=cy*sz;
R22=cx*cz + sx*sy*sz;
R32=cx*sy*sz - cz*sx;
R13=-sy;
R23=cy*sx;
R33=cx*cy;
}
void DBG_(const char *s) {
DBG_PRINT("%s\n",s);
DBG_PRINT("%f\t%f\t%f\n", R11,R12,R13);
DBG_PRINT("%f\t%f\t%f\n", R21,R22,R23);
DBG_PRINT("%f\t%f\t%f\n", R31,R32,R33);
db->DBG_("DB");
img->DBG_("IMG");
DBG_PRINT("map_size=%lu\n", map_size);
for (size_t i=0; i<map_size; i++) {
DBG_PRINT("map[%lu]=%d\n",i,map[i]);
}
}
/**
* @brief TODO
*/
void print_ori() {
fprintf(stderr,"DEC=%f\n",fmod(360+asin(R31)* 180 / PI,360));
fprintf(stderr,"RA=%f\n",fmod(360+atan2(R21,R11)* 180 / PI,360));
fprintf(stderr,"ORIENTATION=%f\n",-atan2(R32,R33)* 180 / PI);
}
};
struct db_match {
private:
constellation_pair *c_pairs;
size_t c_pairs_size;
star_fov *img_mask;
public:
float p_match;
match_result *winner;
/**
* @brief TODO
* @param db
* @param img
*/
db_match(constellation_db *db, constellation_db *img) {
DBG_DB_MATCH_COUNT++;
DBG_PRINT("DBG_DB_MATCH_COUNT++ %d\n",DBG_DB_MATCH_COUNT);
winner=NULL;
img_mask=NULL;
c_pairs=NULL;
c_pairs_size=0;
p_match=0.0;
if (db->stars->size()<3||img->stars->size()<3) return;
img_mask = new star_fov(img->stars,db->stars->max_variance);
//find stars
match_result *m=new match_result(db, img, img_mask);
winner=new match_result(db, img, img_mask);
for (size_t n=0;n<img->map_size;n++) {
constellation lb=img->map[n];
constellation ub=img->map[n];
lb.p-=POS_ERR_SIGMA*PIXSCALE*sqrt(img->stars->get_star(lb.s1)->sigma_sq+img->stars->get_star(lb.s2)->sigma_sq+2*db->stars->max_variance);
ub.p+=POS_ERR_SIGMA*PIXSCALE*sqrt(img->stars->get_star(ub.s1)->sigma_sq+img->stars->get_star(ub.s2)->sigma_sq+2*db->stars->max_variance);
constellation *lower=std::lower_bound (db->map, db->map+db->map_size, lb,constellation_lt_p);
constellation *upper=std::upper_bound (db->map, db->map+db->map_size, ub,constellation_lt_p);
//rewind upper & do sanity checks
if (db->map>=upper--) continue;
if (db->map+db->map_size<=lower) continue;
if (lower->idx<=upper->idx) {
c_pairs=(struct constellation_pair*)realloc(c_pairs,sizeof(struct constellation_pair)*(c_pairs_size+(upper->idx-lower->idx+1)*2));
}
for (int o=lower->idx;o<=upper->idx;o++) {
m->init(db->map[o],img->map[n]);
m->weighted_triad();
m->search();
#define ADD_SCORE\
m->compute_score();\
if (m->match.totalscore>winner->match.totalscore) {\
if (winner->match.totalscore!=-FLT_MAX) c_pairs[c_pairs_size++]=winner->match;\
m->copy_over(winner);\
} else c_pairs[c_pairs_size++]=m->match;
ADD_SCORE
/* try both orderings of stars */
m->match.flip();
m->weighted_triad();
ADD_SCORE
m->clear_search();
}
}
delete m;
//calculate map
if (winner->match.totalscore!=-FLT_MAX) { //Did we even match?
/**
* normalize the posterior to find the probability that the best match is the correct one
* this relies on three assumptions:
* 1. The sample point is approximately the maximum likelihood
* 2. The probability distribution around the sample points are all the same
* 3. the probability outside of the range od sampled points is approximately zero
*/
//calculate p_match
p_match=1.0;
for (size_t idx=0; idx<c_pairs_size;idx++) {
if (!winner->related(c_pairs[idx])){
p_match+=exp(c_pairs[idx].totalscore-winner->match.totalscore);
}
}
p_match=1.0/p_match;
}
}
~db_match() {
DBG_DB_MATCH_COUNT--;
DBG_PRINT("DBG_DB_MATCH_COUNT-- %d\n",DBG_DB_MATCH_COUNT);
delete winner;
delete img_mask;
free(c_pairs);
}
};
#endif
================================================
FILE: beast/beast.i
================================================
%module beast
%{
#include "config.h"
#include "stars.h"
#include "constellations.h"
#include "beast.h"
%}
//newobject gives python control of these objects
%newobject star_db::copy;
%newobject star_db::copy_n_brightest;
%newobject star_db::search;
%newobject star_db::operator-;
%newobject star_db::operator&;
%newobject star_query::from_kdmask;
%newobject star_query::from_kdresults;
%newobject match_result::from_match;
%include "config.h"
%include "stars.h"
%include "constellations.h"
%include "beast.h"
================================================
FILE: beast/config.h
================================================
#ifndef CONFIG_H
#define CONFIG_H
#include <stdio.h>
#include <stdlib.h>//EXIT_FAILURE
#include <string.h>
#include <math.h>
#define PI 3.14159265358979323846 /* pi */
#define TWOPI 6.28318530717958647693
int DBG_ENABLE;
#define DBG_PRINT(format,args...) if (DBG_ENABLE==1) fprintf(stderr,format, ## args);
int DBG_STAR_DB_COUNT,DBG_CONSTELLATION_DB_COUNT,DBG_DB_MATCH_COUNT;
int DBG_MATCH_RESULT_COUNT,DBG_STAR_FOV_COUNT,DBG_STAR_QUERY_COUNT;
//TODO: config class (allows different configs for different cameras)
int IMG_X,IMG_Y,MAX_FALSE_STARS,DB_REDUNDANCY,REQUIRED_STARS;
float PIXSCALE,DOUBLE_STAR_PX;
float BASE_FLUX,IMAGE_VARIANCE,THRESH_FACTOR,POS_VARIANCE,POS_ERR_SIGMA;
float MAXFOV,MINFOV,MATCH_VALUE,PIXX_TANGENT,PIXY_TANGENT;
int KDBUCKET_SIZE;
int ENV_VARS_SIZE;
char** ENV_VARS; //keep track of these so that valgrind is happy
/**
* @brief Loads global variables from calibration data
* @param filename calibration file generated by TODO:calibrate.sh? unit_test.sh
*/
void load_config(const char *filename) {
DBG_STAR_DB_COUNT=DBG_CONSTELLATION_DB_COUNT=DBG_DB_MATCH_COUNT=0;
DBG_MATCH_RESULT_COUNT=DBG_STAR_FOV_COUNT=DBG_STAR_QUERY_COUNT=0;
DBG_ENABLE=0;
ENV_VARS_SIZE=0;
ENV_VARS=NULL;
//move calibration.txt to constellation_db
/* load config */
FILE *stream = fopen(filename, "r");
if (stream == NULL) exit(EXIT_FAILURE);
//FILE *stream = fopen(filename, "r");
ssize_t read;
char *line = NULL;
size_t len = 0;
while ((read = getline(&line, &len, stream)) != -1) {
ENV_VARS=(char**)realloc(ENV_VARS,(ENV_VARS_SIZE+1)*sizeof(ENV_VARS[0]));
ENV_VARS[ENV_VARS_SIZE]=(char *)malloc(sizeof(char) * len);
putenv(strcpy(ENV_VARS[ENV_VARS_SIZE++],line));
}
free(line);
fclose(stream);
IMG_X=atoi(getenv("IMG_X"));
IMG_Y=atoi(getenv("IMG_Y"));
PIXSCALE=atof(getenv("PIXSCALE"));
POS_ERR_SIGMA=atof(getenv("POS_ERR_SIGMA"));
POS_VARIANCE=atof(getenv("POS_VARIANCE"));/* sigma_r^2 */
IMAGE_VARIANCE=atof(getenv("IMAGE_VARIANCE"));/* lambda */
THRESH_FACTOR=atof(getenv("THRESH_FACTOR"));/* lambda */
DOUBLE_STAR_PX=atof(getenv("DOUBLE_STAR_PX"));
MAX_FALSE_STARS=atoi(getenv("MAX_FALSE_STARS"));/* >10 is slow */
DB_REDUNDANCY=atoi(getenv("DB_REDUNDANCY"));
REQUIRED_STARS=atoi(getenv("REQUIRED_STARS"));
BASE_FLUX=atof(getenv("BASE_FLUX"));
MAXFOV=PIXSCALE*sqrt(IMG_X*IMG_X+IMG_Y*IMG_Y);
MINFOV=PIXSCALE*IMG_Y;
MATCH_VALUE=4*log(1.0/(IMG_X*IMG_Y))+log(2*PI);/* base */
PIXX_TANGENT=2*tan((IMG_X*PIXSCALE/3600)*PI/(180*2))/IMG_X;
PIXY_TANGENT=2*tan((IMG_Y*PIXSCALE/3600)*PI/(180*2))/IMG_Y;
KDBUCKET_SIZE=((IMG_X*PIXSCALE/3600)*(IMG_Y*PIXSCALE/3600)*3.5);
}
#endif
================================================
FILE: beast/constellations.h
================================================
#ifndef CONSTELLATIONS_H
#define CONSTELLATIONS_H
#include "stars.h"
#include <set>
struct constellation {
float p;
size_t s1;
size_t s2;
int idx;
void DBG_(const char *s) {
DBG_PRINT("%s\t",s);
DBG_PRINT("p=%f ",p);
DBG_PRINT("s1=%lu ",s1);
DBG_PRINT("s2=%lu ",s2);
DBG_PRINT("idx=%d\n",idx);
}
};
struct constellation_pair {
//TODO: private:
float totalscore;
int db_s1,db_s2;
int img_s1,img_s2;
public:
/**
* @brief TODO
*/
void flip() {
int t=img_s1;
img_s1=img_s2;
img_s2=t;
}
void DBG_(const char *s) {
DBG_PRINT("%s\t",s);
DBG_PRINT("totalscore=%f ",totalscore);
DBG_PRINT("db_s1=%d ",db_s1);
DBG_PRINT("db_s2=%d ",db_s2);
DBG_PRINT("img_s1=%d ",img_s1);
DBG_PRINT("img_s2=%d\n",img_s2);
}
};
struct constellation_lt {
bool operator() (const constellation &c1, const constellation &c2) {
if (c1.p!=c2.p) return c1.p<c2.p;
else if (c1.s1!=c2.s1) return c1.s1<c2.s1;
else return c1.s2<c2.s2;
}
};
bool constellation_lt_s1(const constellation &c1, const constellation &c2) {return c1.s1 < c2.s1;}
bool constellation_lt_s2(const constellation &c1, const constellation &c2) {return c1.s2 < c2.s2;}
bool constellation_lt_p(const constellation &c1, const constellation &c2) {return c1.p < c2.p;}
struct constellation_db {
//TODO: private:
star_db* stars;
star_query* results;
size_t map_size;
constellation* map;
public:
/**
* @brief TODO
*
* @param s
* @param stars_per_fov
* @param from_image
*/
constellation_db(star_db *s,const int stars_per_fov, const int from_image) {
DBG_CONSTELLATION_DB_COUNT++;
DBG_PRINT("DBG_CONSTELLATION_DB_COUNT++ %d\n",DBG_CONSTELLATION_DB_COUNT);
if (from_image) {
stars=s->copy();
results=new star_query(stars);
results->sort();
map=NULL;
int ns=stars->size();/* number of stars to check */
if (ns>stars_per_fov) ns=stars_per_fov;//MAX_FALSE_STARS+2
map_size=ns*(ns-1)/2;
map=(constellation*)malloc(map_size*sizeof(map[0]));
int idx=0;
for (int j=1;j<ns;j++) for (int i=0;i<j;i++,idx++) {
map[idx].p=results->map[i].dist_arcsec(results->map[j]);
map[idx].s1=results->map[i].star_idx;
map[idx].s2=results->map[j].star_idx;
}
std::sort(map, map+map_size,constellation_lt_p);
while (--idx>=0) map[idx].idx=idx;
} else {
stars=s->copy();
results=new star_query(stars);
results->kdmask_uniform_density(stars_per_fov);//2+DB_REDUNDANCY
std::set<constellation,constellation_lt> c_set;
for (size_t i=0;i<results->map_size;i++) if (results->get_kdmask(i)==0) {
results->kdsearch(results->map[i].x,results->map[i].y,results->map[i].z,MAXFOV,THRESH_FACTOR*IMAGE_VARIANCE);
constellation c;
for (size_t j=0;j<results->r_size();j++) if (i!=results->kdresults[j] && results->map[i].flux>=results->map[results->kdresults[j]].flux){
c.p=results->map[i].dist_arcsec(results->map[results->kdresults[j]]);
c.s1=results->map[i].star_idx;
c.s2=results->map[results->kdresults[j]].star_idx;
c_set.insert(c);
}
results->clear_kdresults();
}
results->reset_kdmask();
//preallocate map
map_size=c_set.size();
map=(constellation*)malloc(map_size*sizeof(map[0]));
std::set<constellation>::iterator it = c_set.begin();
for (size_t idx=0; idx<map_size;idx++,it++) {
map[idx]=*it;
map[idx].idx=idx;
}
}
}
~constellation_db() {
DBG_CONSTELLATION_DB_COUNT--;
DBG_PRINT("DBG_CONSTELLATION_DB_COUNT-- %d\n",DBG_CONSTELLATION_DB_COUNT);
free(map);
delete results;
delete stars;
}
void DBG_(const char *s) {
DBG_PRINT("%s\n",s);
stars->DBG_("STARS");
results->DBG_("RESULTS");
for (size_t i=0; i<map_size; i++) {
DBG_PRINT("%lu:\t",i);
map[i].DBG_("C");
}
}
};
#endif
================================================
FILE: beast/go
================================================
make
================================================
FILE: beast/kdhash.h
================================================
#ifndef KDHASH_H
#define KDHASH_H
#include <stdint.h>
/**
* multidimensional hash function based on morton codes
*
* the magic numbers were generated by doc/gen_interleave.py
*
* If we ever need to implement decoding, useful info can be found here:
* https://fgiesen.wordpress.com/2009/12/13/decoding-morton-codes/
* (basically just do everything backwards)
*
*/
struct kdhash_2f {
#define DIAM 0xffffffff
#define R_IN (DIAM/2)
#define R_OUT (R_IN+1)
#define INTERLEAVE(X)\
if (X > DIAM) X=DIAM;\
if (X < 0) X=0;\
X = (X | X << 16) & 0xffff0000ffff;\
X = (X | X << 8) & 0xff00ff00ff00ff;\
X = (X | X << 4) & 0xf0f0f0f0f0f0f0f;\
X = (X | X << 2) & 0x3333333333333333;\
X = (X | X << 1) & 0x5555555555555555;
/**
* @brief hash function which interleaves values so that nearby coordinates will have nearby hashes
* this approach also also allows you to truncate the hash when less precision is needed
*/
static inline uint64_t hash(const float x0,const float x1){
int64_t h0=R_OUT*(x0+1.0);
int64_t h1=R_OUT*(x1+1.0);
INTERLEAVE(h0)
INTERLEAVE(h1)
return h1<<1|h0;
}
/**
* @brief returns returns the number of bits we need to truncate in order to search a specified range
*/
static inline uint8_t bin_size(const float r) {
int64_t h = R_OUT*r;
if (h > R_IN) h=R_IN;
if (h < 0) h=0;
uint8_t sz=0;
for (;h;h>>=1) sz+=1;
return sz;
}
/**
* @brief returns a mask which can be used to clamp the hash to a specified precision
* @param r mask a range of this size, rounded up to the nearest power of two
*/
static inline uint64_t mask(const float r) {
uint64_t mask=-1;
return mask<<2*bin_size(r);
}
/**
* @brief As before, but allows independent ranges for the different parameters
*/
static inline uint64_t mask(const float r0,const float r1){
int64_t h0=R_OUT>>bin_size(r0);
int64_t h1=R_OUT>>bin_size(r1);
INTERLEAVE(h0)
INTERLEAVE(h1)
return h1<<1|h0;
}
#undef INTERLEAVE
#undef R_OUT
#undef R_IN
#undef DIAM
};
struct kdhash_3f {
#define DIAM 0x1fffff
#define R_IN (DIAM/2)
#define R_OUT (R_IN+1)
#define INTERLEAVE(X)\
if (X > DIAM) X=DIAM;\
if (X < 0) X=0;\
X = (X | X <<32) & 0x001f00000000ffff;\
X = (X | X <<16) & 0x001f0000ff0000ff;\
X = (X | X << 8) & 0x100f00f00f00f00f;\
X = (X | X << 4) & 0x10c30c30c30c30c3;\
X = (X | X << 2) & 0x1249249249249249;
///See kdhash_2f::hash
static inline uint64_t hash(const float x0,const float x1,const float x2){
int64_t h0=R_OUT*(x0+1.0);
int64_t h1=R_OUT*(x1+1.0);
int64_t h2=R_OUT*(x2+1.0);
INTERLEAVE(h0)
INTERLEAVE(h1)
INTERLEAVE(h2)
return h2<<2|h1<<1|h0;
}
///See kdhash_2f::bin_size
static inline uint8_t bin_size(const float radians) {
int64_t h = R_OUT*radians;
if (h > R_IN) h=R_IN;
if (h < 0) h=0;
uint8_t sz=0;
for (;h;h>>=1) sz+=1;
return sz;
}
///See kdhash_2f::mask
static inline uint64_t mask(const float radians) {
uint64_t mask=-1;
return mask<<3*bin_size(radians);
}
///See kdhash_2f::mask
static inline uint64_t mask(const float r0,const float r1,const float r2){
int64_t h0=R_OUT>>bin_size(r0);
int64_t h1=R_OUT>>bin_size(r1);
int64_t h2=R_OUT>>bin_size(r2);
INTERLEAVE(h0)
INTERLEAVE(h1)
INTERLEAVE(h2)
return h2<<2|h1<<1|h0;
}
#undef INTERLEAVE
#undef R_OUT
#undef R_IN
#undef DIAM
};
struct kdhash_4f {
#define DIAM 0xfffff
#define R_IN (DIAM/2)
#define R_OUT (R_IN+1)
#define INTERLEAVE(X)\
if (X > DIAM) X=DIAM;\
if (X < 0) X=0;\
X = (X | X << 32) & 0xf800000007ff;\
X = (X | X << 16) & 0xf80007c0003f;\
X = (X | X << 8) & 0xc0380700c03807;\
X = (X | X << 4) & 0x843084308430843;\
X = (X | X << 2) & 0x909090909090909;\
X = (X | X << 1) & 0x1111111111111111;
///See kdhash_2f::hash
static inline uint64_t hash(const float x0,const float x1,const float x2,const float x3){
int64_t h0=R_OUT*(x0+1.0);
int64_t h1=R_OUT*(x1+1.0);
int64_t h2=R_OUT*(x2+1.0);
int64_t h3=R_OUT*(x3+1.0);
INTERLEAVE(h0)
INTERLEAVE(h1)
INTERLEAVE(h2)
INTERLEAVE(h3)
return h3<<3|h2<<2|h1<<1|h0;
}
///See kdhash_2f::bin_size
static inline uint8_t bin_size(const float radians) {
int64_t h = R_OUT*radians;
if (h > R_IN) h=R_IN;
if (h < 0) h=0;
uint8_t sz=0;
for (;h;h>>=1) sz+=1;
return sz;
}
///See kdhash_2f::mask
static inline uint64_t mask(const float radians) {
uint64_t mask=-1;
return mask<<4*bin_size(radians);
}
///See kdhash_2f::mask
static inline uint64_t mask(const float r0,const float r1,const float r2,const float r3){
int64_t h0=R_OUT>>bin_size(r0);
int64_t h1=R_OUT>>bin_size(r1);
int64_t h2=R_OUT>>bin_size(r2);
int64_t h3=R_OUT>>bin_size(r3);
INTERLEAVE(h0)
INTERLEAVE(h1)
INTERLEAVE(h2)
INTERLEAVE(h3)
return h0<<3|h1<<2|h2<<1|h3;
}
#undef INTERLEAVE
#undef R_OUT
#undef R_IN
#undef DIAM
};
#endif
================================================
FILE: beast/stars.h
================================================
#ifndef STARS_H
#define STARS_H
#include "config.h"
#include "kdhash.h"
#include <assert.h> //assert()
#include <limits.h> //INT_MAX
//stl for days
#include <array> //sort, nth_element
#include <algorithm> //sort, nth_element
#include <set>
#include <unordered_set>
#include <map>
#include <vector>
#include <unordered_map>
#include <iterator> // std::next
struct star {
float x;
float y;
float z;
float flux;
/**user defined id (ie hipparcos id, -1)*/
int id;
float px;
float py;
int unreliable;
/** how many stars were inserted before this one? */
int star_idx;
float sigma_sq;
size_t hash_val;
/**
* @brief add star from catalog
*
* @param x ECI 'coming out of image'
* @param y ECI
* @param z ECI z
* @param flux Pixel brightness
* @param id User defined id
*/
star(){};
star(const float x_, const float y_, const float z_, const float flux_, const int id_) {
x=x_;
y=y_;
z=z_;
flux=flux_;
id=id_;
px=y/(x*PIXX_TANGENT);
py=z/(x*PIXY_TANGENT);
unreliable=0;
star_idx=-1;
sigma_sq=POS_VARIANCE;
hash_val=kdhash_3f::hash(x,y,z);
}
/**
* @brief add star from image
*
* @param px Pixel x minus camera center
* @param py Pixel y minus camera center
* @param flux Pixel brightness
* @param id User defined id
*/
star(const float px_, const float py_, const float flux_, const int id_) {
px=px_;
py=py_;
flux=flux_;
id=id_;
float j=(PIXX_TANGENT*px); /* j=(y/x) */
float k=(PIXY_TANGENT*py); /* k=z/x */
x=1./sqrt(j*j+k*k+1);
y=j*x;
z=k*x;
unreliable=0;
star_idx=-1;
sigma_sq=IMAGE_VARIANCE/flux;
hash_val=kdhash_3f::hash(x,y,z);
}
#define OP operator==
bool OP(const star& s) const {return hash_val==s.hash_val;}
#undef OP
/**
* @brief numerically stable method to calculate distance between stars
* @param s Star
* @return Angular seperation in arcsec
*/
float dist_arcsec(const star& s) const {
float a=x*s.y - s.x*y;
float b=x*s.z - s.x*z;
float c=y*s.z - s.y*z;
return (3600*180.0/PI)*asin(sqrt(a*a+b*b+c*c));
}
/**
* @brief Print debug info
* @param s Label
*/
void DBG_(const char *s) {
DBG_PRINT("%s\t",s);
DBG_PRINT("x=%f ", x);
DBG_PRINT("y=%f ", y);
DBG_PRINT("z=%f ", z);
DBG_PRINT("flux=%f ", flux);
DBG_PRINT("star_idx=%d ", star_idx);
DBG_PRINT("id=%d ", id);
DBG_PRINT("unreliable=%d ", unreliable);
DBG_PRINT("sigma_sq=%f ", sigma_sq);
DBG_PRINT("px=%f ", px);
DBG_PRINT("py=%f\n", py);
}
};
bool star_gt_x(const star &s1, const star &s2) {return s1.x > s2.x;}
bool star_gt_y(const star &s1, const star &s2) {return s1.y > s2.y;}
bool star_gt_z(const star &s1, const star &s2) {return s1.z > s2.z;}
bool star_gt_flux(const star &s1, const star &s2) {return s1.flux > s2.flux;}
bool star_lt_x(const star &s1, const star &s2) {return s1.x < s2.x;}
bool star_lt_y(const star &s1, const star &s2) {return s1.y < s2.y;}
bool star_lt_z(const star &s1, const star &s2) {return s1.z < s2.z;}
bool star_lt_flux(const star &s1, const star &s2) {return s1.flux < s2.flux;}
struct star_db {
private:
std::unordered_map<uint64_t,star> hash_map;
std::set<uint64_t> hash_set;
std::vector<uint64_t> star_idx_vector;
std::multimap<float,uint64_t> flux_map;
size_t sz;
/**
* @brief Transcribe a portion of the db between first and last
*
* @param first an iterator to a map. key can be anything, but value must be a star hash
* @param last copy up to but not including the element pointed to by this iterator
*/
template<class T> star_db* copy(T first,T last) {
star_db* s = new star_db;
for (;first!=last;first++) (*s)+=hash_map[*first];
return s;
}
public:
//TODO
float max_variance;
star_db() {
DBG_STAR_DB_COUNT++;
DBG_PRINT("DBG_STAR_DB_COUNT++ %d\n",DBG_STAR_DB_COUNT);
max_variance=0.0;
sz=0;
}
~star_db() {
DBG_STAR_DB_COUNT--;
DBG_PRINT("DBG_STAR_DB_COUNT-- %d\n",DBG_STAR_DB_COUNT);
}
size_t size() {return sz;}
///Philosophically inspired by python sets
#define OP operator+=
star_db* OP(const star& s) { return *this+=&s;}
star_db* OP(const star* s) {
if (count(s)==0) {
if (max_variance<s->sigma_sq) max_variance=s->sigma_sq;
star temp=s[0];
temp.star_idx=size();
hash_map.emplace(temp.hash_val,temp);
hash_set.insert(temp.hash_val);
flux_map.emplace(temp.flux,temp.hash_val);
star_idx_vector.push_back(temp.hash_val);
sz++;
}
return this;
}
#undef OP
//TODO - faster to use insert?
star_db* OP(star_db* s) {
for (size_t i=0;i<s->size();i++) (*this)+=s->get_star(i);
return this;
}
#define OP operator-
star_db* OP(const star_db* s) {
star_db* r = new star_db;
for (auto it = star_idx_vector.cbegin(); it != star_idx_vector.cend(); ++it) {
if (s->hash_map.count(*it)==0) *r+=hash_map.at(*it);
}
return r;
}
#undef OP
#define OP operator&
star_db* OP(const star_db* s) {
star_db* r = new star_db;
for (auto it = star_idx_vector.cbegin(); it != star_idx_vector.cend(); ++it) {
if (s->hash_map.count(*it)>0) *r+=hash_map.at(*it);
}
return r;
}
#undef OP
/**
* @brief returns stars in the order they were added
*
* @param idx the index of the star
*/
star* get_star_by_hash(const size_t hash) {return &(hash_map.at(hash));}
/**
* @brief returns stars in the order they were added
*
* @param idx the index of the star
*/
star* get_star(const int idx) {return size()>0?get_star_by_hash(star_idx_vector[idx]):NULL;}
/**
* @brief make a copy of the star db
*/
star_db* copy() {return copy(star_idx_vector.cbegin(),star_idx_vector.cend());}
/**
* @brief make a copy of the n brightest elements in the star db
*/
star_db* copy_n_brightest(const size_t n) {
//return copy(flux_map.crbegin(),std::next(flux_map.crbegin(),std::min(n,size())));
star_db* s = new star_db;
auto first=flux_map.crbegin();
auto last=std::next(flux_map.crbegin(),std::min(n,size()));
for (;first!=last;first++) (*s)+=get_star_by_hash(first->second);
return s;
}
//std::array* n_brightest(T &hs,n) {
//
//}
/**
* @brief return stars in the bounding volume around the specified star
* @param r minimum radius of the bounding volume (arcseconds).
*
*/
//TODO: group together by hash_lb,ub, n_brightest_search (maybe return a list?)
template<class T> void search(T &hs, const float x,const float y,const float z, float r, const float min_flux) {
r=r/3600.0;
r=r*PI/180.0;
r=2*fabs(sin(r/2.0));
size_t mask=kdhash_3f::mask(r);
for (int8_t dx=-1;dx<=1;dx++) for (int8_t dy=-1;dy<=1;dy++) for (int8_t dz=-1;dz<=1;dz++) {
size_t h=kdhash_3f::hash(x+dx*r,y+dy*r,z+dz*r);
auto first = hash_set.lower_bound(h&mask);
auto last = hash_set.upper_bound(h|(~mask));
for (;first!=last;first++) {
star *s=get_star_by_hash(*first);
float dist_x=s->x-x;
float dist_y=s->y-y;
float dist_z=s->z-z;
if (dist_x*dist_x+dist_y*dist_y+dist_z*dist_z<=r*r) {
if (min_flux <= s->flux) hs.insert(*first);
}
}
}
}
/**
* @brief Load stars from hip_main.dat
*
* @param catalog path to hip_main.dat
* @param year Update star positions to the specified year
*/
void load_catalog(const char* catalog, const float year) {
FILE *stream = fopen(catalog, "r");
if (stream == NULL) exit(EXIT_FAILURE);
max_variance=POS_VARIANCE;
ssize_t read;
char *line = NULL;
size_t len = 0;
char* hip_record[78];
while ((read = getline(&line, &len, stream)) != -1){
float yeardiff=year-1991.25;
hip_record[0]=strtok(line,"|");
for (size_t j=1;j<sizeof(hip_record)/sizeof(hip_record[0]);j++) hip_record[j] = strtok(NULL,"|");
float MAG=atof(hip_record[5]);
float DEC=yeardiff*atof(hip_record[13])/3600000.0 + atof(hip_record[9]);
float cosdec=cos(PI*DEC/180.0);
float RA=yeardiff*atof(hip_record[12])/(cosdec*3600000.0) + atof(hip_record[8]);
star s = star(cos(PI*RA/180.0)*cosdec,sin(PI*RA/180.0)*cosdec,sin(PI*DEC/180.0),BASE_FLUX*powf(10.0,-MAG/2.5),atoi(hip_record[1]));
s.unreliable=((atoi(hip_record[29])==0||atoi(hip_record[29])==1)&&atoi(hip_record[6])!=3)?0:1;
(*this)+=s;
}
free(line);
fclose(stream);
}
size_t count(const star* s) {return hash_map.count(s->hash_val);}
size_t count(star_db* s) {
size_t n=0;
for (size_t i=0;i<s->size();i++) n+=count(s->get_star(i));
return n;
}
void DBG_(const char *s) {
DBG_PRINT("%s\n",s);
DBG_PRINT("star_db at %lu contains %lu elements\n",(size_t)this,size());
DBG_PRINT("max_variance=%f\n",max_variance);
for (size_t i=0; i<size(); i++) {
DBG_PRINT("%lu:\t",i);
get_star(i)->DBG_("star");
}
}
};
struct star_fov {
private:
int *mask;
star_db *stars;
int *collision;
int collision_size;
float db_max_variance;
float *s_px;
float *s_py;
/**
* @brief Get the id of the best match to the specified coordinates
* Used to resolve collisions where the coordinates falls into the region of overlap between two stars
* Adds a bit of complexity in exchange for being able to break ties at
* the subpixel level, which can sometimes make a difference
*
* @param id - the id from the image map
* Any id <-1 is interpreted as an index in the collision buffer (starts at -2)
*
* @param px Pixel x minus camera center
* @param py Pixel y minus camera center
*
* @return The id of whichever star is the best match to the coordinates in question
*/
int resolve_id(int id,const float px,const float py) {
if (id>=-1) return id;
//Any id <-1 is interpreted as an index in the collision buffer (starts at -2)
id=-id;
int id1=resolve_id(collision[id-2],px,py);
int id2=resolve_id(collision[id-1],px,py);
return (get_score(id1,px,py)>get_score(id2,px,py))?id1:id2;
}
public:
/**
* @brief TODO
*
* @param id
* @param px
* @param py
*
* @return
*/
float get_score(const int id,const float px,const float py) {
float sigma_sq,maxdist_sq;
sigma_sq=stars->max_variance+db_max_variance;
maxdist_sq=-sigma_sq*(log(sigma_sq)+MATCH_VALUE);
float dx=px-s_px[id];
float dy=py-s_py[id];
if (dx<-0.5) dx+=1.0;/* use whichever corner of the pixel gives the best score */
if (dy<-0.5) dy+=1.0;
return (maxdist_sq-(dx*dx+dy*dy))/(2*sigma_sq);
}
/**
* @brief TODO
*
* @param id
* @param px
* @param py
* @param sigma_sq
* @param maxdist_sq
*
* @return
*/
float get_score(const int id,const float px,const float py,const float sigma_sq,const float maxdist_sq) {
float dx=px-s_px[id];
float dy=py-s_py[id];
if (dx<-0.5) dx+=1.0;/* use whichever corner of the pixel gives the best score */
if (dy<-0.5) dy+=1.0;
return (maxdist_sq-(dx*dx+dy*dy))/(2*sigma_sq);
}
int get_id(float px, float py) {
int nx=(int)(px+IMG_X/2.0f);
if (nx==-1) nx++;
else if (nx==IMG_X) nx--;
int ny=(int)(py+IMG_Y/2.0f);
if (ny==-1) ny++;
else if (ny==IMG_Y) ny--;
int id=-1;
if (nx>=0&&nx<IMG_X&&ny>=0&&ny<IMG_Y) id=mask[nx+ny*IMG_X];
return resolve_id(id,px,py);
}
/**
* @brief TODO
* @param s
* @param db_max_variance_
*/
star_fov(star_db* s, const float db_max_variance_) {
DBG_STAR_FOV_COUNT++;
DBG_PRINT("DBG_STAR_FOV_COUNT++ %d\n",DBG_STAR_FOV_COUNT);
db_max_variance=db_max_variance_;
stars=s;
collision=NULL;
collision_size=0;
s_px=(float*)malloc(stars->size()*sizeof(s_px[0]));
s_py=(float*)malloc(stars->size()*sizeof(s_py[0]));
mask=(int*)malloc(IMG_X*IMG_Y*sizeof(mask[0]));
memset(mask, -1, IMG_X*IMG_Y*sizeof(mask[0]));
/* generate image mask */
for (size_t id=0;id<stars->size();id++){
/* assume the dimmest possible star since we dont know the brightness of the other image */
float sigma_sq,maxdist_sq;
sigma_sq=stars->max_variance+db_max_variance;
maxdist_sq=-sigma_sq*(log(sigma_sq)+MATCH_VALUE);
float maxdist=sqrt(maxdist_sq);
s_px[id]=stars->get_star(id)->px;
s_py[id]=stars->get_star(id)->py;
int xmin=s_px[id]-maxdist-1;
int xmax=s_px[id]+maxdist+1;
int ymin=s_py[id]-maxdist-1;
int ymax=s_py[id]+maxdist+1;
if(xmax>IMG_X/2) xmax=IMG_X/2;
if(xmin<-IMG_X/2)xmin=-IMG_X/2;
if(ymax>IMG_Y/2) ymax=IMG_Y/2;
if(ymin<-IMG_Y/2)ymin=-IMG_Y/2;
for(int i=xmin;i<xmax;i++) for (int j=ymin;j<ymax;j++) {
float score=get_score(id, i,j, sigma_sq, maxdist_sq);
int x=i+IMG_X/2;
int y=j+IMG_Y/2;
if (score>0) {
/* has this pixel already been assigned to a different star? */
int id2=mask[x+y*IMG_X];
if (id2!=-1){
collision_size+=2;
mask[x+y*IMG_X]=-collision_size;
collision=(int*)realloc(collision,collision_size*sizeof(collision[0]));
collision[collision_size-2]=id;
collision[collision_size-1]=id2;
} else {
mask[x+y*IMG_X]=id;
}
}
}
}
}
~star_fov() {
DBG_STAR_FOV_COUNT--;
DBG_PRINT("DBG_STAR_FOV_COUNT-- %d\n",DBG_STAR_FOV_COUNT);
free(s_px);
free(s_py);
free(mask);
free(collision);
}
};
struct star_query {
star *map;
size_t map_size;
size_t *kdresults;
private:
uint8_t kdsorted;
size_t kdresults_size;
int8_t *kdmask;
size_t kdresults_maxsize;
star_db *stars;
/** You may be looking at the most compact kd-tree in existence
* It does not use pointers or indexes or leaf nodes or any extra memory
* Instead the list is kdsorted in place using std::nth_element()
* which is standard c++ implementation of quickselect.
*
* References:
* Numerical Recipies (ISBN: 9780521884075)
* https://en.wikipedia.org/wiki/Quickselect
* https://stackoverflow.com/questions/17021379/balancing-kd-tree-which-approach-is-more-efficient
*/
#define KDSORT_NEXT(A,B)\
int mid=(min+max)/2;\
if (min+1<max) {\
std::nth_element(map+min,map+mid,map+max,A);\
if (mid-min>KDBUCKET_SIZE) B(min,mid);\
else std::sort(map+min, map+mid,star_gt_flux);\
if (max-(mid+1)>KDBUCKET_SIZE) B(mid+1,max);\
else std::sort(map+(mid+1), map+max,star_gt_flux);\
}
void kdsort_x(const int min, const int max) {KDSORT_NEXT(star_lt_x,kdsort_y)}
void kdsort_y(const int min, const int max) {KDSORT_NEXT(star_lt_y,kdsort_z)}
void kdsort_z(const int min, const int max) {KDSORT_NEXT(star_lt_z,kdsort_x)}
#undef KDSORT_NEXT
public:
/**
* @brief TODO
* @param s
*/
star_query(star_db *s) {
DBG_STAR_QUERY_COUNT++;
DBG_PRINT("DBG_STAR_QUERY_COUNT++ %d\n",DBG_STAR_QUERY_COUNT);
stars=s;
map_size=stars->size();
kdsorted=0;
kdresults_size=map_size;
kdresults_maxsize=INT_MAX;
kdmask=(int8_t*)malloc((map_size+1)*sizeof(kdmask[0]));
kdresults=(size_t*)malloc((map_size+1)*sizeof(kdresults[0]));
map=(star*)malloc(map_size*sizeof(map[0]));
for (size_t i=0;i<map_size;i++){
map[i]=stars->get_star(i)[0];
kdresults[i]=i;
}
reset_kdmask();
}
~star_query() {
DBG_STAR_QUERY_COUNT--;
DBG_PRINT("DBG_STAR_QUERY_COUNT-- %d\n",DBG_STAR_QUERY_COUNT);
free(map);
free(kdresults);
free(kdmask);
}
uint8_t is_kdsorted() {return kdsorted;}
/**
* @brief kdsort the list in question.
*/
void kdsort() {
if (kdsorted==0) {
kdsort_x(0,map_size);
kdsorted=1;
}
}
void sort() {
std::sort(map, map+map_size,star_gt_flux);
kdsorted=0;
}
size_t r_size() {return kdresults_size;}
int8_t get_kdmask(size_t i) {return kdmask[i];}
/**
* @brief Clears kdmask, but does not reset kdresults. Slow.
*/
void reset_kdmask() {
memset(kdmask,0,sizeof(kdmask[0])*stars->size());
}
/**
* @brief Rewind kdresults, and set the corresponding kdmask to zero
*/
void clear_kdresults() {
while (kdresults_size>0) {
kdresults_size--;
kdmask[kdresults[kdresults_size]]=0;
}
}
/**
* @brief TODO
*
* @param idx
* @param x
* @param y
* @param z
* @param r
* @param min_flux
*/
void kdcheck(const int idx, float x, float y, float z, const float r, const float min_flux){
x-=map[idx].x;
y-=map[idx].y;
z-=map[idx].z;
if (x-r <= 0 && 0 <= x+r &&
y-r <= 0 && 0 <= y+r &&
z-r <= 0 && 0 <= z+r &&
min_flux <= map[idx].flux &&
kdmask[idx] == 0 &&
x*x+y*y+z*z<=r*r) {
kdmask[idx]=1;
/* Insertion sort into list from brightest to dimmest.
*
* Note: Different sorting algorithms can result in different
* stars being selected in the case where there are two candidates of
* equal brightness for the last star. This has no effect on match quality
*/
int n=kdresults_size++;
float sm_flux=map[idx].flux;
for (;n>0&&sm_flux>map[kdresults[n-1]].flux;n--) kdresults[n]=kdresults[n-1];
kdresults[n]=idx;
//if we go over the maximum, bump the dimmest star from the results
if (kdresults_size>kdresults_maxsize) {
kdresults_size=kdresults_maxsize;
kdmask[kdresults[kdresults_size]]=0;
}
}
}
/**
* @brief search map for points within r pixels of x,y,z
* @details put all results found into kdresults (sorted by brightness), mask via kdmask
* @param x cos(deg2rad*RA)*cos(deg2rad*DEC)
* @param y sin(deg2rad*RA)*cos(deg2rad*DEC)
* @param z sin(deg2rad*DEC)
* @param r search distance (pixels)
* @param min_flux minimum pixel brightness
* @param min start of bounding box
* @param max end of bounding box
* @param dim start dimension
*/
void kdsearch(const float x, const float y, const float z, const float r, const float min_flux, const int min, const int max, const int dim) {
kdsort();
float r_deg=r/3600.0;
float r_rad=r_deg*PI/180.0;
if (dim==0) kdsearch_x(x, y, z, 2*fabs(sin(r_rad/2.0)), min_flux,min,max);
else if (dim==1) kdsearch_y(x, y, z, 2*fabs(sin(r_rad/2.0)), min_flux,min,max);
else if (dim==2) kdsearch_z(x, y, z, 2*fabs(sin(r_rad/2.0)), min_flux,min,max);
}
void kdsearch(float x, float y, float z, float r, float min_flux) {
kdsearch(x, y, z, r, min_flux,0,stars->size(),0);
}
//use seperate functions for each diminsion so that the compiler can unroll the recursion
#define KDSEARCH_NEXT(A,B,C,D)\
int mid=(min+max)/2;\
if (min<mid &&A <= map[mid].B) {\
if (mid-min>KDBUCKET_SIZE) D(x,y,z,r,min_flux,min,mid);\
else for (int i=min;i<mid&&min_flux<=map[i].flux;i++)kdcheck(i,x,y,z,r,min_flux);\
}\
if (mid<max) kdcheck(mid,x,y,z,r,min_flux);\
if (kdresults_size==kdresults_maxsize) min_flux=map[kdresults[kdresults_size-1]].flux;\
if (mid+1<max &&map[mid].B <= C) {\
if (max-(mid+1)>KDBUCKET_SIZE) D(x,y,z,r,min_flux,mid+1,max);\
else for (int i=mid+1;i<max&&min_flux<=map[i].flux;i++)kdcheck(i,x,y,z,r,min_flux);\
}
void kdsearch_x(const float x, const float y, const float z, const float r, float min_flux, const int min, const int max) {KDSEARCH_NEXT(x-r,x,x+r,kdsearch_y)}
void kdsearch_y(const float x, const float y, const float z, const float r, float min_flux, const int min, const int max) {KDSEARCH_NEXT(y-r,y,y+r,kdsearch_z)}
void kdsearch_z(const float x, const float y, const float z, const float r, float min_flux, const int min, const int max) {KDSEARCH_NEXT(z-r,z,z+r,kdsearch_x)}
#undef KDSEARCH_NEXT
/**
* @brief set mask for stars that are too bright,too close, highly variable, or unreliable
*/
void kdmask_filter_catalog() {
for (size_t i=0;i<stars->size();i++) {
int8_t lastmask=kdmask[i];
kdsearch(map[i].x,map[i].y,map[i].z,DOUBLE_STAR_PX*PIXSCALE,THRESH_FACTOR*IMAGE_VARIANCE);
//TODO: this seems to remove more stars than it should
//if (kdresults_size>1||lastmask || map[i].flux<THRESH_FACTOR*IMAGE_VARIANCE||map[i].unreliable>0) {
if (kdresults_size>1||lastmask || map[i].flux<THRESH_FACTOR*IMAGE_VARIANCE) {
kdmask[i]=1;
kdresults_size=0;
} else {
clear_kdresults();
}
}
}
/**
* @brief Masks the dimmest stars in each area to produce a map with uniform density
* @param min_stars_per_fov Don't mask anything which could result in less than this many stars per field of view
*/
void kdmask_uniform_density(const int min_stars_per_fov) {
std::unordered_set<int> uniform_set;
int kdresults_maxsize_old=kdresults_maxsize;
kdresults_maxsize=min_stars_per_fov;
for (size_t i=0;i<stars->size();i++) if (kdmask[i]==0) {
kdsearch(map[i].x,map[i].y,map[i].z,MINFOV/2,THRESH_FACTOR*IMAGE_VARIANCE);
for (size_t j=0;j<kdresults_size;j++) uniform_set.insert(kdresults[j]);
clear_kdresults();
}
for (size_t i=0;i<stars->size();i++) kdmask[i]=1;
std::unordered_set<int>::iterator it = uniform_set.begin();
for (size_t i=0; i<uniform_set.size();i++,it++) kdmask[*it]=0;
kdresults_maxsize=kdresults_maxsize_old;
}
/**
* @brief Filter stardb based on mask
* @return A new stardb containing only the stars which are not masked
*/
star_db* from_kdmask() {
star_db* rd=new star_db;
rd->max_variance=stars->max_variance;
for (size_t i=0;i<stars->size();i++){
if (kdmask[i]==0) *rd+=map[i];
}
return rd;
}
/**
* @brief TODO
* @return
*/
star_db* from_kdresults() {
star_db* rd=new star_db;
rd->max_variance=stars->max_variance;
for (size_t i=0;i<kdresults_size;i++){
*rd+=map[kdresults[i]];
}
return rd;
}
void DBG_(const char *s) {
DBG_PRINT("%s\n",s);
DBG_PRINT("kdsorted=%d\n",kdsorted);
DBG_PRINT("kdmask at %lu\n",(size_t)kdmask);
DBG_PRINT("kdresults at %lu\n",(size_t)kdresults);
DBG_PRINT("kdresults_size=%lu\n",kdresults_size);
DBG_PRINT("kdresults_maxsize=%lu\n",kdresults_maxsize);
if (kdresults_size>0){
int i=0;
DBG_PRINT("kdmask[%d]=%d\n",i,kdmask[i]);
DBG_PRINT("kdresults[%d]=%lu\n",i,kdresults[i]);
map[kdresults[i]].DBG_("STARS");
DBG_PRINT(".\n.\n");
i=kdresults_size-1;
DBG_PRINT("kdmask[%d]=%d\n",i,kdmask[i]);
DBG_PRINT("kdresults[%d]=%lu\n",i,kdresults[i]);
map[kdresults[i]].DBG_("STARS");
}
}
};
#endif
================================================
FILE: build_production.sh
================================================
#!/bin/sh
[ "$1" == "" ] && exit
cd beast
./go&&
cd ..&&
mkdir startracker-production&&
cp -r beast/ startracker-production/&&
cp tests/$1/calibration.txt startracker-production&&
cp tests/$1/median_image.png startracker-production&&
cp hip_main.dat startracker-production&&
cp startracker.py startracker-production/&&
touch startracker-production.tgz&&
rm startracker-production.tgz &&
rsync -av startracker-production/ root@192.168.100.213:~/startracker-production/ &&
rm -rf startracker-production
================================================
FILE: doc/gen_interleave.py
================================================
from __future__ import print_function
import random
#This script is based on
#https://stackoverflow.com/questions/1024754/how-to-compute-a-3d-morton-number-interleave-the-bits-of-3-ints
def prettyBinString(x,d=32,steps=4,sep=".",emptyChar="0"):
b = bin(x)[2:]
zeros = d - len(b)
if zeros <= 0:
zeros = 0
k = steps - (len(b) % steps)
else:
k = steps - (d % steps)
s = ""
#print("zeros" , zeros)
#print("k" , k)
for i in list(range(zeros)):
#print("k:",k)
if(k%steps==0 and i!= 0):
s+=sep
s += emptyChar
k+=1
for i in list(range(len(b))):
if( (k%steps==0 and i!=0 and zeros == 0) or (k%steps==0 and zeros != 0) ):
s+=sep
s += b[i]
k+=1
return s
def binStr(x): return prettyBinString(x,32,4," ","0")
def computeBitMaskPatternAndCode(numberOfBits, numberOfEmptyBits):
bitDistances=[ i*numberOfEmptyBits for i in list(range(numberOfBits)) ]
print("Bit Distances: " + str(bitDistances))
bitDistancesB = [bin(dist)[2:] for dist in bitDistances]
print("Bit Distances (binary): " + str(bitDistancesB))
moveBits=[]
maxLength = len(max(bitDistancesB, key=len))
abort = False
for i in list(range(maxLength)):
moveBits.append([])
for idx,bits in enumerate(bitDistancesB):
if not len(bits) - 1 < i:
if(bits[len(bits)-i-1] == "1"):
moveBits[i].append(idx)
for i in list(range(len(moveBits))):
print("Shifting bits by " + str(2**i) + "\t for bits idx: " + str(moveBits[i]))
bitPositions = list(range(numberOfBits));
print("BitPositions: " + str(bitPositions))
maskOld = (1 << numberOfBits) -1
codeString = "x &= " + hex(maskOld) + "\n"
for idx in list(range(len(moveBits)-1, -1, -1)):
if len(moveBits[idx]):
shifted = 0
for bitIdxToMove in moveBits[idx]:
shifted |= 1<<bitPositions[bitIdxToMove];
bitPositions[bitIdxToMove] += 2**idx; # keep track where the actual bit stands! might get moved several times
# Get the non shifted part!
nonshifted = ~shifted & maskOld
print("Shifted bef.:\t" + binStr(shifted) + " hex: " + hex(shifted))
shifted = shifted << 2**idx
print("Shifted:\t" + binStr(shifted)+ " hex: " + hex(shifted))
print("NonShifted:\t" + binStr(nonshifted) + " hex: " + hex(nonshifted))
maskNew = shifted | nonshifted
print("Bitmask is now:\t" + binStr(maskNew) + " hex: " + hex(maskNew) +"\n")
#print("Code: " + "x = x | x << " +str(2**idx)+ " & " +hex(maskNew))
codeString += "x = (x | x << " +str(2**idx)+ ") & " +hex(maskNew) + "\n"
maskOld = maskNew
return codeString
kdhash_size=4
numberOfBits = int(64/kdhash_size);
numberOfEmptyBits = kdhash_size-1;
codeString = computeBitMaskPatternAndCode(numberOfBits,numberOfEmptyBits);
print(codeString)
def partitionBy2(x):
exec(codeString)
return x
def checkPartition(x):
print("Check partition for: \t" + binStr(x))
part = partitionBy2(x);
print("Partition is : \t\t" + binStr(part))
#make the pattern manualy
partC = long(0);
for bitIdx in range(numberOfBits):
partC = partC | (x & (1<<bitIdx)) << numberOfEmptyBits*bitIdx
print("Partition check is :\t" + binStr(partC))
if(partC == part):
return True
else:
return False
checkError = False
for i in list(range(20)):
x = random.getrandbits(numberOfBits);
if(checkPartition(x) == False):
checkError = True
break
if not checkError:
print("CHECK PARTITION SUCCESSFUL!!!!!!!!!!!!!!!!...")
else:
print("checkPartition has ERROR!!!!")
================================================
FILE: doc/ost_comm_test.c
================================================
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#define BUFFER_SIZE 1024
#define MAX_STARS 50
/* Coordinates of a star in both camera and ECI frames, and its weight */
typedef struct {
double cam_x;
double cam_y;
double cam_z;
double eci_x;
double eci_y;
double eci_z;
double weight;
} star_t;
/* sendImageCommand:
* This function establishes a TCP connection to a server, sends an image command,
* and receives a response from the server.
*
* Input arguments:
* - server_ip: IP address of the server.
* - server_port: Port number of the server.
* - command: Image command to send to the server.
* - output_buffer: Starer to the output buffer where the response will be stored.
* - max_output_size: Maximum size of the output buffer to prevent buffer overflow.
*
* Output arguments:
* - output_buffer: The response from the server will be stored in this buffer.
*
* Return value:
* - If the function succeeds, it returns the number of bytes received and stored in the output buffer.
* - If an error occurs, it returns -1.
*/
int sendImageCommand(const char* server_ip, int server_port, const char* command, char* output_buffer, int max_output_size) {
int sockfd;
struct sockaddr_in server_addr;
// Create socket
if ((sockfd = socket(AF_INET, SOCK_STREAM, 0)) == -1) {
perror("Socket creation failed");
return -1;
}
// Fill server information
server_addr.sin_family = AF_INET;
server_addr.sin_port = htons(server_port);
server_addr.sin_addr.s_addr = inet_addr(server_ip);
// Connect to the server
if (connect(sockfd, (struct sockaddr *)&server_addr, sizeof(server_addr)) != 0) {
perror("Connection to server failed");
close(sockfd);
return -1;
}
// Send the image command to the server
if (send(sockfd, command, strlen(command), 0) == -1) {
perror("Send failed");
close(sockfd);
return -1;
}
// Receive response from the server
int bytes_received = recv(sockfd, output_buffer, max_output_size - 1, 0);
if (bytes_received == -1) {
perror("Receive failed");
close(sockfd);
return -1;
}
output_buffer[bytes_received] = '\0'; // Null-terminate the received data
// Close the socket
close(sockfd);
// Return the number of bytes received
return bytes_received;
}
/* parse_ost_string:
* Parses a openstartracker string into an array of star structures.
*
* Input arguments:
* - ost_str: The openstartracker string to parse.
* Example (2 stars): "1.0,2.0,3.0,4.0,5.0,6.0,7.0 2.0,3.0,4.0,5.0,6.0,7.0,8.0"
* - max_num_stars: The maximum number of stars to parse.
* If the openstartracker string contains more stars than max_num_stars, only the first max_num_stars will be parsed.
*
* Output arguments:
* - stars: The parsed stars will be stored in this array.
* The array must be pre-allocated by the caller.
* The array must have at least max_num_stars elements.
* If the openstartracker string contains fewer stars than max_num_stars, the remaining elements will be left unchanged.
*
* Return value:
* - The number of stars successfully parsed from the openstartracker string.
*/
int parse_ost_string(const char *ost_str, int max_num_stars, star_t *stars) {
char *ptr = (char *)ost_str;
int i = 0;
for (; i < max_num_stars; i++) {
// Parse the openstartracker string into a star structure
int n = sscanf(ptr, "%lf,%lf,%lf,%lf,%lf,%lf,%lf", &stars[i].cam_x, &stars[i].cam_y, &stars[i].cam_z, &stars[i].eci_x, &stars[i].eci_y, &stars[i].eci_z, &stars[i].weight);
if (n != 7) {
break;
}
// Move the pointer to the next star
ptr = strchr(ptr, ' ');
if (ptr == NULL) {
break;
}
// Skip the space character
ptr++;
}
return i;
}
star_t stars[MAX_STARS];
int main() {
const char *server_ip = "127.0.0.1"; // IP address of the server
int server_port = 8010; // Port number the server is listening on
int max_num_stars = MAX_STARS; // Maximum number of stars to parse
// Send the image command to the server
char output_buffer[BUFFER_SIZE];
int bytes_received = sendImageCommand(server_ip, server_port, "rgb.solve_image('science_cam_may8_0.05sec_gain40/samples/img0.png')", output_buffer, BUFFER_SIZE);
if (bytes_received == -1) {
return 1;
}
// Parse the openstartracker string into an array of star structures
int num_stars = parse_ost_string(output_buffer, max_num_stars, stars);
if (num_stars == 0) {
printf("No stars found\n");
return 1;
}
// Print the stars
for (int i = 0; i < num_stars; i++) {
printf("Star %d: cam=(%f, %f, %f), eci=(%f, %f, %f), weight=%f\n", i, stars[i].cam_x, stars[i].cam_y, stars[i].cam_z, stars[i].eci_x, stars[i].eci_y, stars[i].eci_z, stars[i].weight);
}
return 0;
}
================================================
FILE: doc/viz_q.m
================================================
%Extract the X, Y and Z coordinates
%M=vertcat(sqrt(.5)*[1 0 0;-1 0 0;0 1 0;0 -1 0;0 0 1;0 0 -1],sqrt(1/3)*[1 1 0;1 -1 0;-1 1 0;-1 -1 0;1 0 1;1 0 -1;-1 0 1;-1 0 -1;0 1 1;0 1 -1;0 -1 1;0 -1 -1],[.5 .5 .5;.5 .5 -.5;.5 -.5 .5;.5 -.5 -.5;-.5 .5 .5;-.5 .5 -.5;-.5 -.5 .5;-.5 -.5 -.5]);
sz=100;
[x,y,z]=sphere(sz);
M=[x(:),y(:),z(:)];
M=normr(horzcat(M,max(abs(M),[],2)));
%trisurf(delaunay(M(:,1:3)),M(:,1),M(:,2),M(:,3))
%surf(reshape(x(:),[sz+1,sz+1]),reshape(y(:),[sz+1,sz+1]),reshape(z(:),[sz+1,sz+1]))
surf(reshape(M(:,1),[sz+1,sz+1]),reshape(M(:,2),[sz+1,sz+1]),reshape(M(:,3),[sz+1,sz+1]))
pbaspect([1 1 1])
================================================
FILE: setup.sh
================================================
#!/bin/bash
# requires docker to be installed
# build the Dockerfile to include the current director and have internet access
docker build --network=host -t startracker1 .
# directory of this setup.sh script
DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )"
# Make an alias to start the docker environment
# in interactive mode
# in the proper directory
alias dstart='docker run -it -v '$DIR'/:/home startracker1'
================================================
FILE: starsToStruc.py
================================================
import ctypes
import socket
from io import StringIO, BytesIO
class stars_to_struct():
fields = [("stars", ctypes.c_int),
("declination", ctypes.c_float),
("right_ascension", ctypes.c_float),
("body_x", ctypes.c_float*"stars"),
("body_y", ctypes.c_float*"stars"),
("body_z", ctypes.c_float*"stars"),
("ref_x", ctypes.c_float*"stars"),
("ref_y", ctypes.c_float*"stars"),
("ref_z", ctypes.c_float*"stars"),
("uncertainty", ctypes.c_float*"stars")]
def _init_(self):
super(stars_to_struct, self)._init_()
self.stars = 0
self.declination = 0.0
self.right_ascension = 0.0
self.body_x = [0.0]*self.stars
self.body_y = [0.0]*self.stars
self.body_z = [0.0]*self.stars
self.ref_x = [0.0]*self.stars
self.ref_y = [0.0]*self.stars
self.ref_z = [0.0]*self.stars
self.uncertainty = [0.0]*self.stars
def load_image(self, stars, declination, right_ascension, body_x, body_y, body_z, ref_x, ref_y, ref_z, uncertainty):
self.stars = stars
self.declination = declination
self.right_ascension = right_ascension
self.body_x = body_x
self.body_y = body_y
self.body_z = body_z
self.ref_x = ref_x
self.ref_y = ref_y
self.ref_z = ref_z
self.uncertainty = uncertainty
================================================
FILE: startracker.py
================================================
from __future__ import print_function
from time import time
import sys, traceback
import socket,select, os, gc
import cv2
import numpy as np
import numpy.linalg as LA
from io import StringIO,BytesIO
import fcntl
import beast
from systemd import daemon
P_MATCH_THRESH=0.99
SIMULATE=0
if 'WATCHDOG_USEC' not in os.environ:
os.environ['WATCHDOG_USEC']="30000000"
def trace(frame, event, arg):
print("%s, %s:%d" % (event, frame.f_code.co_filename, frame.f_lineno), file=sys.stderr)
return trace
#sys.settrace(trace)
CONFIGFILE=sys.argv[1]
YEAR=float(sys.argv[2])
#set up server before we do anything else
server=socket.socket(socket.AF_INET, socket.SOCK_STREAM)
server.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
try:
server.bind(('127.0.0.1', 8010))
except:
print("server socket already open: try terminal command: sudo kill $(sudo lsof -t -i:8010)")
exit()
server.listen(5)
server.setblocking(0)
print ("Loading config" )
print (CONFIGFILE)
beast.load_config(CONFIGFILE)
print ("Loading hip_main.dat" )
S_DB=beast.star_db()
S_DB.load_catalog("hip_main.dat",YEAR)
print ("Filtering stars" )
SQ_RESULTS=beast.star_query(S_DB)
SQ_RESULTS.kdmask_filter_catalog()
SQ_RESULTS.kdmask_uniform_density(beast.cvar.REQUIRED_STARS)
S_FILTERED=SQ_RESULTS.from_kdmask()
print ("Generating DB" )
C_DB=beast.constellation_db(S_FILTERED,2+beast.cvar.DB_REDUNDANCY,0)
print ("Ready")
def a2q(A):
q4=0.5*np.sqrt(1+np.trace(A));
q1=1/(4*q4)*(A[1,2]-A[2,1]);
q2=1/(4*q4)*(A[2,0]-A[0,2]);
q3=1/(4*q4)*(A[0,1]-A[1,0]);
return np.array([q1,q2,q3,q4])
def q2a(q):
q=q/LA.norm(q)
return np.array([[q[0]**2-q[1]**2-q[2]**2+q[3]**2,2*(q[0]*q[1]+q[2]*q[3]),2*(q[0]*q[2]-q[1]*q[3])],[2*(q[0]*q[1]-q[2]*q[3]),-q[0]**2+q[1]**2-q[2]**2+q[3]**2,2*(q[1]*q[2]+q[0]*q[3])],[2*(q[0]*q[2]+q[1]*q[3]),2*(q[1]*q[2]-q[0]*q[3]),-q[0]**2-q[1]**2+q[2]**2+q[3]**2]])
#A=prev_body2ECI
#B=curr_body2ECI
#t1=prev_updatetime
#t2=curr_updatetime
#t3=present_time
def extrapolate_matrix(A,B,t1,t2,t3):
# Calculate error angles between A and B via small angle approximation
# of MRPs.
R=np.dot(B,np.transpose(A))
dq=a2q(R)
dp=np.array([dq[0],dq[1],dq[2]])/(1 + dq[3])
anglesAB=4*dp
# Extrapolate to new error angles between B and C.
anglesBC=anglesAB/(t2-t1)*(t3-t2)
# Convert to a quaternion via small angle approximation, then get C.
#C=np.dot(q2a(np.array([0.5*anglesBC[0],0.5*anglesBC[1],0.5*anglesBC[2],1])),B)
C=q2a(np.array([0.5*anglesBC[0],0.5*anglesBC[1],0.5*anglesBC[2],1]))
return (C,(1000000.0)*anglesAB/(t2-t1))
#Note: SWIG's policy is to garbage collect objects created with
#constructors, but not objects created by returning from a function
def wahba(A, B, weight=[]):
"""
Takes in two matrices of points and finds the attitude matrix needed to
transform one onto the other
Input:
A: nx3 matrix - x,y,z in body frame
B: nx3 matrix - x,y,z in eci
Note: the "n" dimension of both matrices must match
Output:
attitude_matrix: returned as a numpy matrix
"""
assert len(A) == len(B)
if (len(weight) == 0):
weight=np.array([1]*len(A))
# dot is matrix multiplication for array
H = np.dot(np.transpose(A)*weight,B)
#calculate attitude matrix
#from http://malcolmdshuster.com/FC_MarkleyMortari_Girdwood_1999_AAS.pdf
U, S, Vt = LA.svd(H)
flip=LA.det(U)*LA.det(Vt)
#S=np.diag([1,1,flip]); U=np.dot(U,S)
U[:,2]*=flip
body2ECI = np.dot(U,Vt)
return body2ECI
def print_ori(body2ECI):
#DEC=np.degrees(np.arcsin(body2ECI[2,0]))
##rotation about the z axis (-180 to +180)
#RA=np.degrees(np.arctan2(body2ECI[1,0],body2ECI[0,0]))
##rotation about the camera axis (-180 to +180)
#ORIENTATION=np.degrees(-np.arctan2(body2ECI[1,2],body2ECI[2,2]))
DEC=np.degrees(np.arcsin(body2ECI[0,2]))
RA=np.degrees(np.arctan2(body2ECI[0,1],body2ECI[0,0]))
ORIENTATION=np.degrees(-np.arctan2(body2ECI[1,2],body2ECI[2,2]))
if ORIENTATION>180:
ORIENTATION=ORIENTATION-360
#rotation about the y axis (-90 to +90)
print ("DEC="+str(DEC), file=sys.stderr)
#rotation about the z axis (-180 to +180)
print ("RA="+str(RA), file=sys.stderr)
#rotation about the camera axis (-180 to +180)
print ("ORIENTATION="+str(ORIENTATION), file=sys.stderr)
class star_image:
def __init__(self, imagefile,median_image):
b_conf=[time(),beast.cvar.PIXSCALE,beast.cvar.BASE_FLUX]
self.img_stars = beast.star_db()
self.img_data = []
self.match=None
self.db_stars=None
self.match_from_lm=None
self.db_stars_from_lm=None
#Placeholders so that these don't get garbage collected by SWIG
self.fov_db=None
self.const_from_lm=None
#TODO: improve memory efficiency
if "://" in imagefile:
import urllib
img=cv2.imdecode(np.asarray(bytearray(urllib.urlopen(imagefile).read()), dtype="uint8"), cv2.IMREAD_COLOR)
else:
img=cv2.imread(imagefile)
if img is None:
print ("Invalid image, using blank dummy image", file=sys.stderr)
img=median_image
img=np.clip(img.astype(np.int16)-median_image,a_min=0,a_max=255).astype(np.uint8)
img_grey = cv2.cvtColor(img,cv2.COLOR_RGB2GRAY)
#removes areas of the image that don't meet our brightness threshold
ret,thresh = cv2.threshold(img_grey,beast.cvar.THRESH_FACTOR*beast.cvar.IMAGE_VARIANCE,255,cv2.THRESH_BINARY)
contours,heirachy = cv2.findContours(thresh,1,2);
for c in contours:
M = cv2.moments(c)
if M['m00']>0:
#this is how the x and y position are defined by cv2
cx = M['m10']/M['m00']
cy = M['m01']/M['m00']
#see https://alyssaq.github.io/2015/computing-the-axes-or-orientation-of-a-blob/
#for how to convert these into eigenvectors/values
u20 = M["m20"]/M["m00"] - cx**2
u02 = M["m02"]/M["m00"] - cy**2
u11 = M["m11"]/M["m00"] - cx*cy
#the center pixel is used as the approximation of the brightest pixel
self.img_stars+=beast.star(cx-beast.cvar.IMG_X/2.0,(cy-beast.cvar.IMG_Y/2.0),float(cv2.getRectSubPix(img_grey,(1,1),(cx,cy))[0,0]),-1)
self.img_data.append(b_conf+[cx,cy,u20,u02,u11]+cv2.getRectSubPix(img,(1,1),(cx,cy))[0,0].tolist())
def match_near(self,x,y,z,r):
SQ_RESULTS.kdsearch(x,y,z,r,beast.cvar.THRESH_FACTOR*beast.cvar.IMAGE_VARIANCE)
#estimate density for constellation generation
C_DB.results.kdsearch(x,y,z,r,beast.cvar.THRESH_FACTOR*beast.cvar.IMAGE_VARIANCE)
fov_stars=SQ_RESULTS.from_kdresults()#REE
self.fov_db = beast.constellation_db(fov_stars,C_DB.results.r_size(),1)
C_DB.results.clear_kdresults()
SQ_RESULTS.clear_kdresults()
img_const=beast.constellation_db(self.img_stars,beast.cvar.MAX_FALSE_STARS+2,1)
near = beast.db_match(self.fov_db,img_const)
if near.p_match>P_MATCH_THRESH:
self.match = near
self.db_stars = near.winner.from_match()
def match_lis(self):
#for the first pass, we only want to use the brightest MAX_FALSE_STARS+REQUIRED_STARS
img_stars_n_brightest = self.img_stars.copy_n_brightest(beast.cvar.MAX_FALSE_STARS+beast.cvar.REQUIRED_STARS)
img_const_n_brightest = beast.constellation_db(img_stars_n_brightest,beast.cvar.MAX_FALSE_STARS+2,1)
lis=beast.db_match(C_DB,img_const_n_brightest)
#TODO: uncomment once p_match is fixed
#if lis.p_match>P_MATCH_THRESH:
if lis.p_match>P_MATCH_THRESH and lis.winner.size()>=beast.cvar.REQUIRED_STARS:
x=lis.winner.R11
y=lis.winner.R21
z=lis.winner.R31
self.match_near(x,y,z,beast.cvar.MAXFOV/2)
#self.match = lis
#self.db_stars = lis.winner.from_match()
def match_rel(self,last_match):
#make copy of stars from lastmatch
img_stars_from_lm=last_match.img_stars.copy()
w=last_match.match.winner
#convert the stars to ECI
for i in range(img_stars_from_lm.size()):
s=img_stars_from_lm.get_star(i)
x=s.x*w.R11+s.y*w.R12+s.z*w.R13
y=s.x*w.R21+s.y*w.R22+s.z*w.R23
z=s.x*w.R31+s.y*w.R32+s.z*w.R33
s.x=x
s.y=y
s.z=z
#create constellation from last match
self.const_from_lm=beast.constellation_db(img_stars_from_lm,beast.cvar.MAX_FALSE_STARS+2,1)
#match between last and current
img_const=beast.constellation_db(self.img_stars,beast.cvar.MAX_FALSE_STARS+2,1)
rel=beast.db_match(self.const_from_lm,img_const)
if rel.p_match>P_MATCH_THRESH:
self.match_from_lm = rel
self.db_stars_from_lm = rel.winner.from_match()
def print_match(self,bodyCorrection=None,angrate_string=""):
if bodyCorrection is None:
bodyCorrection=np.eye(3)
if self.match is not None:
self.match.winner.print_ori()
db=self.db_stars
im=self.img_stars
if db is None:
if self.db_stars_from_lm is None:
#neither relative nor absolute matching could be used
print("")
return
else:
db=self.db_stars_from_lm
assert(db.size()==im.size())
star_out=[]
for i in range(db.size()):
s_im=im.get_star(i)
s_db=db.get_star(i)
if (s_db.id>=0):
weight=1.0/(s_db.sigma_sq+s_im.sigma_sq)
temp=np.dot(bodyCorrection, np.array([[s_im.x],[s_im.y],[s_im.z]]))
star_out.append(str(temp[0,0])+','+str(temp[1,0])+','+str(temp[2,0])+','+str(s_db.x)+','+str(s_db.y)+','+str(s_db.z)+','+str(weight))
print ("stars",len(star_out), file=sys.stderr)
print ("ang_rate: "+angrate_string, file=sys.stderr)
print (" ".join(star_out)+" "+angrate_string)
NONSTARS={}
NONSTAR_NEXT_ID=0
NONSTAR_DATAFILENAME="/dev/null"
#NONSTAR_DATAFILENAME="data"+str(time())+".txt"
NONSTAR_DATAFILE=open(NONSTAR_DATAFILENAME,"w")
class nonstar:
def __init__(self,current_image,i,source):
global NONSTARS,NONSTAR_NEXT_ID,NONSTAR_DATAFILENAME,NONSTAR_DATAFILE
self.id=NONSTAR_NEXT_ID
NONSTARS[self.id]=self
current_image.img_stars.get_star(i).id=self.id
NONSTAR_NEXT_ID+=1
self.data=[]
self.add_data(current_image,i,source)
def add_data(self,current_image,i,source):
s_im=current_image.img_stars.get_star(i)
s_db_x=0.0
s_db_y=0.0
s_db_z=0.0
w=None
if (current_image.match != None and current_image.match.p_match>P_MATCH_THRESH):
w=current_image.match.winner
elif (current_image.match != None and current_image.match.p_match>P_MATCH_THRESH):
w=current_image.match_from_lm.winner
if w != None:
#convert the stars to ECI
s_db_x=s_im.x*w.R11+s_im.y*w.R12+s_im.z*w.R13
s_db_y=s_im.x*w.R21+s_im.y*w.R22+s_im.z*w.R23
s_db_z=s_im.x*w.R31+s_im.y*w.R32+s_im.z*w.R33
self.data.append([source,s_im.x,s_im.y,s_im.z,s_db_x,s_db_y,s_db_z]+current_image.img_data[i])
def write_data(self,fd):
if sys.version_info[0]>2:
os.write(fd,bytes(str(self.id)+" " +str(len(self.data))+"\n",encoding='UTF-8'))
else:
os.write(fd,str(self.id)+" " +str(len(self.data))+"\n")
for i in self.data:
s=[str(j) for j in i]
if sys.version_info[0]>2:
os.write(fd,bytes(" ".join(s)+"\n",encoding='UTF-8'))
else:
os.write(fd," ".join(s)+"\n")
def __del__(self):
self.write_data(NONSTAR_DATAFILE.fileno())
def flush_nonstars():
global NONSTARS,NONSTAR_NEXT_ID,NONSTAR_DATAFILENAME,NONSTAR_DATAFILE
NONSTARS={}
NONSTAR_NEXT_ID=0
gc.collect()
NONSTAR_DATAFILE.close()
NONSTAR_DATAFILENAME="data"+str(time())+".txt"
NONSTAR_DATAFILE=open(NONSTAR_DATAFILENAME,"w")
def update_nonstars(current_image,source):
global NONSTARS,NONSTAR_NEXT_ID
nonstars_next={}
im=current_image.img_stars
db=current_image.db_stars
db_lm=current_image.db_stars_from_lm
if (db!=None):
assert(db.size()==im.size())
if (db_lm!=None):
assert(db_lm.size()==im.size())
for i in range(im.size()):
im.get_star(i).id=db_lm.get_star(i).id
for i in range(im.size()):
s_im=im.get_star(i)
#is this a star? if so remove from nonstars
if (db != None and db.get_star(i).id>=0):
if (s_im.id in NONSTARS):
del NONSTARS[s_im.id]
s_im.id=-1
#if it's already there, add the latest mesurement
elif (s_im.id in NONSTARS):
NONSTARS[s_im.id].add_data(current_image,i,source)
nonstars_next[s_im.id]=NONSTARS[s_im.id]
#otherwise add a new nonstar
else:
ns=nonstar(current_image,i,source)
nonstars_next[ns.id]=ns
NONSTARS=nonstars_next
#wrap around to prevent integer overflow
if (NONSTAR_NEXT_ID>2**30):
flush_nonstars()
def winner_attitude(w):
#w=self.last_match.match.winner
eci2body=np.array([[1,0,0],[0,1,0],[0,0,1]],dtype=float)
eci2body[0,0]=w.R11
eci2body[0,1]=w.R12
eci2body[0,2]=w.R13
eci2body[1,0]=w.R21
eci2body[1,1]=w.R22
eci2body[1,2]=w.R23
eci2body[2,0]=w.R31
eci2body[2,1]=w.R32
eci2body[2,2]=w.R33
return np.transpose(eci2body)
class star_camera:
def __init__(self, median_file,source="RGB"):
self.source=source
self.current_image=None
self.last_match=None
self.median_image=cv2.imread(median_file)
def solve_image(self,imagefile,lis=1,quiet=0):
starttime=time()
if (SIMULATE==1 and quiet==0):
s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
s.connect(("jeb",7011))
data = s.recv(2048)
s.close()
print("Time1: "+str(time() - starttime), file=sys.stderr)
self.current_image=star_image(imagefile,self.median_image)
print("Time2: "+str(time() - starttime), file=sys.stderr)
if (lis==1):
self.current_image.match_lis()
print("Time3: "+str(time() - starttime), file=sys.stderr)
if self.last_match is not None:
self.current_image.match_rel(self.last_match)
if (quiet==0):
if (SIMULATE==1):
print (data.rstrip("\n").rstrip("\r"))
else:
self.current_image.print_match()
print("Time4: "+str(time() - starttime), file=sys.stderr)
update_nonstars(self.current_image,self.source)
print("Time5: "+str(time() - starttime), file=sys.stderr)
if self.current_image.match is not None:
self.last_match=self.current_image
else:
self.last_match=None
print("Time6: "+str(time() - starttime), file=sys.stderr)
def extrapolate_image(self,imagefile1,imagefile2,time1,time2):
#self.solve_image(imagefile2,lis=1,quiet=0)
self.solve_image(imagefile1,lis=1,quiet=1)
print(1, file=sys.stderr)
if (self.last_match is None):
print(2, file=sys.stderr)
print ("")
return
a1=winner_attitude(self.last_match.match.winner)
self.solve_image(imagefile2,lis=1,quiet=1)
print(3, file=sys.stderr)
if (self.last_match is None):
print(4, file=sys.stderr)
print ("")
return
a2=winner_attitude(self.last_match.match.winner)
print(a1,a2,LA.svd(a1)[1],LA.svd(a1)[1], file=sys.stderr)
a,angrate=extrapolate_matrix(a1,a2,time1,time2,time()*1e6)
print(a,LA.svd(a)[1], file=sys.stderr)
self.last_match.print_match(a,",".join([str(i) for i in angrate.tolist()]))
#dummy for now
#TODO: add science data from IR cam
class science_camera:
def __init__(self, median_file,source="IR"):
self.source=source
self.current_image=None
self.last_match=None
self.median_image=cv2.imread(median_file)
def solve_image(self,imagefile):
if sys.version_info[0]>2:
os.write(1,bytes(os.path.abspath(NONSTAR_DATAFILENAME),encoding='UTF-8'))
else:
os.write(1,os.path.abspath(NONSTAR_DATAFILENAME))
rgb=star_camera(sys.argv[3])
ir=science_camera(sys.argv[3])
CONNECTIONS = {}
class connection:
"""Tracks activity on a file descriptor and allows TCP read/writes"""
def __init__(self, conn, epoll):
"""
Create connection to track file descriptor activity
@note: Adds C{fd . self} to C{CONNECTIONS}
@param conn: Any file object with the fileno() method
@param epoll: File descriptor edge polling object
"""
self.conn=conn
self.fd = self.conn.fileno()
epoll.register(self.fd, select.EPOLLIN)
self.epoll = epoll
CONNECTIONS[self.fd] = self
def read(self):
"""
Complete non-blocking read on file descriptor
of an arbitrary amount of data
@return: Entire read string
@rtype: C{string}
"""
# need nonblocking for read
fl = fcntl.fcntl(self.fd, fcntl.F_GETFL)
fcntl.fcntl(self.fd, fcntl.F_SETFL, fl | os.O_NONBLOCK)
data = b''
try:
while True:
lastlen=len(data)
data += os.read(self.fd, 1024)
if len(data)==lastlen:
break
except OSError as e:
# error 11 means we have no more data to read
if e.errno == 11:
pass
elif e.errno == 104:
print("WARNING: ABNORMAL DISCONNECT", file=sys.stderr)
else:
raise
return data
def write(self, data):
"""
Blocking read on file descriptor
@param data: ASCII data to write
@type data: C{string}
"""
if len(data) == 0: return
if self.fd==0: #stdin
if sys.version_info[0]>2:
os.write(1, bytes(data,encoding='UTF-8'))
else:
os.write(1, data)
return
# need blocking IO for writing
fl = fcntl.fcntl(self.fd, fcntl.F_GETFL)
fcntl.fcntl(self.fd, fcntl.F_SETFL, fl & ~os.O_NONBLOCK)
if sys.version_info[0]>2:
os.write(self.fd, bytes(data,encoding='UTF-8'))
else:
os.write(self.fd, data)
def close(self):
"""Close connection with file descriptor"""
self.epoll.unregister(self.fd)
self.conn.close()
if CONNECTIONS[self.fd]:
del CONNECTIONS[self.fd]
epoll = select.epoll()
epoll.register(server.fileno(), select.EPOLLIN)
try:
connection(sys.stdin,epoll)
except IOError:
pass
daemon.notify("WATCHDOG=1")
lastPing = time()
while True:
#systemd watchdog
events = epoll.poll(float(os.environ['WATCHDOG_USEC'])/2.0e6 - (time() - lastPing))
if len(events) == 0 or time() >= (lastPing + float(os.environ['WATCHDOG_USEC'])/2.0e6):
daemon.notify("WATCHDOG=1")
lastPing = time()
#events = epoll.poll()
for fd, event_type in events:
# Activity on the master socket means a new connection.
if fd == server.fileno():
conn, addr = server.accept()
connection(conn, epoll)
elif fd in CONNECTIONS:
w = CONNECTIONS[fd]
data = w.read()
print(data.decode(encoding='UTF-8'), file=sys.stderr)
if len(data) > 0:
if sys.version_info[0]>2:
stdout_redir = StringIO()
else:
stdout_redir = BytesIO()
stdout_old = sys.stdout
sys.stdout = stdout_redir
try:
exec(data)
except SystemExit:
w.close()
raise
except:
traceback.print_exc(file=sys.stdout)
sys.stdout = stdout_old
data_out = stdout_redir.getvalue()
print(data_out, file=sys.stderr)
w.write(data_out)
else:
w.close()
================================================
FILE: tests/Makefile
================================================
CC = g++
all: $(OBJ)
$(CC) -std=c++11 -Wall -Ofast -g -pg test.c -o test -lm
================================================
FILE: tests/calibrate.py
================================================
from __future__ import print_function
from os import listdir,system,environ
from os.path import isfile, join
import cv2
import numpy as np
import math
from scipy.stats import poisson
import sys
from astropy.io import fits
from astropy import wcs
from scipy import spatial
## Environment variables:
try: EXPOSURE_TIME = float(environ['EXPOSURE_TIME'])
except KeyError: EXPOSURE_TIME = 0.05 # s
try: APERTURE = float(environ['APERTURE'])
except KeyError: APERTURE = 60.7 # mm
try: DOUBLE_STAR_PX = float(environ['DOUBLE_STAR_PX'])
except KeyError: DOUBLE_STAR_PX = 3.5 #pixels of seperation needed to distinguish stars from each other
try: POS_ERR_SIGMA = float(environ['POS_ERR_SIGMA'])
except KeyError: POS_ERR_SIGMA = 2 #Check all constellations which fall inside these bounds
### Note: Increasing this can actualy reduce the probability of finding a match
### as the true match has to stand out against a larger crowd
### NOTE: all of the following options multiply runtime by (N+2)^2
try: MAX_FALSE_STARS = int(environ['MAX_FALSE_STARS'])
except KeyError: MAX_FALSE_STARS = 2 #maximum number of objects that can be brighter than the two brightest stars
try: DB_REDUNDANCY = int(environ['DB_REDUNDANCY'])
except KeyError: DB_REDUNDANCY = 1 #of the brightest DB_REDUNDANCY+2 stars, we need at least 2
try: REQUIRED_STARS = int(environ['REQUIRED_STARS'])
except KeyError: REQUIRED_STARS = 5 #How many stars should we try to match?
### For ultrawide fov this may be set to 3 for faster matching
### For ultranarrow fov, it may be necessary to set this to 5 (Also send me an email and we'll talk)
### TODO: figure out how big "ultrawide" and "ultranarrow" are
def angles2xyz(ra,dec):
x=np.cos(np.radians(ra))*np.cos(np.radians(dec))
y=np.sin(np.radians(ra))*np.cos(np.radians(dec))
z=np.sin(np.radians(dec))
return list((x,y,z))
#load our star catalog, converting from id,ra,dec to x,y,z,id
def getstardb(year=1991.25,filename="hip_main.dat"):
yeardiff=year-1991.25
stardb={}
starfile = open(filename)
for line in starfile.readlines():
fields=line.split('|')
try:
HIP_ID=int(fields[1]);
MAG=float(fields[5]);
DEC=yeardiff*float(fields[13])/3600000.0 + float(fields[9]);
cosdec=np.cos(np.pi*DEC/180.0);
RA=yeardiff*float(fields[12])/(cosdec*3600000.0) + float(fields[8]);
X=np.cos(np.pi*RA/180.0)*cosdec;
Y=np.sin(np.pi*RA/180.0)*cosdec;
Z=np.sin(np.pi*DEC/180.0);
except ValueError:
continue
try:
f6=int(fields[6])
except ValueError:
f6=0
if (int(fields[29])==0 or int(fields[29])==1) and f6!=3:
UNRELIABLE=0
else:
UNRELIABLE=1
stardb[HIP_ID]=[HIP_ID,MAG,DEC,RA,X,Y,Z,UNRELIABLE]
return stardb
def basename(filename):
if "." in filename:
filename=".".join(filename.split(".")[0:-1])
return filename
#only do this part if we were run as a python script
if __name__ == '__main__':
samplepath=sys.argv[1]+"/samples"
image_names = [ f for f in listdir(samplepath) if isfile(join(samplepath,f)) ]
num_images=len(image_names)
#NOTE: if you get NoneType error, delete non-png files
images = np.asarray([cv2.imread( join(samplepath,image_names[n]) ).astype(float) for n in range(0, num_images)])
median_image=np.median(images,axis=0)
cv2.imwrite(sys.argv[1]+"/median_image.png",median_image)
system("md5sum "+samplepath+"/* >"+sys.argv[1]+"/checksum.txt")
if system("diff -q "+sys.argv[1]+"/checksum.txt "+sys.argv[1]+"/calibration_data/checksum.txt")!=0:
print ("Clearing old calibration data:")
system("rm -rfv "+sys.argv[1]+"/calibration_data/* ")
system("mv "+sys.argv[1]+"/checksum.txt "+sys.argv[1]+"/calibration_data/checksum.txt")
stardb=getstardb()
astrometry_results={}
#filter the background image for astrometry - more important for starfield generator
for n in range(0, num_images):
images[n]-=median_image
image_name=sys.argv[1]+"/calibration_data/"+basename(image_names[n])+".png"
img=np.clip(images[n],a_min=0,a_max=255).astype(np.uint8)
cv2.imwrite(image_name,img)
solve_cmd="solve-field --skip-solved --cpulimit 60 "+image_name
#solve_cmd="solve-field --skip-solved --cpulimit 60 -v "+image_name #verbose
print (solve_cmd)
system(solve_cmd)
if isfile(basename(image_name)+'.wcs'):
print ('wcsinfo '+basename(image_name)+'.wcs | tr [:lower:] [:upper:] | tr " " "=" | grep "=[0-9.-]*$" > '+basename(image_name)+'.solved')
system('wcsinfo '+basename(image_name)+'.wcs | tr [:lower:] [:upper:] | tr " " "=" | grep "=[0-9.-]*$" > '+basename(image_name)+'.solved')
hdulist=fits.open(basename(image_name)+".corr")
astrometry_results[image_names[n]]=np.array([[i['flux'],i['field_x'],i['field_y'],i['index_x'],i['index_y']]+angles2xyz(i['index_ra'],i['index_dec']) for i in hdulist[1].data])
#Use only values below the median for variance calculation.
#This is equivalent to calculating variance after having filtered out
#stars and background light
THRESH_FACTOR=5
IMAGE_VARIANCE=np.ma.average(images**2,weights=images<0)
bestimage=""
maxstars=0
#for stars over 5*IMAGE_VARIANCE, find the corresponding star in the db
sd = np.array(list(stardb.values()), dtype = object) #<SB> had to explicitly convert to list for python3
star_kd = spatial.cKDTree(sd[:,4:7])
for i in astrometry_results:
astrometry_results[i]=astrometry_results[i][astrometry_results[i][:,0]>IMAGE_VARIANCE*THRESH_FACTOR]
astrometry_results[i]=np.hstack((sd[star_kd.query(astrometry_results[i][:,5:8])[1]],astrometry_results[i]))
if len(astrometry_results[i])>maxstars:
bestimage=i
maxstars=len(astrometry_results[i])
astrometry_results_all=np.vstack(list(astrometry_results.values()))
# Expicitly convert to a float array to prevent numpy error
astrometry_results_all = astrometry_results_all.astype('float')
#find the dimmest star
dimmest_match = astrometry_results_all[np.argmax(astrometry_results_all[:,1]),:]
BASE_FLUX=dimmest_match[8]/pow(10.0,-dimmest_match[1]/2.5)
print ("BASE_FLUX: ",BASE_FLUX)
db_img_dist=np.linalg.norm(astrometry_results_all[:,9:11]-astrometry_results_all[:,11:13],axis=1)
db_img_dist=db_img_dist-IMAGE_VARIANCE/(astrometry_results_all[:,8])
POS_VARIANCE=np.mean(db_img_dist)
#<SB> execfile went away in python3
#https://stackoverflow.com/questions/6357361/alternative-to-execfile-in-python-3
filename = sys.argv[1]+"/calibration_data/"+basename(bestimage)+".solved"
exec(compile(open(filename, "rb").read(), filename, 'exec'))
f_calib=open(sys.argv[1]+"/calibration.txt", 'w')
f_calib.write("IMG_X="+str(IMAGEW)+"\n")
f_calib.write("IMG_Y="+str(IMAGEH)+"\n")
f_calib.write("PIXSCALE="+str(PIXSCALE)+"\n")
f_calib.write("DB_REDUNDANCY="+str(DB_REDUNDANCY)+"\n")
f_calib.write("DOUBLE_STAR_PX="+str(DOUBLE_STAR_PX)+"\n")
f_calib.write("REQUIRED_STARS="+str(REQUIRED_STARS)+"\n")
f_calib.write("MAX_FALSE_STARS="+str(MAX_FALSE_STARS)+"\n")
f_calib.write("BASE_FLUX="+str(BASE_FLUX)+"\n")
f_calib.write("THRESH_FACTOR="+str(THRESH_FACTOR)+"\n")
f_calib.write("IMAGE_VARIANCE="+str(IMAGE_VARIANCE)+"\n")
f_calib.write("POS_ERR_SIGMA="+str(POS_ERR_SIGMA)+"\n")
f_calib.write("POS_VARIANCE="+str(POS_VARIANCE)+"\n")
f_calib.write("APERTURE="+str(APERTURE)+"\n")
f_calib.write("EXPOSURE_TIME="+str(EXPOSURE_TIME)+"\n")
f_calib.close()
print ("Calibration finished")
print ("calibration.txt and median_image.png are in "+sys.argv[1]+"\n")
system("cat "+sys.argv[1]+"/calibration.txt")
================================================
FILE: tests/science_cam_may8_0.05sec_gain40/calibration.txt
================================================
IMG_X=1392
IMG_Y=1040
PIXSCALE=15.7768356032
DB_REDUNDANCY=1
DOUBLE_STAR_PX=3.5
REQUIRED_STARS=5
MAX_FALSE_STARS=2
BASE_FLUX=254758.120205
THRESH_FACTOR=5
IMAGE_VARIANCE=2.12414468046
POS_ERR_SIGMA=2
POS_VARIANCE=0.666903299486
APERTURE=60.7
EXPOSURE_TIME=0.05
================================================
FILE: tests/science_cam_may8_0.05sec_gain40/calibration_data/.gitignore
================================================
# ignore all the calibration outputs in this directory, but don't ignore this .gitignore file
*
!.gitignore
================================================
FILE: tests/science_cam_may8_0.05sec_gain40/input.csv
================================================
1332.66135414,1005.65868251,9.27684107053,668.988734129,830.457341566,9.76312036221,1086.81114937,464.955892187,7.77428272825,252.52804707,586.92908643,8.96669902205,810.549694541,909.672468917,6.67570087357,1222.77253018,588.922220972,9.09333834234,47.8054763038,215.68989355,9.68856752687,155.37293176,102.037964161,9.93286761468,1211.85862788,631.498265359,8.42413992351,1158.19421457,16.883473647,9.03784428344,550.527074851,351.967375445,7.04454402364,1035.70951011,179.052375687,7.80281486578,745.421840851,723.192195778,9.64978076066,893.575154082,493.966146616,10.2691241853,341.183745219,134.211038454,6.8262450064,663.47598836,993.625426313,8.88604694037,878.931937752,59.0887557823,8.12825542144,530.899387009,68.3497597776,8.69925204243,48.6301861272,750.818020798,7.17102229746,538.77769969,843.165215628,8.07385539306,1126.80197661,96.6815209717,7.23839628871,1195.0039573,766.553198746,7.83002695359,778.442991882,734.239442645,8.98892455436,389.854681168,813.250786801,10.3819620783,1199.18962075,445.460883651,8.49054356324,1244.33324977,843.263615312,7.74220053988,1133.03379914,312.108485129,7.460106584,428.860210364,49.1137933311,8.66706978222,442.610329145,706.495818936,6.68162303057,553.288210904,1031.29588468,9.87530276662,745.018908822,227.616401557,7.85192332412,706.064549624,124.445431798,8.99762316643,907.35834934,161.573987156,7.55659177796,1292.24658496,567.709089909,9.17607559759,708.811923457,434.435344299,8.23507548301,55.6824121956,32.1080370985,9.30940180884,1367.26130863,798.527335616,8.60603196482,8.52994280141,892.559738307,9.00410617275,936.706605963,309.36602258,8.45638566575,919.732674913,118.59412702,8.09732282652,993.125128963,701.543990499,8.74720398814,1142.41539859,357.888915335,7.40120262257,380.318257941,610.652920347,7.65963419734,1214.63298937,124.799484879,9.89266690486,894.814636584,958.227777159,10.8916802947,981.540497619,424.321568881,7.86877067496,1088.07474413,924.876826698,8.8945156091,293.058423834,505.163872888,7.21827209799,653.743191279,325.206887944,8.08294207819,1169.83563685,293.762541805,7.97295714855,351.360974628,385.404218102,6.26380735588,1383.46986196,47.6180909771,8.81337708816,353.476290031,884.74272247,6.50625132605,1188.4572659,241.499550703,7.3433412911,349.171686796,1.78688525006,10.7863770211,697.75369712,468.903583642,10.0073128336,969.106478415,435.247992142,8.25199979098,445.282887464,997.604679554,9.52032407196,579.741471062,537.566133275,9.33044815785,289.890174343,185.965372827,8.42171109675,34.3416764664,607.321210309,8.1663780163,839.778639893,449.639379723,6.93819352732,894.517304047,490.783485168,7.63970126336,674.088357472,7.21357647729,7.9113477377,271.245537763,901.728787463,7.13004025655,130.122980674,538.981134709,7.41641308146,174.795081003,788.044874365,7.88548103111,519.64363743,626.800745885,8.78715385698,443.989655145,1033.80565811,7.35381529356,195.290766237,248.52452148,8.40085734041,1331.03316444,363.58614873,7.21789962467,1365.10303272,855.313927946,6.53462122133,193.482075012,1028.52089922,8.88493282993,531.926375169,131.656314787,9.90691242008,304.876302472,552.086823904,8.42745685035,664.128687263,107.7798142,8.50176239177,693.957041092,831.70783991,8.91916380322,1274.7570241,1032.08049656,8.82080400554,1003.66946637,746.246100436,8.60818660145,233.186497325,602.615915382,7.99336494193,624.714860064,650.464351469,8.92562889079,109.998625488,308.140080994,7.48643300472,71.2039075457,258.994652725,10.0484150283,526.667680804,279.191507679,9.57594469155,901.747099641,572.744624963,8.4175551312,835.04885274,837.436077076,8.01422621988,4.15643690466,273.16175585,8.11250596628,191.800809728,332.896753484,8.28901225384,1053.39040359,732.559469306,9.79655811435,183.705755281,754.160515257,8.03360767957,1242.77487761,975.301822611,6.9085260576,313.59644267,674.072634771,7.75830397039,552.397778382,485.832875076,9.44546945441
944.69742609,72.8980624104,7.39656102292,262.303232843,614.845511191,8.4788528588,21.4038946892,262.489453583,6.5663163383,7.25423398866,24.6277721103,9.21068910086,963.844181491,181.75000974,8.55608972161,399.835769215,452.856157083,8.17919160447,422.996464844,561.40856483,7.16151654833,1265.47626687,176.390152153,8.1502239686,172.751544984,456.771289528,7.60967962467,928.336312796,248.042606949,5.90627340893,334.960110822,775.65934916,7.90969285114,71.747194989,106.618080266,7.86405732352,738.506702891,657.432299132,8.08316055767,680.148330544,779.890353534,6.06728448844,1257.20727154,625.416686358,7.26017268027,364.746484888,803.231061485,10.2208641996,445.262244817,499.240820148,8.13533723207,703.237221803,954.861612723,8.83432766743,1324.64848395,801.074312784,7.38839502415,1312.41157759,853.791276665,7.64448309998,773.918573911,710.17249481,7.13424781959,844.112269164,84.0919228077,7.25433438754,823.172648943,269.211439929,7.5015409017,739.377744113,514.199518749,6.95195660116,640.881301089,731.496519739,9.2722867377,226.134036557,788.123390348,8.03200271261,742.826627301,793.604506117,8.85416366108,640.790319142,609.371349401,7.50758437035,1218.79104134,951.683689975,10.2782907076,716.941858104,867.207203557,8.08707454032,940.754393342,522.115420386,8.13183436949,1070.21319305,924.708726057,8.29051238504,278.618000929,664.730676869,7.53554709936,1325.77322284,472.742446356,7.0080280503,589.307238478,736.504751912,7.77363339726,1287.68941796,396.596248276,5.9724914022,1222.19815709,506.847336409,9.84804377965,466.820990642,545.69717745,8.495863722,747.27484709,399.472981303,8.1830626062,574.375531253,338.70011729,7.64134241042,514.030967258,852.873455858,7.62463256413,893.304976652,740.41272758,10.3514977296,845.88916067,83.7088364964,8.32424475947,341.75554737,249.04928767,7.23187527039,261.467229982,337.826807625,7.89050704003,95.3682811109,734.963396365,8.45028399267,80.8278568687,584.727241903,7.30628979317,821.39171365,393.559676837,7.21994081832,1092.2365702,915.294157047,7.02995343335,606.951229596,894.593105826,7.52922364713,1147.66759145,36.6829470231,6.88293108562,1074.35834258,373.363189599,9.90025087967,1222.9050915,121.888287545,7.99481461426,440.738065203,305.556316223,7.9453723581,997.714704505,858.949936474,10.0827406557,1102.35057936,239.236127154,6.66987951459,953.090218857,589.259186495,7.40988139347,838.577466339,144.257491248,8.66054093976,852.498159605,949.724648122,8.21364926138,550.761314738,525.099169264,7.53811305131,751.678214493,9.72837911186,9.68338593765,119.25959842,401.920179587,7.63772388059
826.716286273,367.530930975,7.60377918486,864.254278142,221.125818586,8.2457913237,1177.38692222,595.557802068,9.13118110706,1085.76751818,159.991345211,7.25451977909,176.177028513,4.8565141692,9.22371873376,1359.42196389,253.902372813,7.6755204702,1256.61578823,142.166218951,9.5737999465,34.8582427072,313.564907664,8.66478318416,1029.98328305,985.948235975,9.5818056248,346.820989598,881.302620984,10.1881564225,1027.56527566,1015.30938536,9.60676539534,569.599591169,107.186361903,7.67776236833,835.405542996,843.419530315,9.96028676248,358.026777331,726.008517338,8.52127138275,1052.27563779,737.955618718,7.25638401399,864.332549464,604.462753901,8.4238503186,753.492439995,1035.20788787,8.61244868047,443.892120754,770.561951799,7.7276132328,1265.99037801,635.48223652,9.73808397487,16.0783890149,391.157417279,9.2642527889,1368.6382598,282.49794426,7.38079215595,871.426025994,1015.66692096,7.40255546799,520.774214338,649.248040797,9.08200490328,422.636768768,395.089530519,7.58797121993,401.011674109,246.873090792,8.15508596205,362.213703441,293.837862503,7.78911799784,680.759551517,245.399023089,8.26958935329,644.513838838,744.568734693,8.63342827545,194.423792513,458.961623555,7.7385918515,1144.15285892,607.474393391,7.6565249563,872.860423514,987.52893227,8.30755708937,1002.98230593,501.535038866,10.8474435611,292.51429368,346.981908902,8.26536161867,425.946391897,189.496008028,7.63091260616,1315.31431202,991.02675687,6.13469072602,253.132532004,630.391479439,9.39116830026,1156.17821054,23.7428016344,8.54975438969,812.243586794,867.936745321,7.33065432892,259.816440104,703.574880524,7.44504493235,45.0360906736,886.181969253,9.60402453195,497.628626358,921.651626379,7.73346596986,1139.50661357,278.092062638,8.42590818655,1034.12604719,200.239340426,9.06861620865,984.696314266,811.921875556,8.85689459865,332.49240722,659.417125388,7.57871369304,1007.82073875,320.912711302,8.12810643506,241.923116674,307.942743568,8.05763027364,517.221015869,758.462791742,8.81635677349,908.50513121,245.398544238,6.73228139084,1349.46956182,709.277962964,7.63753499237,683.070865854,292.425921147,9.4174095858,336.81699533,940.155351924,8.07182653068,3.18941400469,1016.56753738,9.22040504999,443.57339695,929.6287291,6.49774570849,79.4907004629,628.735268004,9.46387764598,1087.7456228,678.25040754,7.77526086362,138.680228193,710.796148769,8.89437177401,1013.96500158,127.358164267,9.67591341473,130.911809515,1008.2802983,8.21526276948,1387.95889579,974.379351391,8.49137360184,481.625870755,488.929415294,7.78181394868,569.36498261,327.367320656,8.91900772546,126.800112441,75.0718877016,8.59244484125
813.658686761,729.14133393,9.94566148587,1242.63793428,997.302949751,6.31366906653,685.924821727,432.793053496,5.77732211124,1012.47756339,624.104404367,8.12902467157,60.967360326,995.326140428,8.45201623167,900.76975485,80.1111766192,6.02498357711,958.676162123,331.262041339,9.36072831852,62.2086049522,525.427190637,6.46176177166,466.214912001,507.677276335,7.52095666257,1375.88424847,786.784086515,8.64854162505,1228.63025762,107.960277646,8.32277573314,1297.0184489,318.935041495,8.58448348296,1299.85048095,125.731204908,8.10156883143,959.79793717,539.697030625,10.0980632152,105.389849949,193.398819803,10.0807536778,727.18212595,914.170558025,10.7731113123,403.215334728,362.789887571,6.89960547309,957.562321849,145.189259896,8.54607538914,1125.98992065,405.48542146,6.66724602979,1009.44483412,1004.09509482,8.55054360291,1244.69525835,1001.65351519,8.60867320642,1363.59846348,170.878818739,8.01888248098,861.202912656,156.224869481,8.51434820118,637.975716831,187.271093617,9.71022729856,633.623553984,334.715736075,8.69912993589,460.782609978,859.715292186,9.00665500959,977.872357096,930.506188954,7.84923188939,1179.07122615,515.401994898,9.11744521587,396.342447645,303.523201647,5.77341598425,15.7347487678,536.620579905,8.21223879668,352.040715898,682.01443097,8.42713586189,348.603235492,644.896472633,8.77108392359,19.1653404879,572.386714361,9.3053122286,1060.99218017,25.5025782855,8.92847565541,928.188878027,794.759013439,6.31884395252,434.99531426,717.168095681,8.61240971128,433.877783545,136.583197718,9.41584752241,543.153757274,451.166795296,7.88828577599,759.912609446,206.326910249,10.1340247716,120.931947964,4.66275493197,5.69349057092,601.084180316,944.524384923,8.44010352928,463.30657165,820.320187391,5.93102875801,1374.6210286,879.06820269,9.63457399954,554.527545501,19.8619090438,8.69334908142,475.001241153,229.58089259,9.81579871582,211.647002107,66.0863445128,6.78595740108,473.925519274,595.535594534,7.20946660604,1238.16527832,131.951891229,8.21153063869,172.176770683,870.503509905,8.00030159407,401.195315692,895.118281702,10.2296120951,265.422046459,673.26544456,10.6598068195,326.851307189,484.354144389,8.68511662332,168.164526036,780.974841445,9.19991522554,400.114157423,71.092837351,10.6197884691,794.591051718,241.802896801,8.06039987612,356.639878535,950.097676233,8.65124579849,318.158183917,378.789610743,6.51730689705,1074.3205899,1025.12139158,5.01336819131,940.692737592,274.099707387,8.23609995532,1135.27117508,338.46713641,8.56013499977,637.774069959,192.24510297,6.74292323503,138.429529916,28.1875923552,9.50822411804,1299.81159729,359.563025467,8.94327569495,134.961536785,385.803280379,7.75040654045,76.7220174548,113.241994311,5.31849695101,716.262328476,824.142557026,8.56884583697,363.007636539,323.59328497,10.9388619219,1104.78328032,635.298303525,7.8499991416,491.693087339,364.682050725,7.73792722041,447.61441242,902.098169585,9.58414170339,217.014400127,923.237935979,7.06271220972,1226.66085936,76.4069215074,7.54528629512,136.88947394,985.87028426,8.0919158643,761.321206735,594.998986671,8.56910537322,598.689630197,575.238268401,9.19858217802,1225.03580524,701.899314237,9.30541109982,350.244971344,499.897786277,7.10236281966,99.8969476758,319.379598258,9.9022009401,280.193707134,147.715264862,8.71743152191,960.945441751,363.549467737,8.04682541627,159.635967301,686.441243004,10.0378184058,824.973319497,979.271973787,8.57407597343,104.498309523,750.947559769,7.48946525097,292.024072595,165.439696679,6.43234812203,773.771520801,464.678132886,10.3718615873,959.99206658,195.244363466,8.83064374985,854.330839678,907.246746322,6.66346209747,560.900044562,630.494757628,8.64256302693,736.673456369,785.460726274,7.94609773802
1275.3296058,912.056140621,8.89910424965,948.724059429,75.8638890211,9.15558138358,1168.63773366,1038.0045075,7.41107856018,624.095569192,309.506437786,10.4060632935,384.554807744,713.181820828,8.00538949862,706.468463206,352.205124827,8.12875347407,223.429477955,530.767580935,6.81751322403,259.28158623,520.683842242,7.73310695473,1161.92145624,144.45491898,8.28319262127,431.64074015,412.946439073,4.79092459903,13.3367995107,702.972244264,7.31914852372,1167.42654583,358.712143032,7.89860904731,1220.90661058,382.501903718,8.94218637911,1075.26518711,250.020465008,7.84271073596,808.825094795,288.398259447,6.24070687634,1079.06079051,621.953831634,8.92701110395,433.791014474,264.900887885,7.53477957316,301.311599401,35.5435978534,8.48803624538,447.379062779,744.852395383,8.22032191934,724.712501434,799.946451797,6.84010849285,705.911223975,201.682313349,7.70955669404,591.224018804,559.700127474,9.58530706625,1212.01016138,616.92104329,6.50848656841,571.579417563,845.800040246,7.5399160286,453.437139507,150.68309084,10.4182442732,836.355865658,576.302469092,7.87982020817,41.7720327727,365.59248259,9.16133387872,455.309206975,539.495789232,8.34887544675,1308.81505096,986.439973379,7.62191716941,798.76076536,29.3688340258,8.5748156492,1085.62163847,570.401459742,8.12719434774,883.812491746,646.599898808,9.38488396524,773.393260051,966.262461542,9.48183914155,987.516564218,926.257018143,8.47323999546,1315.40596973,797.052112482,9.51698622522,807.397152625,787.819779192,8.43787505011,260.104508145,377.475557556,8.57129588606,78.3821637292,706.158982105,7.49567613146,1152.35635522,131.76351111,6.57978420431,667.678205802,858.17180205,7.70281410851,988.035936454,791.95183761,9.45802845702,581.747150149,888.643047427,6.64139958617,1148.97387968,763.751346675,6.56713985429,772.425864142,485.80809472,5.72743891502,173.021915122,631.149381865,9.60336550402,172.078415341,908.228939051,7.99787972175,584.792689584,954.897214935,7.68966728973,145.475599046,165.558634047,8.5919815574,1278.90924242,986.080667764,7.20062185644,726.374680403,613.867276877,7.51929063628,428.365566047,996.131365278,9.19427685684,298.14746345,839.600528667,7.77076117721,124.913119261,1030.9831187,8.3227742661,719.805219675,318.137429015,6.81760182903,1384.15482108,154.054722276,9.90534558676,35.7310218282,431.87267324,9.49580084875,1195.83947936,908.006076775,7.99047278582,590.080791923,547.550182147,7.96057707769,812.709649134,612.020459543,7.16135308064,1367.86076936,455.099438509,8.87915611999,1160.33748407,811.141823368,8.10675594377,1096.29238246,143.510513065,6.90907762922,832.201951953,280.574253389,9.13368503943,1176.74164597,324.304045763,7.63835701067,1036.909017,957.368866645,9.47296869383,1186.76779297,330.082456487,6.572572994
933.5526378,875.159034967,9.88971816473,1359.90177538,497.667644937,8.31195059001,1039.76845582,637.212978189,7.80842124006,568.151775826,727.003055047,9.524105247,379.69627872,407.914171335,5.47363350528,1269.78426982,243.966630685,8.52028642516,582.695663461,867.047426591,9.11852751628,458.803182446,865.489646196,7.19311367725,248.664350348,938.998907273,9.57194926649,1223.65981675,679.528247642,8.11120830049,1155.73117024,925.02770921,9.28336476989,281.960759851,843.291910956,6.61323522504,265.032932618,536.539797072,8.49867177474,471.766485038,863.264014348,7.70735787707,1043.2585068,58.950067925,8.04007329388,704.702849598,622.493231569,7.28947123634,877.798192163,438.040486892,8.28767182693,1235.62259729,32.1442646263,8.28039623559,565.433476963,285.620204956,10.8717685828,925.170243595,55.2404054142,7.03597962929,240.128965807,338.600641358,7.9782014455,57.3376827438,960.877446489,7.00879252305,1319.90793767,649.654326584,9.32463128642,770.375086753,591.616146085,6.83212758231,1296.56447182,384.510223256,7.45135479153,520.481105347,739.393184129,9.13030181628,188.473217196,563.548382896,9.56763472064,1193.47912298,406.331822406,6.98324868146,252.691298153,106.732438976,7.73240854984,521.24642174,200.844595507,6.43378068149,309.98584669,324.6271491,7.48461400846,734.966291579,893.615008751,7.37644688234,382.351423815,450.894506344,7.93877506773,425.653308801,399.423990753,8.46811993438,35.7574793789,476.498287275,7.74906682986,1270.83156906,505.115813558,6.66360314864,747.044682791,806.778676051,9.40085203182,131.991649245,522.454668407,8.06514038067,516.905192987,978.238058744,7.8774756398,352.368909127,57.9511650672,6.2128402197,1013.36378462,420.046940742,8.83267444417,429.387217327,677.487364408,8.37105022142,415.959430951,712.427793247,9.48067160368,551.842532651,586.94606319,8.48416677393,669.419568832,166.555044871,5.92489037873,862.480500401,602.032398039,7.8031933235,719.734570767,131.890945912,8.35389375435,100.770816316,956.348043888,9.18141688199,574.326841143,443.483890535,9.24659241216,1076.38252108,535.770500551,7.2883310106,973.586247448,673.802139464,10.5174327541,1292.60311216,373.861617617,8.37822212561,710.242886153,920.879211261,8.98226149962,1015.65948667,994.992400097,7.79662462447,928.899332332,364.62357216,9.3734729391,312.621808275,137.715577144,9.6672538795,0.173833365419,744.642700963,8.85485548789,1171.94737182,761.695139621,8.15924928844,1255.86223636,830.344413541,8.00466054162,914.936487851,7.51874491781,9.2734890023,430.024357224,12.8100265202,8.14505304144,494.34678809,224.713952045,7.56661396637,135.865244288,193.711971095,10.5129003902,822.119660366,200.871263139,8.2321799692,215.085287885,10.224336474,9.562969106
1320.80257916,277.438249122,6.6679628741,577.979994056,609.637385122,6.76072337459,569.949626415,594.11249109,9.43755006562,1169.66282455,72.2749523134,9.39534938317,702.346135992,859.380031475,7.91946980691,666.151568575,583.633372229,6.85039365029,272.357606143,671.907976831,6.52396030209,193.500368678,550.770880444,7.38855874359,596.475102908,816.722331237,4.92026325901,4.04559697522,454.995525795,7.20290582664,865.561598796,190.983699402,9.86283522446,42.0323037143,747.281213324,8.10649028988,816.746920635,720.916212651,8.04143490518,981.973857703,393.264294498,7.91764777232,822.34836063,795.771719207,6.7446130621,492.780746967,454.73019693,6.60042156693,688.94716227,492.648488312,7.20994717023,957.155743899,751.735131099,8.33855556608,19.9722455097,463.734027465,8.66335575358,834.705761647,438.108847642,6.53377853653,991.800759026,374.411416973,8.40748756942,1031.62980077,320.383275006,7.28434531598,254.715302963,539.983542928,6.31835547126,952.219953438,18.3761158419,10.4068454256,443.102730192,267.409120205,7.71405656787,1278.31991502,1029.86606024,8.04371897127,625.388801322,455.91560729,8.80987801731,714.310664552,680.341486993,6.07798451803,1375.52121521,305.834598991,6.53892213663,780.280068737,514.396662006,5.73885317796,468.291637285,32.5193707793,9.58856541937,436.302789255,889.233550962,8.7665827146,991.879256781,44.8638733036,6.08573879984,746.811448163,491.426145503,4.9334275452,81.2547927977,52.4476974844,8.06375960066,207.897671455,304.497410701,8.60901601623,446.615861258,1012.80278921,4.34848916241,206.314531752,577.463624991,8.65991061045,752.884910161,508.357011185,5.94072604271,1145.44090929,820.136517836,7.22697191322,300.015704008,213.272907221,7.82548184494,312.945587969,374.195450814,8.35060784849,738.824233187,803.683253014,6.13787204246,1189.59429696,804.257607492,5.61880917396,32.6522236354,869.315899211,8.31357613392,1127.22953815,755.137153769,7.20409556621,675.239215613,553.398814737,5.43285112437,855.417151266,900.629286269,9.58745999064,145.622969218,997.757072457,7.45206515285,199.566054405,469.647723384,9.30063060249,1151.12934915,578.756244183,5.65841776372,694.018625788,253.093534954,8.28241540428,763.466086218,760.03316674,6.17545593663,1174.80179363,845.574587726,6.07556344873,512.411758943,561.561095612,6.90727767875,1276.59724088,852.428416086,8.89406673017,1187.77379799,523.781939891,7.61432901635,768.630285387,831.775153713,6.21335338665,138.938393881,579.753570466,7.2574313892,758.942583886,734.589244975,6.34566257744,120.324589662,493.057119892,4.90030357673,465.179909623,155.877011165,6.88776155394,1127.29302794,980.619819697,7.01174041503,1350.47729764,330.985749887,6.29861383445,933.308038907,771.160008676,8.1561894583,99.1627106774,381.561312401,7.21611869091,1370.33423686,930.069848528,7.42040655475,1226.22715993,158.928634469,8.26222531841,579.405818076,339.690535003,8.25486086647,743.60805089,762.701666604,3.76094522746,442.000579611,670.189734962,7.20371801121,273.821286172,141.441747221,9.11661340703,655.230209736,420.287680456,6.57553168668,392.37896616,336.231850808,6.59691961022,1067.73438483,172.775279996,6.78514832515,1041.52043296,653.260235155,7.15621993538,101.530685809,123.688397978,9.05573147213,1364.61265565,405.267499367,8.13559702434,744.89147086,811.496215834,8.06960812669,575.467599095,652.108646402,7.8446894382,83.5551839334,869.599975397,3.65318585045,440.620536644,114.435686759,6.58000236601,461.675274492,870.285557833,7.21022977142,359.252037829,770.532018497,9.01714916294,471.829957994,764.388099291,6.98028764306,1303.75737542,624.620757539,8.19370392537,522.035078357,505.258863829,7.60176894159,122.545936156,694.958995708,6.45071747849,1265.51595912,462.562195657,7.76452446791,1061.57912855,415.537476787,9.23441064757,337.112465549,628.510121978,8.8748562679,900.130961118,561.249909434,5.79931886622,821.562161939,748.325776783,8.1978738593,480.595840478,488.267568595,8.16827845434,644.116164473,897.901911848,6.8906493529,1314.66997163,672.824984803,7.63068375028,339.02407338,534.249436445,8.59983133656,421.947170093,746.541942448,6.5023612449,909.954247497,74.7985170447,7.66188691179,1157.87465312,552.226491462,9.45588184575,581.974963614,11.2335841156,7.95477541438,97.0502187826,739.18232563,6.35213633233,46.7186775199,261.095102007,8.20344423952,200.05914002,882.494914185,9.26317920961,1249.47301476,373.118936221,5.23655837027,847.757929791,438.357467768,8.51320813982,366.33440933,263.304965578,6.67211198368,763.305858387,14.7550498257,5.41566772893,1332.0747857,397.511193364,8.45096724438,944.155970019,575.024182524,9.2866669039,16.5628701069,911.919210462,7.19393163397,666.491248811,349.907836386,8.07342555165,1303.44526533,973.022389754,7.81034226409
337.520433749,437.851621994,9.83964867648,621.502544435,705.538158465,9.48186488053,384.867066223,395.485178188,9.72842474371,1295.73530064,345.270586613,7.23578588701,42.9066466939,921.527057352,7.54135073558,107.173337458,294.068205476,6.85993266723,1384.28739071,855.400951953,9.44991646875,1302.29810419,736.419160836,6.88677657343,192.099334495,893.378376622,8.79541335444,1108.78424058,197.267466636,7.54181703747,1134.11007044,852.149918854,8.05482054745,1018.37673387,466.322450882,9.66077959018,661.935885726,41.6526513609,8.53376970798,422.811435253,905.430575652,6.83293531723,555.991064088,753.165909714,8.6238868432,915.362391228,599.600875656,7.47892758696,545.927546481,351.085334562,8.8849767567,207.73699863,509.355624323,6.53529451951,936.632247074,252.586498447,8.19064907379,1146.29948411,416.842670741,7.81999474626,530.049755463,973.751396563,8.52482152076,193.773308203,81.0327232261,9.07567945391,887.515162174,44.0416802164,8.14706181708,1342.14163803,279.320433365,8.1761511754,1035.03330234,741.460726665,8.82862153823,1257.43098254,943.390303377,7.30485007268,1062.86173644,729.27553443,6.76675235197,393.837111288,293.666539352,10.7439340561,722.622353061,163.404387514,8.2418488966,1080.05591826,219.570660048,8.18787158846,1039.56579242,860.782830164,7.58729414067,929.65610071,360.836865467,7.88071587368,228.206552351,488.065064008,10.3924713531,693.255381265,848.825627594,8.6165185976,1046.21005498,737.764901735,8.79348607316,1165.77954147,437.441322304,8.49327135143,791.134798546,413.202685778,8.65821590591,1128.49683702,45.8586979092,9.41988126737,296.908921022,755.268635556,8.6259817415,1253.53267129,533.233494988,7.43930438125,758.513079299,989.544179488,8.20127246317,377.916182354,754.328704335,10.8370054583,899.606537144,451.577447079,6.1726259957,30.5639301414,209.348784153,8.28548032332,16.6757934885,753.641515699,5.18287202823,1149.09037615,222.03752973,8.60641072443,567.233727745,580.371080774,8.12195968848,112.51102373,677.660030986,9.58319491654,819.829442548,593.974813079,10.2380735577,465.894640098,575.080049772,10.1682302726,350.17566157,113.367392301,8.49297276145,681.568150488,559.650435788,9.32741384021,476.921911627,194.053771216,5.60188429561
244.950929379,336.920354011,8.89832139007,484.614867814,127.108531639,7.59924746173,788.590535762,99.9835500601,7.62226157082,701.823153999,51.3420025687,7.89349257787,1230.32110464,913.385486651,8.70452406391,374.24899277,555.662843356,8.18206836602,73.6590738708,996.134485679,7.10645963969,1354.7817824,438.695671692,8.35700440686,745.971480979,972.396552095,8.62609979473,711.117331004,714.743723886,7.50359784483,567.313433938,574.961936119,7.76040029656,355.704648929,160.331192117,8.96285465325,480.943976611,355.992719051,8.74318930041,590.108257869,148.756276052,8.53719892708,1185.15577212,705.152389043,8.40524004486,556.05732334,95.3071381372,8.96799401165,120.1682283,923.471055763,8.47689890672,555.402202478,895.057772315,8.76768045593,267.382062362,489.706944287,8.45460430081,231.847129371,67.0692772142,7.38461753832,191.090772513,696.084863432,8.72359800583,527.947793296,891.87508475,7.96884169452,776.790972873,579.656241424,7.08158592179,701.838361361,785.012962657,7.56863677517,699.668442676,256.464093153,9.15446690316,875.405019548,380.589747509,8.54870890247,964.823918545,193.856099663,9.33873688382,201.359895219,86.1574446975,7.26572197364,1053.66061166,241.065348416,8.94756913775,459.499532289,898.332389564,8.45577047545,1024.66319916,971.283980934,8.79763515249,624.173613718,560.298273036,9.31243846415,977.117800047,519.189658701,6.68192034036,20.1013998034,496.5041652,9.02916669242,1388.26469912,902.74195469,8.27987540112,606.739925792,155.704983141,8.99177737014,709.185169432,978.429817213,9.38853557908,753.593416934,118.756523167,9.0070845001,1246.97537012,430.743530077,6.88953535708,332.899053256,1005.19549909,7.33799207444,959.479056077,191.900444938,9.51507825219,1048.36723609,76.1869322481,7.59606965045,1269.56583344,61.364491629,6.9610880268,381.505620929,360.537163249,8.56726904534,78.9827685988,5.22218184273,7.91591243967,72.9079714995,49.7571920147,8.85216153222,1039.23590954,681.038278338,9.34181065252,862.521225926,494.433329886,7.62747508316,113.337836932,529.786099089,9.19565644545,266.08037246,987.725531389,8.15168251477,1110.64393755,296.464375944,7.51673102124,1180.7829334,63.9769111726,7.80658115806,86.5501375852,850.96546078,5.90666457704,602.792375114,156.619351099,6.82613167115,1083.94745316,80.6043120834,8.0540797954,1108.82265181,566.270113055,7.59106456745,1070.0338719,275.367457642,8.34202129399,402.207334398,584.066104987,9.36422163106,669.528594324,890.492127604,7.76982458228,103.822070063,185.821658692,8.74519267571,1266.08742638,180.668335078,8.90762321004,986.291231606,414.239504576,7.43564817906,1085.03822137,836.228283164,9.5656029794,707.699552994,958.303505341,7.93372943344,540.164787924,963.796127985,7.04397723844,1316.40862523,758.1079285,8.41719803545,406.121074977,686.663638405,7.73885358056,800.333616077,380.429597257,8.1912437031,173.701543546,1019.24717575,8.49832526663
1216.52232952,261.213208838,4.27768830506,180.963267168,441.365236413,6.32445717593,358.648372027,725.119805865,7.26909229298,384.078659617,433.546349474,8.76524593567,1201.02610701,678.738151926,7.96702328796,1213.34984739,887.572595062,9.34777658397,628.408354696,741.885037105,7.83332420844,989.10323887,690.985834798,7.18244444232,858.101969151,544.748305328,7.33966836302,615.411824131,1011.0326809,9.12040308062,355.706065535,948.539758164,7.8112639155,698.200401033,891.467164475,8.85126791784,1096.47646762,734.155289635,6.66820618572,976.87633639,926.079868993,9.16900407843,332.155250533,331.293184364,8.83320930205,1254.95893232,749.58864258,9.1619184253,1151.42026993,307.999152435,8.86168732943,281.09967485,545.199511188,10.2548893098,146.097418266,526.674675193,9.0542342341,994.507877723,416.38279361,8.90941100068,1093.84735505,656.79770848,9.17824446199,102.870011365,793.591094664,6.88420500529,90.6201988886,39.0278533858,6.88678980709,455.107733866,793.343366431,8.22539522886,48.4863359301,183.085521987,9.25659275745,1167.57751219,509.056987265,9.32591336581,1093.02862299,32.0193708545,4.51042389097,973.008214152,120.668053641,6.95988112306,927.251582716,80.35618965,9.61408607421,86.5110148298,978.485197867,8.89156413774,554.509844374,23.5646241609,7.79193414385,833.107431016,539.381537258,7.52354444729,1133.2314022,995.237286678,5.80415300207,1342.51188935,325.021240022,9.35477842206,201.820096771,783.150900953,7.85577876916,581.292223979,272.285979295,8.65519094069,245.402627249,713.013761872,8.03777051526,1298.8331703,455.367140858,6.70851625996,413.603185415,270.235947463,10.6738595529,522.728622456,25.5355453733,8.82838780642,178.646584809,740.74314996,8.75510137367,1206.89990469,225.555912889,8.91322005903,768.759242868,946.536359713,6.44863251372,683.164811491,444.171504848,7.33017188455,1234.79799691,164.098465062,7.01169777799,460.722299656,617.525426016,8.9421892358,308.181384953,64.5915239527,8.54039259102,1122.8717735,121.531373813,6.75929314299,916.727938005,372.600113902,8.6864380288,495.551571265,298.853815315,7.28811027084,1356.86687043,737.989527535,7.02361853963,466.939794817,662.500722683,6.8995247021,662.542887874,627.551711627,6.87299379029,814.276480613,325.614104074,7.52449571205,118.926327016,501.690416395,10.6025886078,833.250802631,281.733486467,8.1235724583,1336.38627179,457.434410287,8.47859423405,583.936104327,271.087904562,9.16672669603,1388.69625214,960.507088846,7.53664254113,701.539203478,576.730776682,6.05097846282,639.083816723,577.267472983,6.52973904839,925.376123123,924.780234882,10.4473775019,84.2888831029,995.806060787,9.68886149072,468.041997478,938.549624509,7.73312340036,1377.56713076,704.867264148,5.262830075,38.4364357388,743.374778153,7.46437042669
740.623239792,77.902426078,9.39639192871,791.416598129,400.276552318,9.23973762249,1129.44170992,79.4621784686,7.21373892411,1321.10860876,717.980276972,8.87276486911,834.364847002,734.173747894,7.58375787858,254.691393889,780.984141378,8.78641438791,212.93300103,602.297181032,6.31156802205,748.476084321,218.333612294,7.30334809892,346.41141652,56.3632749298,8.35319993818,655.892200853,628.117268289,9.12703661879,531.911387928,540.910989431,10.1896360422,544.382997362,248.367528464,7.38712042394,421.336442631,571.501381985,4.90168106218,330.281389243,720.826428122,6.99645096403,1338.95956417,573.14663273,7.116247958,689.624143532,308.914383934,8.14256344025,870.243312795,992.913201175,9.37891236303,270.848842456,499.134512677,8.91671713703,852.202801476,1015.23841855,9.05641313162,20.2990681886,861.073063146,9.23692736248,421.473333732,763.985846106,7.80658299759,1318.45493586,690.691819728,8.45044061627,920.22384358,44.6201379959,5.91765007602,1311.92786578,122.544925518,7.75848929364,1354.1665071,144.02215201,7.48788396123,942.12542987,51.6945964961,8.9880410516,1272.00409966,107.147360422,7.42384812596,197.906043375,360.574588424,8.08705422857,899.436329573,32.9191746009,9.33833448754,208.734859502,84.1612719221,7.06651111327,704.11766841,50.9881861027,7.87052592145,1042.56107336,990.487647274,8.35429359519,433.268476874,378.170383584,9.10588223302,665.137385286,1027.06000974,8.26340004616,614.421077345,243.897001729,10.1689183531,477.69754143,910.713628125,8.78920836212,1014.23420819,781.823524438,7.92023063813,539.561492498,794.236150051,6.48294767392,302.911763287,95.9669486762,9.48300731568,1365.2779801,211.787068727,8.72910125505,1038.87656536,625.516825163,8.79129566203,401.689430819,160.297426901,8.28115347297,610.325031858,832.101162268,8.41894267579,1204.23729667,647.294561024,10.3231992732,1163.70462603,180.368334958,10.4119915982,788.419253681,1006.60700545,9.17300403762,1124.62608639,324.587296985,7.89931352129,36.4013707319,586.280465769,6.8151114658,889.276828821,848.643806995,10.3832065852,1323.44588518,409.444955108,8.01471050379,1121.1559139,122.684976633,10.6682802616,1260.43578466,887.506811934,8.44362987815,1296.16219651,397.562927073,8.85888754726,860.265322186,637.097264155,8.03574858764,1330.93543492,866.286532275,9.39833230391,1365.13290967,471.089873608,9.65548150433,582.301565698,802.082387653,8.9133670735,183.521857253,22.1366778448,6.77252643899,120.65290682,785.018696519,10.7743513913,705.057407607,272.226472847,5.66791498528,469.833686643,359.77442005,8.73989804462,1150.07694605,179.859491919,8.43541856068,971.98155612,120.655473327,8.28338113775,1267.50685264,119.002308411,8.70129784996,765.053494653,773.327432112,8.53170301331,1379.41327486,10.9364868842,8.42375597096,348.897049105,358.325119373,7.73614798941,466.314518498,953.603751701,8.64353747191,135.773352908,530.706057838,9.38095223099,434.914351547,942.171646884,9.96703301009,260.887411009,569.745963536,8.72147878643,136.693144325,624.01459133,8.08635542179,57.0182981563,816.336056767,8.66153824096,1112.93286181,903.335850035,7.9799187429,284.040380807,936.574443552,9.06975859588,514.14809693,43.8756748429,6.81487935776,855.207680608,190.490596764,9.64543828781,934.505078186,505.712536403,8.65689322517,462.093086811,848.769352222,6.96946664545,124.56435472,215.550599994,7.5425195543,1026.30135502,909.449459979,9.47475512038,1086.90583875,757.392668492,6.98811084368,350.731604007,687.61906373,10.1631170945,764.039673776,466.752279493,9.70834060309,942.219950979,643.352390917,8.85879536652,1309.75649919,1018.59440115,9.05993145275,746.365225195,251.471359739,6.49718204176,276.418143537,670.702639125,8.40934866069,518.936211923,160.24465813,7.14011212694,986.798791244,451.136277144,7.86276517783,722.628205705,277.368062089,7.20879298421,1231.5877746,968.246047316,7.14324119306,190.302546023,136.182119616,9.2770490141,1100.08389621,480.115641082,8.26748700336,965.150715243,854.341142986,7.42590716499,1333.620841,395.714767967,10.2550282227
866.545073265,214.710695044,6.76008875836,595.690756992,427.829446663,8.75598658723,338.315934873,778.710194437,7.77087494869,800.593617645,1039.8393269,8.10068878961,843.511313101,247.964969456,7.38231246873,347.288273532,154.196032283,7.73232367375,605.811301872,854.092660147,9.67211427818,1334.01845201,448.207331794,7.44393238486,1138.75322602,378.729993691,5.37718996341,130.078912554,2.18930639016,8.19703371336,0.0397243729987,695.941333496,9.24570294542,720.940646968,903.235617789,8.21008103088,1065.61597106,180.380300301,10.4490142969,793.317350341,704.859518061,7.86661267518,140.203837908,1009.77436919,5.78903115469,485.600939269,423.210893469,6.28020723188,954.823378857,997.592715738,7.84332239663,851.282580903,934.669046534,7.7696556755,265.397802905,564.711684222,9.29731771278,761.549748213,519.914603663,5.2171676993,51.5135188886,575.303377701,7.82943250543,993.685768626,41.800345892,7.36944399651,77.4173905626,3.27080267227,8.59514350977,1194.32784771,908.278540379,9.31105092581,463.833074693,954.736250186,8.65462565748,1312.91368807,552.373842475,7.71554592168,1266.5790075,659.933559228,9.95084853678,166.964552567,1016.16163664,10.3925208964,336.807208426,92.7568144901,9.53699112503,237.43983509,846.10529123,8.00559900166,506.696776831,251.537883767,8.18379504829,803.14511183,649.151525552,8.677168077,140.230730309,1010.00236118,6.43142788425,1275.25259599,926.395640549,8.00779393278,465.610631374,375.098159601,7.35071766622,139.220740672,997.653652901,8.50724005238,1205.15555206,1037.87910913,8.84518358751,60.604390775,792.254113842,8.16926462659,1035.44019231,550.490855108,9.17238455788,294.793112363,374.644453271,7.26633593404,998.093174337,574.134847725,9.46080305045,521.132024894,503.21667584,6.00032896531,711.852015416,280.782853167,4.85400543839,96.1096844808,335.881334811,8.15799556033,472.209137512,246.107477811,7.87750635921,1061.15443348,668.213272193,10.0859733071,940.431180706,647.966224194,7.98699264664,226.930619705,394.798146802,6.69185133208,35.2616882075,326.950926822,9.78596304472,113.777918558,418.397650072,9.30669078818,1214.08953939,236.564517053,9.01920256038,170.867986297,778.850297314,6.38550092613,1011.17198821,131.241409278,7.86160563747,271.282935657,402.35831299,7.29773545943,984.86999675,243.383548773,10.4396792237,91.7490433271,643.8486277,8.41247433007,622.480662611,645.303920141,7.8594146212,259.399434571,154.472792269,8.58537193701,207.629621735,230.537046568,8.29719337998,1070.76923099,981.775722162,8.46344567153,789.285493057,493.065747148,8.71419862717,1028.4656292,832.02079401,8.0480338695,93.2746469883,937.813499873,6.19866115246,676.490275855,913.178631824,8.78647755074,771.474404642,759.408818574,6.01927791819,801.906000623,68.6476599,9.17349543211,2.27807693746,176.984173135,8.93291179835,366.132745108,306.962922954,9.15197644141,192.153929949,550.200891036,8.71460662001,1126.968955,296.458737073,6.94150901849,364.832159813,508.684491696,7.656883712,949.405381893,75.186738855,8.20446089783,1261.17975201,736.749470927,10.1715271235,84.6458782227,131.772904452,8.79297066396,1301.12354889,392.303844334,7.43663190773,735.166501416,923.517415431,8.04412738386,893.237678821,332.219327765,8.7493957605,1284.46502994,153.077299136,7.03357348025,14.3642612771,925.692576881,8.99970732116,723.569236875,921.002469472,7.38310346521,674.929554526,16.5320080765,8.56374854385,1282.20349786,464.045576614,8.99725394321,1351.79195704,51.0201331639,7.57304444482,414.103631946,319.2585581,7.58565543349,716.418306201,192.238311092,10.3360239169,558.89959073,431.376229779,7.37439684451,1360.21195611,833.66817707,8.71474858784,470.741251422,735.08854505,9.6957298523,28.0439980223,144.188833132,9.47582773688,1151.83643464,158.679655801,6.02390236503,1113.09376386,318.808205431,7.54568391319,264.009746431,746.766598487,5.3454158573
746.50315424,379.24351713,7.07789155059,842.689549283,488.384262527,7.50875177391,535.317982834,51.9464798322,8.84272944933,502.32739652,1012.71585141,10.3438405377,259.721696998,168.121047046,7.86826421101,574.030252382,469.26346255,6.22782072522,52.5058946251,501.420334003,9.02214069517,965.686210024,427.32469016,10.02822493,1000.6898261,632.28490513,7.45389575198,380.202937206,511.259076324,6.43137037132,661.627801191,200.920236532,7.94377145347,827.792738862,674.280984373,8.22529657175,1384.17564478,448.323968943,3.70720435077,749.876386462,614.621382661,6.28475018145,536.533570626,54.6358374713,9.08578120678,181.940807839,294.987086481,6.93411051904,1024.03693746,178.67611399,7.40399686523,679.2458267,395.975540093,9.24356877277,1343.31506984,418.707593147,8.85717046338,827.839147817,316.964066136,9.91623709138,506.658785483,690.574864792,9.55370646389,178.352850727,629.464094367,8.57730566097,666.014769266,104.928250361,6.89948256293,396.314286349,822.514234548,8.45971694779,369.597180872,507.818016463,7.82092730645,798.190290427,940.643330643,8.11255000481,1082.22108955,159.595324553,7.1897754386,660.422656125,820.550412593,9.31688995423,695.991544745,734.114066363,8.11570705616,678.542019228,396.358243052,8.81496686604,335.942949778,32.5385382434,10.2554364525,1357.10353827,1.83231420545,8.64799756441,1143.90448342,874.264214491,9.35628083333,523.736019816,688.897834455,7.64736720969,484.62819114,343.541068655,6.23702127949,629.015063606,128.279455853,7.20374641357,1015.59308147,1026.07315329,8.44660627011,433.908034747,464.969029191,6.31170740511,847.292425354,375.969967244,8.45451660532,573.800594572,746.007211662,8.36408186669,1195.113525,1021.16061764,8.89096808999,1068.29976485,153.407037179,8.3972500613,140.360928386,803.623254042,7.46692135836,386.133280379,774.166414801,6.03506986602,8.40259167374,653.094946002,9.76918285977,63.216283176,78.0037118936,6.65382558299,99.8362327413,321.575001425,5.02727367125,1191.29075822,809.931072227,5.74410099796,1373.24013251,747.311406053,8.31492875875,301.549933444,136.078710193,7.5673321598,469.93185692,455.88721372,8.88545887676,71.8341898247,102.579360758,7.56389276633,481.801213184,858.431489924,7.82213526864,428.866696551,242.141503483,6.71074056016,597.684813497,283.471884153,8.43400920457,1080.32672837,526.916147073,7.82774177374,1184.94248397,425.402678844,7.7480439631,910.201476241,77.0844248472,7.26241597034,216.941331177,1036.22112786,9.4999145914,271.445959915,1001.36760451,8.01662667622,388.897764586,243.427550938,7.31150597489,1341.75012062,417.698866237,7.75775885083,832.95807523,867.260829658,8.46385874314,450.609220961,135.8635622,8.14081548957,23.5524394119,116.023880044,8.63982245328,387.074261812,1020.79079711,10.6745356023,1136.87582598,1032.8932026,9.26622073817,1238.24956762,708.961732186,8.30886485847,1364.91196689,1030.05008661,9.14502965289,169.397308399,267.059271803,9.12188361844,1082.33376043,319.055206303,8.13706816,305.514135158,106.882976337,8.62802780323,1260.3619094,433.821211298,4.68739307908,569.793894758,949.617116179,7.19235443324,1190.82224153,171.529614938,7.85483931248,165.286580403,676.582971407,7.42587474992,916.286744038,73.238251621,7.37929079322,17.6826352764,291.158815331,9.21761135268,1339.40764483,421.617760549,8.92548978277,75.4061279934,734.260109311,9.77169839297,416.046080922,697.527139323,6.00274722491,271.758291539,407.670044845,7.92649512938,394.646267263,820.565698327,10.3597038563,924.545551918,892.590575998,6.64434149048
631.990698685,907.350830348,6.28811212596,833.002667275,891.87967987,8.76900996893,1372.06164239,317.229582824,8.1762817247,1002.87488425,790.269699072,9.2676421271,422.332932017,255.013179259,8.9587742693,896.514691285,584.698151662,7.69864011971,1385.68573501,159.339297721,7.21711559987,1365.87610021,710.51416899,4.78409925272,303.174277167,478.781837249,9.1786553384,753.458439747,948.37212618,8.44358428166,452.005986147,961.510329754,7.56602798526,723.365844128,250.403547397,7.70541719292,240.864404759,588.881074249,8.00368347693,1040.25187085,1037.68857106,7.94348796441,1083.20484298,902.840932593,7.15922572967,611.694615534,435.619810465,5.17919324283,1366.59064418,32.7343620726,7.30691198449,807.64471296,47.9308868914,8.4955205237,1041.46113616,194.876508002,8.73363038206,638.369183994,52.8866084711,8.20512782979,14.4283175021,288.053855898,8.61816467132,761.975870379,415.54786521,7.11814459046,736.628489712,682.934995261,8.02283062454,689.371330583,908.398580686,7.22904754614,131.383743955,264.713318862,5.94590654717,480.926349094,515.729413969,7.81623449555,1191.85601218,707.679164159,5.26980567803,1211.64296984,542.982708656,7.89384891336,295.306445633,731.52812763,8.02281540655,933.906849585,751.80930573,8.59392600984,147.674763131,899.24709891,8.03629459145,1123.70544583,840.814556423,9.02501473514,3.29650778805,597.768949723,6.11040242354,1050.66412038,536.039231739,7.09379328827,241.48241979,683.631615654,6.79756059185,179.417987277,1023.14766907,9.40321944864,1219.55840787,318.553462459,9.30580830101,109.200058431,219.350228795,7.39730241929,523.59298071,95.9468020135,6.81065059436,1297.66176343,806.314685197,6.98809471099,1088.83438806,876.614775234,5.50058820858,675.815564622,244.280659457,8.71709152776,694.111430301,928.087253176,6.98329089214,380.812687199,197.546187349,9.05707632006,423.558762554,153.159786686,8.38286524671,879.352733368,45.4759095567,9.06635183517,207.065104275,66.0279620436,7.33594381929,510.448722814,493.696325512,7.26678124965,780.554878535,384.705410348,8.33004031698,903.49925431,309.45420222,8.24660629758,1190.62204959,795.085035653,8.90264251411,39.8808377764,667.480180563,6.29916693941,565.930374209,192.877969196,7.81492706321,1245.12059904,779.477402042,9.52321048746,818.321143688,667.033200335,8.22429024672,375.44754797,962.34746631,9.74297850617,396.486891586,607.55404645,8.46108804382,1085.28946945,360.00480628,9.76810989693,523.6507952,97.564710013,5.50842629456,512.566085828,238.015106237,8.55914275344,879.118683045,1001.04494797,8.44950084138,615.516490138,279.917815735,8.57586261782,731.154245711,906.600858715,8.00483652342,292.461240147,380.008982335,7.6761298988,1004.03509057,744.695943975,8.99060988194,1032.98746861,409.286897412,8.44720791925,898.8110433,178.013163304,9.25846249308,101.699549243,389.257772185,7.63449244671,950.81065219,510.960620903,7.55143982466,1341.89655925,204.524382075,6.64326314228,592.148402062,685.30665286,10.2986372106,1346.67247365,482.242716188,9.6966972304,782.714572858,547.827213258,8.9326172261,773.500538107,14.3797922862,8.42422951908,76.2202715637,502.822165934,9.78234152384,1154.98840511,977.722834065,9.02579492174,805.244143339,531.19956257,8.20145082478,1262.0865491,1021.42716698,9.49611477977,483.762373666,766.323984545,8.30350673806,1061.57345127,48.2873475789,8.5414470189,757.815700523,139.24598986,8.63267869246,248.691962881,704.238135892,9.15482964513,201.046000149,982.005313066,7.86089237931,1015.97939781,137.633534739,9.45972760441,1380.67196281,720.946506438,7.84296059206,32.261502573,980.28630328,8.69499391995
977.876222371,127.19742023,7.98318119556,1372.57315468,136.752419225,9.84072660533,1147.28825588,567.487855441,5.45379704418,124.29685609,61.7765164259,9.36045410443,311.016031187,744.239270387,7.93424898341,471.278595595,129.01251493,7.96781086066,749.215004779,318.055258292,6.70377538721,449.062572825,666.234383581,6.53203722093,820.874558413,817.314304662,8.94466049578,318.623588432,953.150210834,7.75951443,964.94498754,317.37623537,7.48065476811,98.1912626151,627.889844499,7.14129769358,1319.2396802,921.385093686,8.04694677809,254.685572251,999.007133455,9.15189556341,213.507583491,108.531089386,9.15640905304,918.074990413,568.3092459,7.95234027625,1245.38517752,410.289469463,9.87919450749,1378.22579138,440.673873788,8.79418245001,30.3656854673,479.574797304,7.67300828388,280.644426688,8.39478305574,10.684426889,818.618160971,818.057295299,8.2169249524,1140.04267833,454.210627829,7.34684400339,665.64155335,695.663736459,8.55390739667,873.201764832,415.985119173,5.8398047395,858.823328334,966.826110968,9.70255530901,441.639336899,25.5498944651,8.87788801017,441.904786989,25.824926847,8.06613745391,1189.3921797,587.248683944,9.46286354272,1369.81494559,105.326362877,9.03973909851,757.825057417,879.990315307,7.30954452488,452.842484039,812.987499704,9.82004076522,599.76696931,338.30077435,8.4919149148,934.995143757,608.91600284,8.1259602719,460.320533136,363.201235705,8.5805651316,659.971889089,94.1835226754,8.42709996786,5.51836268972,329.397710164,8.76068073459,33.8700018974,486.75405235,9.63400282776,286.757505609,595.584712705,6.32736951969,1149.74031428,268.725250948,8.04005768108,128.239347747,36.7747107944,8.38531039842,95.4566178262,215.084365608,9.42891179522,420.471317303,930.530080243,8.81259612804,1119.43845036,963.798448242,8.68649356477,865.833527529,388.31680549,9.35694271211,1109.12519715,266.356026425,7.62018938551,1233.90302748,59.6219624286,7.33580083901,347.46367685,269.631340117,9.26439098648,101.350014826,827.362371204,7.55357305163,666.882255851,695.28294515,10.7312482668,27.4901337246,182.919865495,8.19014810406,1206.26337483,15.0663363236,7.47821884669,620.117939797,181.152131392,8.29410214647,1386.48278945,843.265439577,10.0581935734,482.942740536,363.658640242,6.72054880672,264.118835733,667.789815749,5.63578107416,307.239324217,539.743243706,8.16442039346,318.575518771,952.668631243,5.89850551362,911.512846906,45.3410340318,9.48056125067,1291.67168257,766.671177673,8.90524944961,1025.63234818,878.503532111,8.31929784714,952.578445504,1037.23343029,8.5322086761,1243.43335282,177.750896367,8.09559174284,671.065114153,576.936301358,10.0001779415,662.272034801,378.357878138,8.8780877885,990.567034288,563.14302715,8.60149971282,144.251335261,369.09601305,8.9279206546,246.750900338,813.150385158,8.09858190219,404.720429654,581.274668208,10.5134849957,849.464007054,157.076199929,7.70657159952,888.460554231,260.227277736,9.16267475596
1156.51788073,969.569883421,9.58926612464,334.713514291,704.407712863,7.84276653683,1032.70197,960.172639463,7.35502899516,456.16971808,602.816484836,7.79582984369,1196.53658834,55.4221317765,7.29360055821,534.826638476,606.717694292,6.86634532797,483.043191854,194.043009749,8.83446053452,856.552122004,658.647188406,9.11117305455,655.082001362,1005.25052613,7.78561087591,928.450441213,741.942564881,10.273231781,1123.66946952,816.87703323,9.46980758015,939.167641267,720.305283071,8.60492713588,23.4784043787,618.184948173,6.02998471079,1200.28004936,953.826957637,7.64979619633,74.564629811,428.045707812,8.49679483811,382.78915601,807.628411698,7.03696542546,607.799381488,543.528890807,7.45381899579,193.12256293,1038.56188583,9.05332642192,230.856148389,1000.83546209,6.99643845638,1281.75764073,269.43536854,7.97428186615,592.794776995,144.230162316,6.35365989165,1298.81920253,29.2043089036,7.46680261673,46.2971140603,1015.8928253,8.68953479011,186.838206621,600.269993624,8.67390970876,1385.52964525,778.585227629,7.82909355129,1359.02954221,491.158593483,7.00964562474,1063.69964505,109.564632809,6.65852996089,1217.14699969,41.9346508888,8.49933462051,748.139253161,839.922125175,7.71520152858,839.41603567,494.423343031,9.4534322993,934.612883395,521.604060735,7.65892026305,314.051902879,124.856265336,5.35431809484,1170.66121115,437.331686362,7.0127579162,877.334611982,32.8536819742,6.94667430242,440.059174869,247.483230299,9.21175002026,1369.45338286,593.458549688,9.90586220405,512.039424229,413.563574811,5.8990370897,1059.45579608,437.026399422,9.19401557175,804.760262901,689.971229335,7.97918444631,367.569771235,0.852241323395,7.32914776408,7.86887105806,144.322113904,7.24829291133,1268.89970928,746.720764266,8.81373682994,334.320533078,87.5502722288,7.69556469623,351.242089082,73.4729063212,8.22930332332,1066.98430992,500.430502044,7.96151191442,1162.78283361,577.240401583,8.49354293169,66.7063282039,20.0336864665,10.0738882271,645.339500937,489.867748958,8.02538853129,470.843544924,847.684174361,9.12575160559,209.033065126,223.949240373,8.76103360142,641.197039071,649.145119186,10.8092558696,1228.21986603,271.041055474,9.90158545085,288.590855311,367.456199283,5.94524620567,644.801515868,128.797625544,6.66096138391,1228.29796082,397.063029739,7.3856999917,1233.02278352,934.537859493,6.23699817173,1375.19983302,759.471697711,6.80402763967,162.698648781,235.258659737,9.05763919979,680.28990423,264.992558368,5.44161611349,1136.1109946,599.272134732,7.49795694151,611.721210446,358.68687134,7.89493591654,333.800052459,969.15643419,6.20556059172,189.691960283,613.532953914,6.90135519423,479.096759944,339.414872754,6.93508923401,221.785051679,800.886257589,8.05101459272,756.00526097,19.3507949272,7.45096553063,185.403180471,589.013428414,7.13390459368,1115.05643816,122.549514989,7.19454572049,901.54150184,656.320435597,7.43332735671,1021.03244984,790.458689835,6.22499104737,202.613381092,326.576371345,8.94838158065,42.8415091659,1016.50717693,7.16231185318,433.284397059,44.652220785,6.56204822293,97.4243443694,651.157011529,8.90251938634,981.061767305,890.953673009,6.95003938522
95.9918148929,618.870106105,7.35746862154,185.720439684,371.366942651,8.70468402609,803.973080264,332.451957106,6.53867012571,803.723937801,274.843832339,8.02052244517,414.735990033,530.030354146,8.75805717053,719.742048223,481.442164627,7.83399929625,684.882935958,592.917552091,7.44171036634,1171.72708945,360.600430212,10.060639463,1112.25051138,683.114676322,6.53006430289,820.298207096,716.49772838,9.63431038115,93.3778494989,59.458798063,8.72446672129,80.6603758695,986.295335696,8.41877425925,242.415281472,33.7719669325,4.13487079939,1222.70508173,296.022798481,8.02848573504,1179.56933881,682.909399291,7.83387136308,1216.10763782,730.693431198,7.6999931286,506.26134069,656.252910042,9.21921271215,1096.71980657,18.0435351474,8.92899085674,52.1876731908,160.85512911,8.09250497649,888.546064412,42.5406849874,8.72841461951,5.08389172605,550.326566677,8.15960030116,1235.82604977,684.118659888,8.21414264571,1260.50319044,527.819589213,9.22686897594,430.220768095,56.6577930935,7.22245730784,980.229841056,330.383347658,7.35220010887,58.175553679,781.687990263,9.08763207176,882.659662053,446.890350601,7.95467077261,58.0943467201,976.718075411,4.88956278551,1217.78139577,247.497755801,8.985170082,1005.63971933,990.085823485,8.64753911546,80.7550033199,527.416542422,10.7163537522,447.786005412,199.508774329,7.57605603843,205.531788405,176.631230045,9.40788202417,373.380267587,216.498208429,8.94095586316,866.567203345,324.123206711,7.23854926516,414.750002598,528.420107603,9.37386660276,439.654884981,746.194061044,8.05391846474,812.004980144,423.254979114,8.34166337243,655.360283792,37.7085183246,10.1952861229,921.211818733,404.673794036,6.38152896319,973.280972382,663.677388445,7.7362035766,1024.27110482,8.68117892772,8.84347348733,828.893075096,185.760851697,7.88687767281,969.021409319,190.118764338,8.38037409318,1380.63552124,432.177866137,8.20076512993,1191.14433783,1004.45635629,8.3775158143,591.526472436,969.130862481,9.07569288609,1144.45925225,927.190705612,9.42238590684,330.674736678,255.839254865,8.45606623311,831.879426116,899.678166782,9.23908680258,342.575912791,957.042826278,9.89342070463,164.049259132,327.148639337,7.79581191578,14.73862248,756.484621168,8.88161659603,1325.7675344,418.890561477,7.42013741711,1130.67280114,310.774368081,5.99671537508,575.462835928,683.047268264,9.07697213661,1260.18367853,83.8710843714,7.83351986211,380.696175236,511.865410222,6.89396885423
1223.49083811,615.033572624,9.29072109538,847.524606059,301.086987333,7.8431958357,706.877070777,398.090455619,8.11318928364,1125.79845165,846.887790142,8.81228809163,182.771655805,1015.23785154,8.53168360485,903.716395543,134.089146225,8.22781325904,842.044465857,94.4728246559,4.74255143925,849.00294721,551.786160716,8.55658587434,284.177118795,938.493815986,8.68666873954,188.938959081,171.286510142,8.53892333468,225.38435105,17.083410294,9.13936754799,859.736686458,737.69225098,7.8032182022,56.4719404403,822.836306831,8.671051412,966.927821616,578.807885464,8.60979196422,772.92160803,303.937068881,9.07227809105,6.93677626131,299.85777835,5.38203906012,496.063924448,630.854475209,10.1182896701,335.413269639,506.942734521,9.70637634209,1342.81829183,883.679127601,8.97790305876,400.326329094,421.389013664,9.6461690708,258.759125339,39.2361863326,9.26071538974,1182.98163058,965.270763949,8.85025024009,28.5945076903,603.804312474,9.78640120254,1375.50034224,572.8725572,9.27853424871,753.879621809,869.737334054,5.44090852074,265.303912923,653.69627951,7.9863589857,451.582203991,315.505881777,7.65021185121,1260.51733778,983.870139924,9.11084865528,1347.6067676,694.766122692,8.95977869831,1097.60168323,590.740822316,8.23612275783,578.318847036,531.823806425,8.31634519216,724.861710631,408.537876937,7.78868790792,981.812377302,82.4941515745,7.93859965435,89.5055538396,1029.53511771,6.37942374467,482.373671037,102.219070738,8.19136939464,347.705158412,795.591065044,8.48751531475,551.671660766,102.569359804,7.64442043593,1198.39979373,149.636705275,6.89466779435,619.270298638,952.970769605,10.0823374798,889.392733124,872.631191959,9.5649634842,439.747137222,71.0955325875,9.0645902093,871.450581616,379.469262986,9.56741660855,538.316729592,236.403838394,10.7774272638,294.264784596,962.177520773,7.49035265456,1223.63887701,314.013279348,9.80052442244,495.264305618,481.692373891,9.32311422501,946.243361555,35.3793125152,8.36257604268,46.1841917793,125.955907601,7.17252967924,155.436351705,265.408612896,8.42065019101,1172.74433362,762.871760153,8.04759060103,693.692795529,140.554896831,9.46326783991,1042.67186971,512.568640418,8.45932669237,53.9957310497,960.009084766,8.08755018057,1093.04160173,262.257814269,10.1527817089,20.3727165293,698.1589962,8.18493619265,1187.41537737,473.51786657,9.15353836551,173.473866916,746.736253373,9.08112377966,1334.6773627,1021.5672755,9.02860314017
785.029350355,47.4105197445,10.7267864239,110.833100431,715.176773134,8.59370535366,1256.21937989,1035.50819194,9.61657012443,457.185984196,383.732611851,9.31268665197,606.033886457,933.79122817,8.96981410202,1154.34242751,601.96579626,6.30220063129,331.328244087,129.824368574,7.74430730929,390.820243685,92.1821617365,8.57363178809,419.488609674,607.928249902,8.49473486403,275.523882857,656.683799983,10.2211160886,679.711036494,94.7373802039,8.13390364054,847.062275678,387.686043203,8.65204415503,608.866848354,740.35982143,8.14516588833,226.752499735,1009.34960144,8.45452468054,379.542065922,840.950474319,8.53167857255,496.674670963,705.697136775,7.86358443269,1252.10851958,494.434929645,8.24951753363,103.989374287,135.652625442,10.4360104992,585.696481738,167.830586733,6.95865752734,1237.00734921,855.308435735,5.61986997627,1024.01643609,937.604785669,9.8680403693,415.567281004,795.387463272,8.41906205554,123.244284372,634.084310476,7.28165884976,1139.22673638,771.229016342,7.7778051216,1142.71677461,866.628516803,8.17340855194,864.455534796,584.504088201,7.32061670262,1258.97848581,866.069505388,7.01546580038,941.691259477,305.300314744,7.16318900349,297.871851846,293.505863304,10.4059157408,1177.07339538,781.603206044,9.81637028552,1077.21080356,887.033169232,6.58531832137,958.086213623,434.976518839,6.78782391678,396.089936154,389.803120961,6.62099568889,955.796587055,970.173964814,8.10199568397,312.699741428,91.5886914894,5.49793250948,618.811743258,546.767815814,9.01868006322,710.065971397,977.104128292,7.84163041031,775.083844951,438.047948555,7.69398930741,624.522270384,226.492435722,8.51198743531,344.583497959,890.797459567,7.78389526371,820.503358749,722.539053335,8.21637533857,1204.95664431,336.463000538,9.12830340445,505.645069239,495.088847839,8.87908321055,700.81695292,423.147074161,7.81057072083,450.748026642,805.624345266,8.3538877259,1154.46559738,757.946998979,7.88964729723,795.963413135,724.40061306,9.62919927788,124.907874895,371.093821408,7.24263096638,1230.60295851,658.24820712,8.21124466124,1286.3077243,496.128962799,8.14396447447,595.135854616,86.4614436105,8.54438010351,249.627229824,276.838783047,7.78631256531,911.578252512,196.604388875,5.40567610232,1171.77308491,83.3005140661,7.48763215969,1182.67447767,194.803757986,9.70351425106,1122.91168309,973.693609052,7.02896783674,554.246543374,725.510853783,9.14313069749
715.795660951,291.129260632,7.00704910226,728.142926929,544.595313704,8.6110845706,138.769985374,920.788288229,7.45774848031,1101.8795966,43.6508386171,7.40726429203,1075.1838909,610.600259051,7.61141933455,1228.29689386,719.636354902,9.43323768445,237.4977195,192.553883593,7.99473379455,487.188173307,92.6189315471,7.37975006922,1306.14077244,499.249429173,7.38552416837,371.089745503,622.306936592,7.31520819854,875.281413524,320.619748836,7.51267716252,504.329399913,530.47136138,9.91735234483,557.29263439,740.140564018,7.29802846844,893.708503252,886.465840923,8.47082356856,845.957230545,694.945143014,9.15961651773,173.078030414,537.58456286,7.71944490218,191.707103137,463.918020923,9.12057679906,1275.52904601,531.759493426,10.3305011143,161.368202734,116.866162847,6.0435902351,1128.5023403,990.013409748,7.09352542166,704.810172833,0.0673765872036,6.93115071721,525.879936834,912.58171287,10.4248561905,575.527060526,155.118245643,7.88759668082,755.96749198,752.826825272,8.0569909936,1224.14925301,834.381426474,7.27691072074,762.058923495,668.671899483,8.34617625193,293.191027629,443.860798922,8.02657118302,1202.17927047,284.521838819,9.61778239506,727.022717399,529.460723059,7.5014143927,1348.54878977,847.604925506,9.87211229397,1385.93604069,445.916035463,3.30437409308,739.375264632,0.431690369915,8.4166040924,1085.49528517,306.119516129,7.63066763392,1036.52975799,442.929245024,7.02215416898,409.162442841,760.340751955,7.47841770904,80.0639596741,877.098942309,8.14514277691,734.807660451,349.40088489,7.69426718684,667.76351979,1010.1602525,7.65074941776,52.9123494503,123.989510058,7.83494961463,1334.47263125,246.639495691,8.30201871639,778.293507152,1025.27620618,7.61728580556,220.275062221,953.930076457,7.70902733738,308.104123262,343.716067822,8.76127390394,777.368027874,819.901215274,7.43833297666,881.416039636,318.038350547,7.77681426223,553.720019042,266.258147269,10.7199559831,1372.45210953,943.354597089,9.58425072956,68.7051402895,691.510319542,6.52812549069,1228.03131208,261.773667109,7.15966765646,474.700946939,273.88784789,8.12485974944,600.742695766,729.391774473,8.54809812482,233.370320113,607.749837736,5.53049467233,1379.32358917,104.073292362,8.11384735444,515.514646426,635.99915598,7.58665461493,269.96885271,233.963640046,9.42054701848,643.593969821,866.400073284,7.5870964617,700.029500589,93.580775823,6.33962071462,1039.0906682,442.160380479,6.64132640524,1054.78728997,89.8960627907,9.39168361567,336.93291149,347.229626601,8.76266274419,601.866398265,355.914263029,7.5747421246
961.581901828,115.576041957,8.51684311831,178.751948068,559.627336916,8.06827575891,756.929414308,249.925948253,9.83783369796,5.94922962654,286.202018819,10.3233952462,1351.43504693,945.545966646,8.11112797506,1376.44620091,841.976975101,7.30559383171,952.430849169,439.387463277,9.18234598337,481.079957423,158.903350373,8.47343701282,376.418212661,85.7228127729,7.40633473034,1259.90249648,16.118766451,8.62107309162,530.929272123,728.32300011,9.8865412849,1374.80120125,725.6001137,6.81737235274,1032.56584188,923.337717329,7.60948170534,553.273678039,220.354102055,9.40213870567,634.755263164,887.566764448,8.28884461912,827.179253719,79.5260232371,6.66648876275,649.854825624,954.835878673,7.61630979625,999.025780901,407.608272941,7.40601882455,284.479423583,126.432124928,7.60985544813,605.664409412,354.166019908,9.36452412121,554.359263518,639.801977636,8.64020793756,741.483557093,191.366821359,8.65560417629,1005.98911101,519.264910979,7.91567894599,42.3048881721,344.331033434,7.76223569419,331.864266137,554.192905663,7.93511725972,1052.01013246,227.680361902,7.11806401783,988.940950856,707.011964169,8.75957062946,836.080426482,963.905026301,7.24692858635,165.635770635,399.928819134,9.1785234991,898.117268121,779.562295798,5.93401805143,1309.59561417,574.960602111,9.41658083153,400.646844843,825.13779251,10.2640910275,1253.18169748,980.985824714,8.26724245984,831.855232595,229.173932446,8.53260904788,696.231968188,155.361703291,9.6409607519,1256.43721989,918.81704668,6.29742785931,746.530171872,1007.42776108,6.77582193382,677.508510116,15.2181011698,10.8650223154,554.614335266,917.36995117,4.91068947829,169.944994434,162.71284623,9.44110749432,45.5546365679,527.267517642,8.04912678131,265.118111815,1001.20820352,9.26738435357,1356.17338577,678.044432855,8.94180858051,166.136817953,551.849649133,7.06645028443,130.56558869,26.9652330782,8.81097364486,1237.92775496,133.945064165,10.8351339176,37.1631118052,891.078794846,10.0377993596,346.180606495,375.849120847,8.40560799537,386.878835515,857.891630836,7.83205428209,198.003683557,665.680816952,8.3516454344,520.529683627,20.5934301904,7.46490900082,1239.88647972,515.233571985,8.68294004638,1287.25318574,709.845070566,4.4315825967,846.63011952,327.889152035,6.99902451955,975.426144676,532.943713012,9.42975617287,773.922053363,667.488265633,7.66223001219,321.634049646,130.608266723,8.98951051655,311.885822474,852.433244229,4.01398429235,4.97101187676,436.423940202,8.83727983774,73.245972032,820.087521014,8.59657638683,730.742772036,906.526812364,8.11754336953,236.765522934,960.840101238,8.99711065914,1144.32729864,279.564295375,8.68093176864,363.377734947,331.318755276,9.31218092357,163.937277591,57.7606874242,8.10018509349,424.196367926,506.932834315,7.40275290603,934.633518073,765.883232775,8.06399435236,1315.86032184,715.031365887,6.8545230064,1142.63654661,616.8171795,8.21232532723,415.483772755,560.862086824,9.8668460803,1071.56988633,556.623014589,6.68254602081,142.053905668,1025.21858576,6.40005850861,469.342624657,718.42414461,8.38686224458,904.501071799,245.917720663,8.00633535331,1330.90242972,316.706472721,7.78480814691,505.362634233,998.582252047,10.1058956672,152.280301244,821.717800431,7.90436523689,224.179038757,277.150810908,6.06216849901
802.525830209,325.089867582,6.74199860538,1305.37742945,279.585988231,8.45138514957,658.508791641,280.88076349,8.11073039805,275.930265052,951.449997028,8.55913299232,1251.06349536,525.154826556,7.74712644179,529.58559302,839.255538907,9.26957540029,685.643617723,52.0663816284,10.7660269839,168.914200954,670.471907566,9.12280664642,878.009350492,481.522148831,8.1229326681,471.095501406,633.262098041,7.84099183392,1040.04268122,319.796081039,7.99110315348,1383.83430551,495.554624919,9.27202953975,1033.79799782,490.999877237,4.2170032895,551.222952679,499.282523918,8.62122485201,790.392964951,676.584245621,9.25657874447,788.29680061,175.364272486,8.19722267559,907.905027705,749.857892015,8.93646688671,170.810961681,581.688258282,8.0827514512,1178.35430653,156.120161836,8.30069637098,1174.99410675,828.219914204,5.98455976003,945.437468423,548.188078899,7.42121922478,989.858443178,187.010719902,8.27198229863,949.709056056,974.416786644,7.24894853282,668.561680905,364.047210615,10.883714339,924.57469933,691.144562204,9.06454496206,995.071153909,520.386616624,7.20014891704,1092.36610366,630.429010306,7.9374085002,707.009047113,968.665220027,8.1128060922,29.2267261367,91.2240395316,8.29126578185,823.204037163,981.880455515,7.55455856461,215.231020372,37.1878011009,8.5512201544,1337.06058535,127.214374257,9.98054994458,533.775910803,953.694155844,8.37597496762,571.20108158,583.951788022,7.10157689364,1372.03261809,807.013933388,8.09603385538,1043.57128698,675.533058096,7.46446010812,375.555330323,824.64111288,8.34279051936,1263.89589068,612.760133986,6.87335937079,851.286658634,379.380122679,7.22919159363,117.190176506,872.402221424,10.6526785929,1078.18526937,260.271343673,7.04015957778,725.537350958,717.502627081,10.2540055459,581.789314074,999.037142928,7.50798738366,188.792350984,834.996916522,8.90737499392,1057.71852783,843.908640474,6.69989825926,119.637047291,85.8797700771,8.43295810205,384.966789952,100.723686937,7.33603069667,409.36407703,441.639721047,8.12603512348,335.20402397,665.743488533,8.94601235678,1216.65119912,4.69248586448,8.6569894403,1034.25189745,208.079593573,7.88977214705,905.987323877,826.458093926,9.83053208605,1113.88775712,392.939314619,9.49407088281,810.654913675,448.174089995,8.95614637291,194.267679208,237.563915427,9.30061607056,149.238250642,676.77798828,10.2346193732,1236.78699631,850.656457125,8.84013384246,1098.15418315,551.742812153,7.9827881356
531.831588641,689.883450667,8.46774391112,180.010250168,335.41022227,6.68352865898,537.733106669,990.801551902,9.51456756239,238.944507912,415.111206539,8.87305742997,55.6249662536,185.525545304,9.69779508019,1135.79743893,386.495446267,2.34085633022,369.272182059,980.818621691,7.66373696265,8.75837324153,60.5081000173,9.36797727753,467.593210629,287.473793689,7.85019334034,1078.31075022,124.980542704,9.13413282573,1205.72354449,853.613090609,8.11731657374,1051.25215292,568.815088005,8.47115219654,206.950548224,607.836517502,7.26648205495,637.230839411,12.6786057206,8.5137413832,148.446090364,917.040583476,9.0550253454,4.63716317217,999.929965126,8.82616000937,812.120425547,148.871113718,8.97891482286,1176.25792511,989.765544767,8.8211269079,646.28999863,225.07740405,8.81156204354,32.2115796828,767.367969289,10.05007762,755.129618569,916.921838511,10.6248556227,338.421641281,49.8156070032,8.73794484035,978.001495629,482.388550126,8.78622687628,1222.9357953,296.992298739,8.80623264093,455.227455383,892.592796483,8.69481241553,610.849617661,472.136591312,9.5260035836,949.407949056,60.7627468251,8.58677190142,320.781110876,686.865452372,8.12463135391,860.411264855,720.684935188,5.90078561799,526.569854125,194.432869545,10.7639877865,756.346500106,415.559554406,10.3182089994,141.845704897,790.708199895,7.72413905389,1121.96724153,962.381458412,8.38009312379,742.086205108,221.286052114,7.40022456886,995.717856234,637.364034059,8.6190687026,1354.54571423,712.911031511,8.30306345181,1223.24273044,267.408575347,4.59718554416,198.851774989,832.223488023,9.27209547473,47.184632543,869.066758053,8.40412442233,611.472068522,1036.26467658,6.56977874013,149.519092678,304.681751236,4.45231588709,52.5039445426,770.088421382,9.39808762384,9.87005989233,695.493518394,9.92059510181,687.403082705,13.1399445964,10.3429467938,283.606020326,894.17681421,8.40086761541,1073.49242675,481.456773986,7.96806347955,700.376260525,685.701287011,8.43699581134,716.665644173,858.23754353,7.515882193,451.301193779,985.648247787,8.7691712374,1291.36845628,928.591543757,9.20202467122,298.465842264,546.475955715,7.54639513997,1315.87972496,149.769698263,8.05643383034,380.481057292,362.18219322,7.88025662916,1282.63387736,850.77352251,7.67301730955,1351.7750822,477.277607233,8.69263417128,1080.34441256,864.143345079,10.6508024579
785.695900798,454.135021879,9.85262554165,47.0761274861,987.320941247,8.48519128811,355.651886206,639.156095514,9.44039973482,365.213485375,351.680359787,7.75279222146,191.533564854,284.27429306,9.52195729968,149.377846628,949.995218728,8.8273644491,72.8506443029,158.449611251,10.085419759,462.399653614,337.230490791,8.22356966962,196.369490573,251.662638716,10.2326569505,1023.92524121,582.001931118,7.61740631675,1259.63733448,644.147400881,6.67464241457,631.779352921,272.389972101,4.96669374131,269.927658667,667.687291282,9.42296599103,952.391411079,509.237577313,8.8913510431,211.265926685,219.674899305,5.58681010548,457.511780142,1011.71428173,9.64538614871,991.150939543,542.739279657,8.24881951396,929.831178648,2.19090926358,8.69972702028,443.537109495,912.706545273,7.78231704319,1234.54246943,262.02485105,9.43218161348,435.881613829,788.221630816,8.03904681568,1274.30983615,180.502006633,5.93177117483,1369.28886611,33.184884584,10.4367685671,595.955735796,798.016853695,10.9359049801,439.676214553,235.49343323,8.57664632859,257.687038103,687.390360091,9.17324655606,1274.83419275,849.703868929,7.28031030965,942.431124642,117.070347096,8.79586862837,345.554515606,441.510306298,8.36801718347,1153.14762181,801.915044165,8.61418076967,1347.387084,875.492819866,10.729902182,1159.93797441,364.56246771,8.33233512937,124.172132538,61.2851317118,7.37051841628,707.443975515,272.738005508,8.60211704592,1182.47445569,540.890444515,10.0691804286,702.430975082,208.511058285,7.07949097092,690.522047382,276.585579363,10.3404799446,371.802368665,130.838427708,7.90793696104,514.179701608,652.351868546,6.91785434137,976.692988099,711.248476531,10.0335660117,678.483510971,436.569799563,6.49002245442,1348.30676347,360.659295736,9.80030616205,21.7931166847,715.731278887,8.03685737651,571.88972608,317.170790536,8.62483851485,1184.01700232,94.3678606621,4.63408919082,1017.85279874,321.046105539,8.04389446604,756.884441527,49.0164091985,7.93043179898,234.801332287,622.690072383,9.66730210506,793.485281416,53.1645471142,8.6847279597,1346.29735106,966.472502186,8.87452227204,1227.93174219,435.142198381,8.86119445263,4.68141507772,517.209089657,8.28308538487,930.488728953,466.728423307,9.65280876918,1110.58466574,340.674724453,7.93419655138,80.7328948627,340.087474712,7.75404227701,1355.99129301,927.105999366,8.2248094823,406.473322468,320.923615052,8.22879390799,1014.05373837,777.81007343,8.05025635304,784.355490429,800.543939194,9.60206283089,627.876135523,940.673734413,7.61431338384,770.35008859,211.809836824,7.07018271432,281.140377101,41.0160149515,9.41199837619,1285.90123987,515.812559904,8.03030352443
1079.82557182,463.537349553,9.82284856296,1016.16857329,1021.3989652,8.48062515371,701.900762708,66.5642537781,8.64019069974,668.859352624,377.086238081,7.05697238184,251.856717834,387.423427946,9.42621694998,992.986663084,937.53847387,6.79940560511,351.71367997,301.040455364,6.66995905698,679.109532792,112.70221127,6.70175274968,293.28141936,187.820075709,9.79437379608,773.78885643,146.686292196,9.79483801476,70.5183069152,636.150914774,8.42141550409,697.227679879,521.548051201,8.31765125922,525.556458684,322.617135282,7.92299923029,303.49683352,856.730185752,7.22104277413,832.904269944,964.688764343,9.68037325548,368.050691444,684.825586248,7.87017470328,469.141278966,275.675537393,8.2505901908,930.659284362,333.761394019,7.77018039027,253.669053563,431.436704416,5.75816468643,112.596664175,566.344647319,9.77241477889,586.778336831,645.174762927,7.2676954863,1065.88798796,63.4873019644,10.2069675218,194.745371202,813.922662754,8.39275455543,592.971355651,72.3979674846,8.41176677401,42.5264153708,228.164158043,6.83447768446,68.438650156,569.281564472,6.44504419719,820.630787359,730.244160741,8.71038043748,655.489086705,855.459965436,8.99090275921,235.355244716,825.074679446,8.40829680987,101.862279558,291.784623865,7.8700536679,1119.5108289,455.764429105,9.1470870938,363.272701037,638.222483636,7.40909293608,1176.925547,873.301680911,7.23947528646,1261.23209472,201.210067679,7.36386823416,1165.48764944,610.619379016,7.87918794586,972.2945462,999.860025073,8.33346759242,727.795151757,800.772308423,8.14856743343,1026.30504464,113.743909807,7.74241512406,532.394298698,559.315627254,6.12516268072,758.843615351,396.351055241,8.55922168789,1124.09245088,1023.12175094,6.98361919632,1080.48563221,41.7840766987,8.48296145099,23.6350923387,292.575264404,7.92082344507,318.80131937,181.432974228,7.75001305943,181.471590889,244.914032534,7.77038129815,812.056704827,681.523001154,7.66627201828,521.070107152,979.492754289,8.47055325252,687.021376231,613.252299095,6.54771355643,287.577348246,622.345561862,8.80426131565,1080.79187065,683.978954892,8.00305957743,329.250628507,75.9441820809,6.76523800076,713.644327837,978.681233128,9.17213341251,1097.31401758,266.986827179,8.8430364885,604.006691435,532.367808763,9.86589708046,286.757231154,633.990262179,8.66038213225,791.587170837,276.90192307,8.5845293242,618.146450496,65.4644242204,9.32495434492,370.978113336,883.204915703,10.2105078188,1193.08522727,744.908169209,9.95263771046,562.238589484,10.270825096,7.35461709375,923.958691916,874.310413303,5.44966710821,1068.54856437,889.959357408,7.76437070057,1158.37244831,180.540130403,8.12144722322,720.914642882,86.5408652719,8.19879826389,1239.78126506,461.197362727,8.12420123309,217.128232319,774.416840721,6.23062792698,318.979012519,593.846628454,8.08227550821
446.869091119,84.0550791634,7.75938200538,1319.32232103,70.1382474378,7.93666572514,32.8634910476,72.4659851223,8.54089540335,987.468449775,0.129446566159,6.55060112995,418.253705875,622.126596993,8.83733471807,1048.69153696,614.154043281,8.70387623941,1180.34153906,500.144704152,7.47511347462,718.019607894,278.760165794,7.83128629536,46.257864659,936.645432381,7.31269367737,3.52837778755,1026.1952635,8.07649047109,368.097771623,10.6244850531,8.43414174532,10.6421962675,238.575433153,8.29375605542,1151.77871045,70.7957395004,8.32123166101,218.533983549,771.386473599,6.72107889044,1301.84762565,390.498507818,7.92465927485,259.262092033,529.110163971,6.48945374499,1040.84410256,219.163293998,6.4959852376,226.953329039,678.663891656,7.68614945876,416.206216817,337.209092371,6.11493119202,738.266578007,366.716468697,6.4326813251,46.2154802478,439.077105293,8.24338773955,186.937327862,1031.1842187,7.27393180097,75.034314203,25.4623757325,8.22904124948,364.160662447,262.287575691,8.22572421961,587.660952256,882.251584972,8.68548183005,1168.91012403,544.937622601,7.48120254158,171.584809083,330.605028799,8.35814178276,316.136035128,1014.77459583,6.06583129475,822.865573387,579.881173146,9.47185631021,573.741038785,398.728396683,8.44569029859,73.742988795,607.613291507,8.26951815161,732.765177595,35.509245093,9.34370755418,149.306848071,274.48616336,9.54722228321,85.3654290621,454.419430643,7.83270662405,1303.42448169,261.509676315,7.05002742798,766.196242897,693.368153643,9.68635814457,250.481854479,838.639171205,8.74474672892,272.670526933,987.326574453,6.15087584829,834.359496844,950.051169221,8.92921925888,495.222646946,259.993283302,8.83368196595,742.652660493,894.224055936,6.682284187,1217.60950548,727.321337258,5.39842432115,189.658847508,202.812177824,8.11313782541,122.940665514,469.351345467,7.03951817624,515.599121519,999.099093186,6.27355707237,1035.15888706,1001.26914755,9.70507731067,1387.25666486,636.502194251,7.30658378139,571.224567809,722.408100479,6.68553059151,932.308436309,231.13013594,6.9755816537,1265.95225536,937.465645896,8.50901246361,421.831480353,868.323806817,8.1014764561,1281.42749334,544.07784043,8.53250710274,611.995522009,678.044308761,7.86061074368,308.060929466,918.324713722,7.55721755745,605.688716513,695.830694112,10.3363017597,848.290205485,158.444700751,5.55191670425,715.591096212,407.215096574,7.76542310709,863.737190493,801.054024888,6.78391197797,369.758219833,195.942372298,8.96451782693,221.432773577,1035.86208403,7.16101430513,64.8455121306,703.293471888,8.01883835351,420.383636646,547.995557691,9.29558538377,814.658015524,919.153773932,6.03891179356,647.623362325,206.264854034,6.63321007545,898.431263855,733.351002006,9.41061608902,476.167600312,577.19745524,7.01049267512,352.171971185,399.473634984,7.6744014262
654.605898903,421.193953067,9.36598816486,977.971036953,1013.86367522,6.82725821254,114.889892858,302.722319999,10.1484644076,400.944024167,255.378570483,10.3309872057,976.973498683,812.329864335,8.26015640513,418.158955263,936.437707084,8.48165209578,1305.3703329,1005.01691638,6.50631326895,718.707793617,346.346613102,8.62194338401,1338.33661484,6.22243510924,7.9907091621,837.338454491,145.233757618,9.88556474712,286.901475744,414.848853446,8.21090473531,158.682252466,547.689776975,7.44133950383,668.394471424,22.0743545729,9.1047026665,366.781841144,181.789865075,7.00397867716,328.010387059,499.355835645,6.64646950392,1128.76717418,14.7870082767,8.24538979072,1022.53868122,126.177801014,7.59009976428,89.4135849209,482.753823668,8.18066366727,192.334896543,53.4067840336,8.99730705871,1293.51561436,925.819885267,7.64462298876,1180.22001388,33.3504888725,7.72548052972,921.335094164,165.394163008,8.43869460497,692.233319243,394.353479633,8.61828782264,208.964299475,573.939320828,6.82313530092,177.429087519,1030.36847426,7.92016267851,1198.41731196,870.915417199,7.46543370141,886.26213994,690.263892487,9.41098996035,661.262809004,454.436743407,6.74507216066,321.895324411,162.19301834,8.68996443589,389.180420867,796.053421463,7.22182390402,560.06875714,102.69402207,7.99954369083,363.506542274,984.374232707,8.59713552757,347.463239567,553.344585308,7.45594860946,749.781330682,386.034040607,8.44628716039,61.1642296386,168.614438947,9.31712351047,581.842668076,571.01753248,7.59051692775,209.673480364,1007.52865868,8.91251722879,1197.42968104,554.641641785,7.40968578839,1142.3220765,262.22181067,7.5448986904,1116.51904091,275.794244636,9.04369286356,892.706270297,536.9512487,9.04235468139,521.274392494,146.351208301,7.81092415407,589.592287917,253.65347057,8.6882966279,230.347198316,513.187896124,7.82965595862,304.469495798,714.477857667,9.16685908305,1107.84081013,193.879888553,8.17151216395,1331.19513658,812.699755471,10.9338028227,1239.4647433,361.375875065,10.4090123829,19.247589988,230.168697873,7.10987574939,983.687836896,529.629273737,8.59264852568,71.5675127442,100.665834705,8.10272122429,1379.88751187,218.180969975,8.54110372078,1134.68603578,1023.67684172,9.39965167696,1.05419324849,721.814243098,8.39754450989,156.810351017,360.694300822,8.3914166839,595.101699907,267.167697494,5.85193326171,338.721736499,269.779708408,6.06249662392,146.08883902,1026.23193891,9.99635628771,1364.8036419,173.999799241,7.77109200159,815.445943297,164.119023701,9.07201350483,729.853328487,802.271325776,9.28376658213,1042.37464691,337.430934442,9.19889220494,971.686157719,875.944623603,6.9961237652,1144.61711661,450.917368809,8.19299341917,1390.11358172,688.4268479,9.3625475083
1339.79703838,353.988918959,8.74790142506,855.81830056,874.232002079,6.47793875266,528.730397811,463.721719431,7.75809457048,997.137349128,959.650760945,8.61966078885,530.562096186,296.027219571,6.66746869158,107.861022705,400.923113732,9.80306446568,966.29209622,626.797779996,7.12466535946,1348.18847693,203.075328677,9.46089809119,361.459286766,76.6822017659,8.36543957407,1175.61687579,1037.35188139,9.43338868979,599.50694768,812.23880472,5.91330450213,1191.79039935,795.330400518,8.44619674368,1348.62151629,104.486797464,8.80208053295,931.804295994,44.9436857583,7.22055355947,393.795194826,963.767712479,7.88576679694,1315.09561442,1035.6214647,8.58193167427,623.186975168,285.527142451,9.45973502194,947.84495123,853.930400471,9.07020217123,635.400894267,848.121278175,7.38167522048,737.217102956,830.937238307,8.28158472742,754.351683401,469.920015248,5.57110975003,545.03440099,873.414901394,8.34611889867,713.208955006,678.958188826,8.31597933606,427.191111949,253.488145379,8.26322763567,433.503140298,1031.72827121,9.29967469922,238.107965687,243.077446907,7.50882952407,1037.88844068,99.8244475064,7.81944412964,1379.80773729,784.461423591,9.07827826275,1199.95408854,107.169012333,8.10084976272,708.826564997,648.91204304,7.87108216156,517.580248823,167.376656151,7.54190991699,381.701181004,68.1125263724,9.48940438415,795.871739515,208.543113888,7.19930152259,510.696239813,92.046553541,6.84842754384,588.679217567,149.475543181,7.30045542939,780.408840542,37.666513667,6.87338018018,820.483492772,416.619848509,6.84509896878,170.763491611,921.167368473,7.53758751282,120.211274727,133.185122843,6.73640190271,167.481444226,522.432950859,8.43957827422,966.737348977,514.152749554,7.21815907329,781.313653947,636.218729666,6.94275795675,654.322437148,553.938048327,9.29334041801,159.885005647,780.633704629,8.77237070566,1212.05809127,681.359764051,7.56635523983,319.584983029,691.94131111,6.9464512831,24.968126756,238.733432984,8.42699365814,1303.39614074,13.1059757659,8.91542134117,1381.72910322,630.495438688,8.35685279663,1148.20003675,663.693039109,9.51839683737,141.8618852,160.744880749,9.02053243431,397.858296136,322.187627056,7.50307079636,880.774958752,520.83097092,6.91877392427,589.885970827,147.136705418,9.99580454435
267.348681443,488.565829846,7.03708568758,1124.70247128,669.248076248,7.38604342211,852.280701075,580.375467426,9.83674619511,807.225257155,199.390843623,8.34839217504,617.273205801,549.253974795,7.92391580091,571.50544235,711.606862727,8.36968692185,1301.35777444,381.067423881,7.76659720596,239.521269153,1039.12953128,7.51133105791,1016.30799497,923.222995294,5.43255341515,176.700668683,826.250181724,7.32726500671,389.390939489,217.93411733,7.33439436657,277.410799037,351.576519572,8.55533143341,277.455078104,45.0426484102,7.19948839867,1235.19567133,1005.92060195,10.1321939535,1052.04229635,718.750566543,8.12244100199,801.508099998,898.573815349,7.87916233557,533.920928373,723.523773457,7.07509363693,729.07999621,343.733743126,7.26616179977,6.76035478635,203.333475357,8.43831262473,1139.32121359,787.580364644,9.50597025202,795.952082142,14.9605630484,6.49896644315,1163.98485196,402.204678131,8.18647206176,102.965182246,544.359515405,7.43308295865,713.802213454,407.332480236,7.82939522969,410.73877994,506.881923288,7.67176287832,625.452809709,933.196275778,8.53019505111,1243.24250207,850.062577468,9.95213935561,423.029714634,627.752547586,6.43822662914,1143.73083229,728.565165477,7.49198612199,204.719658258,286.798081581,6.22720774847,531.631359578,580.080309226,10.6159289735,352.931857264,917.825121443,8.03801984567,244.321047289,278.461442784,10.7863659579,350.016342951,749.929111556,8.08957452772,395.588740368,863.616544703,7.06532732669,522.423119621,59.5991034038,7.13325605294,1265.8783778,376.334540703,9.22011416273,828.33311407,187.98667193,7.23438600801,124.869954266,639.442875661,9.91033697995,872.65837111,354.313136317,8.53033490416,1222.51343312,433.418589176,8.68271374723,357.812480985,412.589610436,7.79033590086,834.436993941,872.336775927,7.80714607022,911.09029946,581.643403892,8.57342980001,74.8931609321,787.285473675,9.33925305121,983.143159618,895.326175193,6.81646700731,200.388580361,577.482162658,7.64036517774,880.911726558,956.801993366,7.36303000943,658.410175346,669.505018745,8.142534641,1010.89409846,492.0504807,8.86981995184,54.7839060144,475.733166232,7.33077512522,667.9948592,859.907945439,7.42745798237,1089.90209771,634.504806251,7.86898737378
541.107877315,185.684321366,9.16748872164,266.901982289,923.333570067,7.99717641677,1318.01472514,1037.96474592,8.26327517582,1201.4962568,785.961418663,6.24430289423,241.842652222,382.962275688,8.03961610751,802.244700253,984.726559244,5.62008960177,940.019578074,633.796873834,5.4526738624,187.28485959,976.340730178,6.90361316274,940.581164494,968.520382705,7.5709823706,114.786130929,613.059616598,7.04148679602,727.022805016,164.589951616,9.59979941191,884.569193222,459.66001683,10.1351062728,781.244436083,574.887354712,9.85132619512,1135.29962566,798.985975449,8.39579497881,1128.54733779,919.721787525,7.00727550157,1138.08018062,928.730581476,8.7626643388,1244.87078986,8.49780360702,6.24228895667,345.974242869,973.335760819,8.98495631626,1167.32180214,758.285659306,7.92924082317,75.4427153902,1009.74639141,8.73544509924,1024.97672411,123.904198538,8.12923815145,1133.25285552,805.463188816,8.79697776491,50.802690753,419.132438631,9.50799600594,639.024949513,465.950673802,10.4521899036,1149.91060741,491.893965165,10.3426881403,1277.17050749,11.1675741133,9.01039116672,530.72595181,232.40653176,8.02594138215,299.196338175,37.7290156138,8.40150965325,625.823273661,1006.31989123,9.92459574924,939.284183606,994.875540008,7.78208201245,280.869620965,837.207249858,8.14152164684,1064.21008968,598.539393476,6.84399142871,386.984507307,462.620250749,9.30840080722,259.174616915,234.251693571,8.97365355616,188.713367665,764.319255553,10.6227978176,171.360142445,942.680051036,9.54428682261,399.567412135,812.01559595,9.10818328032,1331.86913569,767.072546309,7.0993062347,85.7677929685,869.730376833,9.87707267767,17.0167053357,81.0098978735,8.14656204477,684.980748035,452.723172917,6.48815897842,932.894114233,754.585235983,8.00413967206,788.677165684,98.0238873971,7.94591969339,292.827296918,438.183811512,9.09471557386,529.320993898,183.332914137,8.84365515493,840.32815065,232.976262116,7.23460637526,675.390999556,456.705515495,7.93725971714,228.301872864,732.361547949,7.99133483746,1191.26183403,190.723053621,8.07254402828,548.196933914,739.88283659,10.7412451075,802.440146352,969.910816751,9.30475574228,1320.8971769,236.791582783,6.49024679127,44.7666044908,838.22674819,9.93445293472,105.412531762,350.399445048,7.52028223993,597.685259388,823.462558725,8.4593641068,995.309538197,46.8261573706,9.50885897229,463.923991344,935.535380162,9.33443400329,574.522771207,792.300301813,4.01863677221,992.796815202,89.007072913,8.42866899489,1243.73924873,10.6332539754,6.88865468157,1030.31008117,695.201755453,9.11751469642,373.03057477,246.304239664,8.51215619849,463.880324385,86.7852387181,7.67122175556,487.210858227,656.060443871,8.65492745167,927.210675751,128.16315345,8.94189156233,663.014778419,816.926241248,9.58901946168,1104.65166579,361.459067199,8.11120721207,174.740478516,1034.91883799,5.77601066929,354.399518534,494.676825514,10.862880524,162.632004425,242.269456935,6.5110741345,700.865408866,303.38981379,8.72578992668,568.555644721,99.7603275873,9.28846474076,464.19001212,807.09868419,8.23968226019,1032.96471191,346.969484406,6.15490981893,1297.2753902,890.369098032,9.14809098107,642.415451867,800.455883676,8.26785287924,507.575637772,173.690376749,7.89642834838,787.092133882,752.170389912,7.19160272898,310.376829594,674.573287928,9.35836093259,1302.09772762,628.529851937,7.67874746314,1188.36963817,594.352877401,6.68920802258,854.345215568,249.66087816,10.9129425945,601.729592459,547.533458665,9.04059675246
1115.41055532,20.5157938331,8.67688929801,704.843131034,477.214873415,8.13653052726,1054.94603625,660.547401948,9.46281045896,1172.67013243,424.25124691,6.35599917478,1220.86412557,531.468647052,9.52563173717,471.081744122,482.302949134,9.11941809769,643.000526926,751.98235862,7.88003230451,418.823942211,56.3703481377,8.81833819096,768.850958726,152.736605937,9.50385584466,567.67340065,894.337112315,9.85542154035,1385.59030942,399.379820907,9.00460906608,1120.36803844,288.353448731,9.89934879937,74.5429002591,268.195718319,8.24613070315,859.644818685,157.046655661,6.84358416884,216.505975103,82.0419835232,8.28674243254,224.848450192,603.950781699,6.3596403202,512.822530939,565.617378861,10.0030816385,550.31474434,81.6022972292,8.89984125097,699.907517192,1009.04506374,8.29126462278,193.543540551,770.74433512,8.94869831177,765.226230617,664.31716771,9.56067358885,303.20891563,759.975623282,8.7805329307,1253.36631029,549.6861627,7.51601824657,1072.44668507,752.65604045,8.1703790158,623.873371555,226.975133201,9.6115602177,1364.80356963,1033.52334348,7.57427103896,1192.59461571,316.327418629,9.13678227214,666.933983963,183.243693315,6.02985850022,1012.76493408,295.591725569,8.20271171124,755.033410717,921.734978411,9.5423210254,253.389557496,293.034110499,8.26866251914,726.386782034,944.872438669,6.9216216418,1269.89878811,1033.09470618,7.8322938467,17.3057785392,1022.29681217,9.34515266407,1365.46717927,873.855678338,7.20162057217,1042.391163,514.807635574,8.79881277111,1040.53932776,837.580833763,9.75560228495,514.656206895,582.330149943,10.0725102166,309.190462469,421.607302748,8.9609816566,993.103713291,635.204218846,10.4096377475,358.93044936,1037.49413372,8.59143444798,152.128240564,989.748078336,5.19838116413,749.014416399,313.976709106,8.58327384825,494.482849323,764.845288148,8.76314753312,214.968198789,937.293802496,10.3973655781,90.8862180371,567.80738537,8.5732105103,1055.82301638,660.400914436,7.63458791733,981.098795128,253.83025625,9.37517945693,952.887381086,846.186270971,9.45370977586,1341.30187342,83.3894797636,6.43153608553,91.3319334338,871.991080654,8.76932697291,1234.72618255,914.353807405,7.79526018548,1378.12157765,755.531203335,7.93489778777,1287.95607611,503.980237839,6.89351522465,546.723609881,363.310476266,9.37708201502,1118.28407858,44.264702082,8.53793253295,115.272783684,326.811280868,7.16213816148,257.918796625,953.41863461,8.98814909364,774.404035526,232.92513233,4.2086996533,632.091771206,26.7224299057,9.15889689838,7.71790515503,632.198188677,6.71615867612,662.952579899,94.0317642762,7.2521082322,1272.4636475,299.856111052,8.12116055009,830.684076524,570.957373786,7.66675318604
786.690746756,624.539517042,8.43951075618,1018.47884437,741.625707901,5.8964634416,1058.99746343,837.498525291,10.2855445646,788.223961891,270.79685758,8.35096193937,241.514181973,303.422968274,8.36563251093,642.744592326,37.1006513479,7.75454014025,1301.47468058,820.434746814,8.04940196035,364.131606795,86.5811591921,7.52100351835,592.610770643,358.601961532,10.6663325752,870.449267863,284.994593867,8.33683411252,742.895677022,20.0349154286,8.43175185885,200.109768386,741.973183722,9.53055358654,41.182468785,4.71117163026,8.68235075405,614.850049743,703.471638929,5.49341595433,1364.55343337,516.693945442,9.62526325199,668.422878248,291.314072194,9.37665922964,961.38848279,394.771878394,9.56165905151,402.501960396,868.408892357,8.01894383901,1005.39949332,481.172901776,8.59670030003,467.941796331,20.6934861282,7.20412717748,1114.42307264,931.62062927,8.23214336421,845.522464314,247.490525977,8.38291760081,240.361724474,305.007510764,7.90698882273,952.875555008,686.983367592,8.16654698394,1107.08144313,673.271037928,9.25434461639,921.544625086,799.368169647,8.81714561616,354.872477112,27.6910458278,7.98904534984,1292.51108493,1035.21035111,8.33421278517,1344.56215199,387.78742302,9.57586619393,482.479780053,201.483345751,7.32756036277,599.574418866,823.227343022,7.28587932479,569.466892102,468.730549644,8.42185661862,951.038350867,1.0578698652,9.09862236424,1356.54995094,1011.21383497,9.36609622286,485.478109686,748.702997876,9.2404088302,231.873362266,280.636215308,8.23847169022,77.0551393979,540.823270409,4.69800048301,333.814264835,875.534298649,5.51058717426,188.646316553,868.093770928,7.75892642185,916.633351552,901.645398339,6.79501256897,414.376009592,438.764490647,8.91421450408,727.052570629,242.754038521,9.68672252107,1029.23073287,635.536365849,9.89310593589,338.835901791,736.796918362,7.93674999057,1321.67271085,179.869788285,8.29509455124,323.453393704,590.066688296,9.95028810977,929.313507487,93.5314511271,8.97973356968,64.4992836156,801.429460206,8.96890608054,946.324422154,155.805981328,7.94092151922,707.700662208,52.0367800645,7.87737491064,458.476087706,833.542218486,8.63860768609,1087.46484838,212.101604209,7.81483355678,1.64743564697,207.189008925,9.2636780665,756.20095051,865.213526573,8.74681545158,1250.08477769,2.19195324346,8.124068584,793.600750512,446.859161641,8.5791733339,984.388168503,385.531234627,8.73549582736,983.178746845,1009.87493713,10.9111446999,507.088009504,488.577335434,7.41091347112
78.0404909923,13.8841748774,8.79719818261,44.0098955473,887.941519107,8.06049041754,427.594808158,742.154190703,8.12459226925,307.201657736,424.140618047,9.03817567509,296.569152385,1011.20610869,7.32463889505,617.968317245,711.336309193,8.21152284113,911.792999317,170.089662051,8.85685178981,1104.61740991,594.365447155,7.90371365842,272.978917071,558.144607893,10.7740481162,470.330201032,1002.65834238,7.8530012548,1265.61852616,104.140252382,10.2601763645,806.748871324,1021.96087732,8.15970123732,1114.34398509,384.664858439,8.83101913473,1035.91534016,759.718746087,6.47006836306,1293.35217332,592.119322655,9.98904082873,980.676133559,565.187689163,10.3257599123,802.181266887,118.435481208,9.01220032197,901.046358774,29.0653961007,8.94176309396,43.9924708593,251.916171481,7.21517135912,172.026422277,779.726385194,8.57824381446,678.187148083,560.734356832,7.88014681874,1088.39673109,897.891629683,9.97092982752,260.724544927,38.6473781469,7.83988444341,425.33042032,497.032005355,7.67319477852,558.117082001,917.252243961,8.09377025573,298.327488,61.2641625222,8.61884611361,515.57819651,1021.86113658,7.59458526379,593.567694769,170.555590373,6.12298824456,13.2504526816,616.665783801,9.36863201234,990.335783509,695.188906104,8.68406377603,1095.27225079,705.890172415,7.32327501343,155.778645685,306.786226233,7.49394944065,535.933837502,683.359777194,8.2354223144,1174.73494729,924.860902521,6.20998366988,123.602387721,687.542018681,7.89696568093,750.8178568,377.820342305,9.26043639906,1370.21392004,633.61481094,9.35121190924,374.577615878,185.736441204,8.26146480502,223.416880021,385.215777159,6.99599491048,1305.82273627,234.133286619,7.83204694192,378.296002073,607.622834131,6.29182271139,169.016367782,740.489717132,8.57868728189,453.789076775,0.698688811569,6.81149037053,11.258247047,779.302336099,7.83737823797,637.280072266,425.820713266,9.26746053388,246.537334357,523.087920471,7.56512820964,935.288911737,131.343155109,7.61928477891,684.076987267,45.1694870851,8.96022063697,1242.47329163,94.637427772,8.81909979946,1328.17643572,258.641079596,7.8646675975
192.207036236,789.107601712,9.22297555573,1148.82945298,886.926958315,8.89746115986,893.25453577,55.1272483992,8.25502890897,911.801568036,610.405599451,9.01904290468,1328.67196688,1004.16543682,9.77938245217,255.217443704,733.663625307,8.67973015183,1088.3987219,859.325502312,6.39534075881,340.282871022,929.88740572,7.69472468898,712.233434447,66.7554511249,7.97290953254,59.1060713662,777.794104045,9.98104718634,399.227445853,69.0544983477,6.44839180772,929.95665689,595.648200975,9.7959951475,1248.96933534,519.081821825,8.05599166442,575.533436714,237.11333806,9.58747754512,409.156809741,908.60898501,10.0923340404,1273.88318783,373.965530044,8.82482245981,303.152759867,268.539238116,8.60062866996,237.939529878,428.150561248,7.95005140371,1055.11705761,754.763596758,9.15262132977,540.412792781,51.9313039535,9.83559952703,425.74161414,714.71047896,7.83884559054,132.426333385,374.882748329,6.82157727917,893.936678399,625.475686118,10.0040396178,689.740304332,366.084775272,9.06309545547,441.503801397,387.049565028,8.48746051656,24.2748608551,572.539722276,10.4313242743,972.607396125,613.667124558,4.6444061771,938.405349038,344.107352806,8.30582802228,1304.17355143,120.651528525,8.99015560983,267.94437832,525.676233806,8.24201686364,912.688140611,521.500188759,8.56674540042,689.908339108,645.640424162,7.12528063426,54.2803065917,244.533653902,7.25554679789,1034.65116409,80.1616442805,8.57978111576,543.376166032,805.13146011,9.17513802161,1322.95637348,304.409767175,8.29999547734,254.861200972,239.02246516,6.48749402021,888.689207195,996.460132786,9.9560305949,141.877214862,879.545356466,10.5325650445,651.037237528,919.204314941,9.77750003437,933.254119361,894.822910598,9.4078315638,656.397857452,68.2470926953,6.79912710114,425.048777945,717.174060516,10.8472731299,1147.78129927,277.898963968,9.07214981626,1371.07854816,232.532532673,8.89901186859,554.807535701,147.929253001,8.7818252806,1297.76494697,737.369386332,9.04826805635,966.047823459,153.902826845,8.10805938216,967.031069266,138.073659434,8.93209412457,1279.98693814,461.726694931,8.53209592315,851.598773911,178.73623245,7.31779968747,572.048235427,603.974893063,9.22630472699,595.324756959,52.0570473151,9.45009635038,427.191126876,154.074500069,8.26097199183,510.2864085,663.709661904,8.55613281622,1243.75434085,628.491470091,8.71447030792,451.437346854,166.56103087,7.78941940142,682.023936369,960.246186295,8.1517423889,1321.87412476,933.071902715,8.87757858949,1254.7020048,734.58993023,8.23470755473,148.101802058,329.732095441,7.84047763167,1079.23879654,722.395334482,8.08467808116,401.308438474,613.264353267,8.34000272864,1034.45922077,714.027612138,7.9627974872,155.228795714,534.358504605,7.53804647631,665.211280633,1033.44810271,7.75952286076,362.02719291,226.453113746,8.15251176153,342.364084961,875.378739043,8.0863998175,1338.2622923,238.466269971,10.3070882341,737.267333065,154.094018844,10.3587241949,574.159630716,648.636123678,8.07565756574,825.215158896,1037.46909521,8.84365275281,280.543045133,367.015446029,10.1505124176,966.460664686,183.069703848,10.4308012957,50.5391553312,258.522877665,8.89093876751,882.310807856,786.387709901,7.95200919064
1152.89710898,421.863332105,10.7559878179,1341.83226319,397.153148501,7.30473530785,748.962806752,600.395539818,7.54719637372,802.336945228,197.330326869,10.7304995591,807.949824955,515.732090337,10.6445521997,874.654282873,307.89762628,5.9897464476,474.678234385,283.578515888,9.21298852489,195.020564105,439.33432604,9.7788486315,699.784019959,682.209006535,8.99570953995,999.549651981,906.068474789,6.6510402605,1250.25983997,733.945255392,9.38788081425,540.330691095,756.072664751,7.42036611796,733.962624446,1000.02756979,9.22548464756,675.175440795,664.897941024,8.92493839678,1292.22990337,452.235295332,10.5212205881,949.664426508,677.198794523,7.61098495328,358.842237066,906.002958137,10.1619891505,1047.86753653,209.43807623,8.62809380018,809.392135892,264.83772577,8.59326184879,471.714264656,1038.5061164,8.81024246102,1330.29070148,428.667313039,6.9076745246,32.2723014535,226.270663772,8.58783243664,521.077593082,179.686629821,6.20931635973,891.618430397,19.1145951554,10.001102481,1237.1522931,835.663030757,10.1236781233,565.904550224,802.126596374,8.29897113258,1319.09611532,410.759183085,9.00183124184,924.240923069,711.078841066,9.85103783096,354.141747835,758.311506752,9.93562902845,472.792438171,501.095988758,8.44607776786,228.402555131,681.992736595,9.72808508357,1255.4989168,892.440539771,4.90416364148,597.105201004,191.813830941,7.78370974424,366.581078853,183.396428656,9.42587865208,160.33092382,198.208474973,7.47660139938,440.341252395,298.075478366,8.3759841808,196.551008388,302.788832433,7.56194589653,1099.41405826,342.926620497,10.3639821625,607.384348061,486.561340819,6.88156584095,930.819305901,199.912879951,8.97754032241,1076.1155868,941.116844272,6.18298600382,117.984833746,807.918925154,9.21927472847,727.3900313,523.120565158,8.44575425668,892.264144044,441.800596594,6.3044927712,851.484338454,1026.3174739,7.3432517486,111.960951863,1021.99643126,7.32825941139,1152.54453021,634.258996703,6.82177402281,1165.20688391,235.391749106,6.48173628464,39.4924153619,835.365374551,7.86874828838,563.997034032,627.857984046,8.19275391086,1361.8387417,827.289692581,10.911235906,253.190068769,834.71626146,8.0222874769,528.603423116,409.605344954,10.3935762484,495.997845856,1020.64912843,7.66790661305,816.247987979,300.665771907,4.49460761249,190.23115297,559.276279511,9.37150156591,1310.56316251,937.189976336,9.62602555866,1188.28270893,524.614763786,7.55099538497,1186.49955251,511.383802996,9.25367646986,659.034216987,759.679980944,7.59458879766,945.006022754,36.6150176273,3.3847995284,718.988351231,251.269698748,5.390554617,1332.45546381,428.504318588,4.00934560948,1018.6308913,697.612001093,8.43332835252,679.521383805,821.640452997,7.74193812204,712.714615336,1031.41442684,10.3376911955,764.679590554,573.75580542,8.62459431604,1185.2165486,4.76025529764,7.35639720873,159.880444958,700.459414565,8.44066337659,672.064296021,767.869565796,9.90905816034,863.769438661,73.6154814573,8.6794495729,321.311757093,331.214675931,7.96039170467,852.605766223,990.1102227,7.53881422184,1071.03615248,693.707788455,8.21354811032,1233.80137885,249.681316266,7.96593650501,275.339974943,529.103731224,8.19684462953,414.895291827,508.88348181,7.41871109576,521.077755711,222.540182453,8.7404497888,953.71289637,586.345848725,8.99272484658,968.149443758,845.037860305,9.68134216075,384.882787198,185.340708545,8.15627849187,1257.53843917,1011.63698835,9.54317359015,700.400064389,472.738072077,7.26366142451,1065.41433597,641.085296307,7.80769396476,899.053461287,74.5669936193,7.06991752326,1121.59851821,804.383773219,6.56952785338,445.121670988,893.298555538,10.1879500778,564.654069103,1017.62344787,10.158574816,1041.21920937,130.506715715,8.56068929637,360.56563264,94.3692104801,7.92359654451,1015.39548936,455.02352348,6.45627144061,365.965962755,184.168369483,10.0290483547,407.205816589,714.950710449,8.47877483387,653.949403798,58.4127619268,8.42636462545,411.492300146,660.241288988,7.28966061213,189.186355387,563.543692755,7.37463699,1267.04430066,702.747064134,9.11875254492,1248.64300034,289.996296907,6.78422679185,17.7739279938,544.499330254,7.06614323277,375.234319632,135.170108359,7.14765365086,577.973947699,75.0567927895,8.43461387083,549.199686886,316.019181243,7.46901240887,87.4260356146,812.104696324,6.9843582638,1103.80204725,277.413541667,9.59430545622,176.564988693,1019.20356494,7.93135853492,787.349449104,651.850140034,6.45365507356,575.592667694,189.480766098,7.61409950736
1023.10672355,748.830277406,8.8944882758,149.853894791,877.43044557,8.40751805616,936.198297007,584.858045016,7.07875233873,1353.84319178,791.749544818,8.75010001171,450.356828891,45.1652605712,8.86159197697,152.07573431,740.73560039,7.49480653576,521.00838454,310.852088928,6.86522152127,1271.90415962,510.462435715,8.11440569136,292.08650909,492.507004836,6.99330146368,167.066545295,524.330926576,8.27135306424,156.525924491,860.797074705,8.50958118,1249.82499619,917.706083986,6.61198991881,1058.96761192,216.179562496,7.84478766361,940.29110649,120.624368922,7.57628571198,421.162076314,356.304025423,7.59923052349,512.561422847,70.2857906477,7.93886801973,40.8358473726,76.3996684626,6.71699023637,961.27176084,260.569477879,7.95505404434,212.491826233,278.73829411,8.39208038098,801.779570445,951.693504007,7.62612163473,200.426865279,657.017683644,9.57704612209,177.710118847,513.001931004,7.74771568041,362.82492115,722.589602163,9.18755583461,605.214737772,738.079045718,8.57421216916,11.3863914095,171.778351095,7.07493421348,706.883187246,858.596352948,8.00050813726,461.482546827,655.971193134,7.70262841229,517.335705392,685.980969155,5.98992661729,1270.0380135,295.345366556,7.95958012968,626.068673701,161.346525755,7.45473695353,318.166896826,648.336124521,9.26866327613,198.615676171,655.534215249,7.43286257996,508.187348396,1037.52672178,9.94017788822,1329.19060614,53.446323185,7.9057258543,345.862290082,932.782681161,8.4605611214,889.917768083,477.385136063,7.31597124951,501.539310353,631.335294816,6.62249903891,3.39512134056,712.117069779,8.65383139996,1305.32862163,15.4203873767,7.53640865464,635.169378627,841.289473035,6.0014955083,1104.99502051,975.612118591,9.31381570201,1333.93482803,261.814587565,8.09820514559,1270.92461047,979.542052854,5.58839984417,1187.82229853,106.592411322,6.98333461316,288.554323639,367.899776434,7.83492260217,1129.85886229,436.748082537,8.73372346527,191.302586741,698.489242405,8.53197759452,827.947741202,149.027255193,8.31183306303,87.8700975607,551.602130795,7.98805874665,494.470952206,222.818459,8.16318953231,782.199037791,159.359121546,7.83047983827,768.076548964,423.010730636,7.03593120914,1126.31280682,739.465797672,8.2679537953,799.129779405,669.102510122,8.12707031399,926.367092261,845.306356403,4.69598918754,22.5837475161,247.79204708,9.4611086336,1114.82464388,468.091112461,9.98402878932,311.969014654,518.572336971,9.80911075672,799.543027413,566.69006543,6.49383180777
662.951272375,792.069384064,8.41485159404,264.865525348,141.673843783,6.62408637885,1314.66820587,889.779186918,7.07333043921,76.8289853502,644.276368982,6.12372174407,759.456580719,313.74602552,5.8938536673,373.923190673,944.385623221,5.83250795942,891.95460536,489.416773487,8.6979281776,795.086139952,583.497895107,8.31987246082,998.321121418,463.925524019,5.39273778439,1337.14991365,698.153203511,6.43025479606,725.952780005,225.345325551,7.27675950854,1012.63410424,398.841532738,8.21225296833,399.432326202,688.600123389,7.3171405839,536.371556543,675.67884231,8.07221192713,434.502334974,674.185729779,7.1262719178,1230.95626831,237.511499271,7.39127412615,720.637699729,306.328900649,5.76701292627,534.156725577,126.372683918,7.46457429708,564.407266972,531.627359949,8.32568824791,188.055975819,946.518940329,6.90129975659,160.051240743,27.0365171202,8.19902220738,199.618713119,654.366852526,7.91434706062,745.048027267,905.379199119,7.45421497827,432.798738546,823.895215153,9.03368230411,140.441741552,717.108060032,7.45249163103,407.095842378,929.546103371,7.58415541337,124.993299833,995.222146365,6.80580106741,1103.96057323,790.783750681,7.41344697634,1254.69561532,938.493866341,8.8205703947,352.484371503,423.653842711,9.63852831478,1349.50184889,129.277483717,6.47728331584,328.316963866,169.895524091,8.11500076404,60.3899916094,937.221396854,7.64490436988,1209.8281988,536.627769668,8.04778429158,1249.87934704,142.457906501,7.92657235463,228.34255615,115.154323696,9.1429886
gitextract_orpqwhda/
├── .gitignore
├── Dockerfile
├── LICENSE
├── README.md
├── beast/
│ ├── Makefile
│ ├── beast.h
│ ├── beast.i
│ ├── config.h
│ ├── constellations.h
│ ├── go
│ ├── kdhash.h
│ └── stars.h
├── build_production.sh
├── doc/
│ ├── gen_interleave.py
│ ├── ost_comm_test.c
│ └── viz_q.m
├── setup.sh
├── starsToStruc.py
├── startracker.py
└── tests/
├── Makefile
├── calibrate.py
├── science_cam_may8_0.05sec_gain40/
│ ├── calibration.txt
│ ├── calibration_data/
│ │ └── .gitignore
│ ├── input.csv
│ ├── result.csv
│ └── result_real.csv
├── score.py
├── simulator.py
├── test.c
└── unit_test.sh
SYMBOL INDEX (184 symbols across 12 files)
FILE: beast/beast.h
function size (line 45) | size_t size() {return map_size;}
function init (line 51) | void init(constellation &db_const_, constellation &img_const_) {
function copy_over (line 64) | void copy_over(match_result *c) {
function related (line 83) | int related(constellation_pair &m) {
function search (line 91) | void search() {if (db->results->is_kdsorted()) db->results->kdsearch(R11...
function clear_search (line 95) | void clear_search() {if (db->results->is_kdsorted()) db->results->clear_...
function compute_score (line 99) | void compute_score() {
function star_db (line 133) | star_db* from_match() {
function weighted_triad (line 158) | void weighted_triad() {
function DBG_ (line 274) | void DBG_(const char *s) {
function print_ori (line 290) | void print_ori() {
type constellation_pair (line 337) | struct constellation_pair
type constellation_pair (line 337) | struct constellation_pair
FILE: beast/config.h
function load_config (line 34) | void load_config(const char *filename) {
FILE: beast/constellations.h
function DBG_ (line 21) | struct constellation_pair {
type constellation_lt (line 47) | struct constellation_lt {
function constellation_lt_s1 (line 55) | bool constellation_lt_s1(const constellation &c1, const constellation &c...
function constellation_lt_s2 (line 56) | bool constellation_lt_s2(const constellation &c1, const constellation &c...
function constellation_lt_p (line 57) | bool constellation_lt_p(const constellation &c1, const constellation &c2...
function DBG_ (line 130) | void DBG_(const char *s) {
FILE: beast/kdhash.h
function bin_size (line 15) | struct kdhash_2f {
function mask (line 55) | static inline uint64_t mask(const float r) {
function mask (line 63) | static inline uint64_t mask(const float r0,const float r1){
function bin_size (line 76) | struct kdhash_3f {
function mask (line 108) | static inline uint64_t mask(const float radians) {
function mask (line 114) | static inline uint64_t mask(const float r0,const float r1,const float r2){
function bin_size (line 129) | struct kdhash_4f {
function mask (line 165) | static inline uint64_t mask(const float radians) {
function mask (line 170) | static inline uint64_t mask(const float r0,const float r1,const float r2...
FILE: beast/stars.h
function star (line 19) | struct star {
function OP (line 86) | bool OP(const star& s) const {return hash_val==s.hash_val;}
function dist_arcsec (line 94) | float dist_arcsec(const star& s) const {
function DBG_ (line 104) | void DBG_(const char *s) {
function star_gt_x (line 119) | bool star_gt_x(const star &s1, const star &s2) {return s1.x > s2.x;}
function star_gt_y (line 120) | bool star_gt_y(const star &s1, const star &s2) {return s1.y > s2.y;}
function star_gt_z (line 121) | bool star_gt_z(const star &s1, const star &s2) {return s1.z > s2.z;}
function star_gt_flux (line 122) | bool star_gt_flux(const star &s1, const star &s2) {return s1.flux > s2.f...
function star_lt_x (line 123) | bool star_lt_x(const star &s1, const star &s2) {return s1.x < s2.x;}
function star_lt_y (line 124) | bool star_lt_y(const star &s1, const star &s2) {return s1.y < s2.y;}
function star_lt_z (line 125) | bool star_lt_z(const star &s1, const star &s2) {return s1.z < s2.z;}
function star_lt_flux (line 126) | bool star_lt_flux(const star &s1, const star &s2) {return s1.flux < s2.f...
type star_db (line 128) | struct star_db {
function size (line 160) | size_t size() {return sz;}
function star_db (line 163) | star_db* OP(const star& s) { return *this+=&s;}
function star_db (line 164) | star_db* OP(const star* s) {
function star_db (line 179) | star_db* OP(star_db* s) {
function star_db (line 184) | star_db* OP(const star_db* s) {
function star_db (line 193) | star_db* OP(const star_db* s) {
function star (line 206) | star* get_star_by_hash(const size_t hash) {return &(hash_map.at(hash));}
function star (line 212) | star* get_star(const int idx) {return size()>0?get_star_by_hash(star_idx...
function star_db (line 216) | star_db* copy() {return copy(star_idx_vector.cbegin(),star_idx_vector.ce...
function star_db (line 220) | star_db* copy_n_brightest(const size_t n) {
function load_catalog (line 265) | void load_catalog(const char* catalog, const float year) {
function count (line 294) | size_t count(const star* s) {return hash_map.count(s->hash_val);}
function count (line 295) | size_t count(star_db* s) {
function DBG_ (line 302) | void DBG_(const char *s) {
function get_score (line 313) | struct star_fov {
function get_score (line 378) | float get_score(const int id,const float px,const float py,const float s...
function get_id (line 386) | int get_id(float px, float py) {
function kdsort_y (line 466) | struct star_query {
function kdsort_z (line 500) | void kdsort_z(const int min, const int max) {KDSORT_NEXT(star_lt_z,kdsor...
function is_kdsorted (line 532) | uint8_t is_kdsorted() {return kdsorted;}
function kdsort (line 536) | void kdsort() {
function sort (line 542) | void sort() {
function r_size (line 546) | size_t r_size() {return kdresults_size;}
function get_kdmask (line 547) | int8_t get_kdmask(size_t i) {return kdmask[i];}
function reset_kdmask (line 551) | void reset_kdmask() {
function clear_kdresults (line 558) | void clear_kdresults() {
function kdcheck (line 575) | void kdcheck(const int idx, float x, float y, float z, const float r, co...
function kdsearch (line 618) | void kdsearch(const float x, const float y, const float z, const float r...
function kdsearch (line 626) | void kdsearch(float x, float y, float z, float r, float min_flux) {
function kdsearch_x (line 642) | void kdsearch_x(const float x, const float y, const float z, const float...
function kdsearch_y (line 643) | void kdsearch_y(const float x, const float y, const float z, const float...
function kdsearch_z (line 644) | void kdsearch_z(const float x, const float y, const float z, const float...
function kdmask_filter_catalog (line 650) | void kdmask_filter_catalog() {
function kdmask_uniform_density (line 668) | void kdmask_uniform_density(const int min_stars_per_fov) {
function star_db (line 686) | star_db* from_kdmask() {
function star_db (line 698) | star_db* from_kdresults() {
function DBG_ (line 707) | void DBG_(const char *s) {
FILE: doc/gen_interleave.py
function prettyBinString (line 7) | def prettyBinString(x,d=32,steps=4,sep=".",emptyChar="0"):
function binStr (line 35) | def binStr(x): return prettyBinString(x,32,4," ","0")
function computeBitMaskPatternAndCode (line 38) | def computeBitMaskPatternAndCode(numberOfBits, numberOfEmptyBits):
function partitionBy2 (line 91) | def partitionBy2(x):
function checkPartition (line 95) | def checkPartition(x):
FILE: doc/ost_comm_test.c
type star_t (line 13) | typedef struct {
function sendImageCommand (line 41) | int sendImageCommand(const char* server_ip, int server_port, const char*...
function parse_ost_string (line 104) | int parse_ost_string(const char *ost_str, int max_num_stars, star_t *sta...
function main (line 125) | int main() {
FILE: starsToStruc.py
class stars_to_struct (line 6) | class stars_to_struct():
method _init_ (line 18) | def _init_(self):
method load_image (line 31) | def load_image(self, stars, declination, right_ascension, body_x, body...
FILE: startracker.py
function trace (line 18) | def trace(frame, event, arg):
function a2q (line 53) | def a2q(A):
function q2a (line 62) | def q2a(q):
function extrapolate_matrix (line 71) | def extrapolate_matrix(A,B,t1,t2,t3):
function wahba (line 91) | def wahba(A, B, weight=[]):
function print_ori (line 120) | def print_ori(body2ECI):
class star_image (line 139) | class star_image:
method __init__ (line 140) | def __init__(self, imagefile,median_image):
method match_near (line 186) | def match_near(self,x,y,z,r):
method match_lis (line 201) | def match_lis(self):
method match_rel (line 216) | def match_rel(self,last_match):
method print_match (line 238) | def print_match(self,bodyCorrection=None,angrate_string=""):
class nonstar (line 270) | class nonstar:
method __init__ (line 271) | def __init__(self,current_image,i,source):
method add_data (line 280) | def add_data(self,current_image,i,source):
method write_data (line 296) | def write_data(self,fd):
method __del__ (line 307) | def __del__(self):
function flush_nonstars (line 310) | def flush_nonstars():
function update_nonstars (line 319) | def update_nonstars(current_image,source):
function winner_attitude (line 352) | def winner_attitude(w):
class star_camera (line 366) | class star_camera:
method __init__ (line 367) | def __init__(self, median_file,source="RGB"):
method solve_image (line 373) | def solve_image(self,imagefile,lis=1,quiet=0):
method extrapolate_image (line 403) | def extrapolate_image(self,imagefile1,imagefile2,time1,time2):
class science_camera (line 427) | class science_camera:
method __init__ (line 428) | def __init__(self, median_file,source="IR"):
method solve_image (line 433) | def solve_image(self,imagefile):
class connection (line 443) | class connection:
method __init__ (line 445) | def __init__(self, conn, epoll):
method read (line 458) | def read(self):
method write (line 485) | def write(self, data):
method close (line 506) | def close(self):
FILE: tests/calibrate.py
function angles2xyz (line 37) | def angles2xyz(ra,dec):
function getstardb (line 44) | def getstardb(year=1991.25,filename="hip_main.dat"):
function basename (line 73) | def basename(filename):
FILE: tests/simulator.py
function angles_to_vector (line 45) | def angles_to_vector(azimuth, altitude):
function vector_to_angles (line 59) | def vector_to_angles(vectors):
function split_vectors (line 68) | def split_vectors(vectors):
function randomVectors (line 72) | def randomVectors(num):
function random_matrix (line 84) | def random_matrix():
function add_vector_noise (line 110) | def add_vector_noise(base_vectors, stddev):
class Camera (line 127) | class Camera(object):
method __init__ (line 128) | def __init__(self, resolution, pixel_ar = 1, principal_point = (0.5, 0...
method from_angles (line 133) | def from_angles(self, azimuth, altitude):
method to_angles (line 155) | def to_angles(self, pos):
class EquidistantCamera (line 177) | class EquidistantCamera(Camera):
method __init__ (line 178) | def __init__(self, f, resolution, pixel_ar = 1., principal_point = (0....
method project (line 182) | def project(self, theta):
method unproject (line 185) | def unproject(self, r):
class RectilinearCamera (line 188) | class RectilinearCamera(Camera):
method __init__ (line 189) | def __init__(self, f, resolution, pixel_ar = 1., principal_point = (0....
method project (line 193) | def project(self, theta):
method unproject (line 198) | def unproject(self, r):
class OrthographicCamera (line 201) | class OrthographicCamera(Camera):
method __init__ (line 202) | def __init__(self, f, resolution, pixel_ar = 1., principal_point = (0....
method project (line 206) | def project(self, theta):
method unproject (line 211) | def unproject(self, r):
class EquisolidAngleCamera (line 214) | class EquisolidAngleCamera(Camera):
method __init__ (line 215) | def __init__(self, f, resolution, pixel_ar = 1., principal_point = (0....
method project (line 219) | def project(self, theta):
method unproject (line 224) | def unproject(self, r):
class StereographicCamera (line 227) | class StereographicCamera(Camera):
method __init__ (line 228) | def __init__(self, f, resolution, pixel_ar = 1., principal_point = (0....
method project (line 232) | def project(self, theta):
method unproject (line 237) | def unproject(self, r):
class CubicCamera (line 240) | class CubicCamera(Camera):
method __init__ (line 241) | def __init__(self, k1, k2, resolution, pixel_ar = 1., principal_point ...
method project (line 246) | def project(self, theta):
method unproject (line 249) | def unproject(self, r):
class StarCatalog (line 278) | class StarCatalog:
method __init__ (line 279) | def __init__(self, filename='hip_main.dat'):
method preprocess (line 284) | def preprocess(self):
method lookup_indices (line 306) | def lookup_indices(self, indices):
method read (line 311) | def read(self, filename='hip_main.dat'):
class StarDetector (line 400) | class StarDetector:
method __init__ (line 401) | def __init__(self, sigma_psf, t_exp, aperture, base_flux):
method norm_gaussian (line 408) | def norm_gaussian(sigma):
method compute_flux (line 411) | def compute_flux(self, magnitude, add_noise=True,photon_floor=0.001):
method compute_magnitude (line 421) | def compute_magnitude(self, flux):
method compute_magnitude_threshold (line 424) | def compute_magnitude_threshold(self):
method add_noise (line 428) | def add_noise(self, magnitude):
class Scene (line 434) | class Scene:
method __init__ (line 435) | def __init__(self, catalog, camera, detector, gaussian_noise_sigma=Non...
method compute (line 446) | def compute(self, orientation=None):
method add_false_stars (line 482) | def add_false_stars(self, false_stars):
method copy (line 500) | def copy(self, camera=None, orientation=None, copy_false_stars=True):
method scramble (line 525) | def scramble(self):
method add_magnitude_noise (line 537) | def add_magnitude_noise(self, gaussian=None):
method filter_magnitudes (line 546) | def filter_magnitudes(self):
method random (line 553) | def random(catalog, camera, detector, min_true, max_true, min_false, m...
function write_csv (line 642) | def write_csv(filename, lines):
FILE: tests/test.c
function star_id (line 54) | void star_id(double spikes[], int result[], size_t length)
function main (line 95) | int main(int argc, char* argv[])
Condensed preview — 30 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (503K chars).
[
{
"path": ".gitignore",
"chars": 176,
"preview": "# ignore files generated by beast\nbeast/__pycache__\nbeast/_beast.so\nbeast/beast.py\nbeast/beast_wrap.cxx\nbeast/beast_wrap"
},
{
"path": "Dockerfile",
"chars": 1438,
"preview": "\nFROM ubuntu:20.04\n\n# deal with timezones (change to what suits your use case)\nENV TZ=America/New_York\n\nENV DEBIAN_FRONT"
},
{
"path": "LICENSE",
"chars": 1084,
"preview": "MIT License\n\nCopyright (c) 2018 UB Nanosatellite Laboratory\n\nPermission is hereby granted, free of charge, to any person"
},
{
"path": "README.md",
"chars": 5446,
"preview": "# openstartracker\nA fast, robust, open source startracker based on a new class of baysian startracker algorithms\n\nFeatur"
},
{
"path": "beast/Makefile",
"chars": 348,
"preview": "CC = g++\nPYTHONHEADERS=/usr/include/python3.10\n#PYTHONHEADERS=/usr/include/python2.7\n\nall: $(OBJ)\n\tswig -python -c++ bea"
},
{
"path": "beast/beast.h",
"chars": 10508,
"preview": "#ifndef BEAST_H\n#define BEAST_H\n\n#include \"constellations.h\"\n#include <float.h>\n\nstruct match_result {\n//TODO: private:"
},
{
"path": "beast/beast.i",
"chars": 508,
"preview": "%module beast\n%{\n#include \"config.h\"\n#include \"stars.h\"\n#include \"constellations.h\"\n#include \"beast.h\"\n%}\n//newobject gi"
},
{
"path": "beast/config.h",
"chars": 2632,
"preview": "#ifndef CONFIG_H\n#define CONFIG_H\n\n#include <stdio.h>\n#include <stdlib.h>//EXIT_FAILURE\n#include <string.h>\n#include <ma"
},
{
"path": "beast/constellations.h",
"chars": 3722,
"preview": "#ifndef CONSTELLATIONS_H\n#define CONSTELLATIONS_H\n\n#include \"stars.h\"\n#include <set>\n\nstruct constellation {\n\tfloat p;\n\t"
},
{
"path": "beast/go",
"chars": 5,
"preview": "make\n"
},
{
"path": "beast/kdhash.h",
"chars": 4829,
"preview": "#ifndef KDHASH_H\n#define KDHASH_H\n#include <stdint.h>\n\n/**\n * multidimensional hash function based on morton codes\n * \n "
},
{
"path": "beast/stars.h",
"chars": 21486,
"preview": "#ifndef STARS_H\n#define STARS_H\n\n#include \"config.h\"\n#include \"kdhash.h\"\n\n#include <assert.h> //assert()\n#include <limit"
},
{
"path": "build_production.sh",
"chars": 502,
"preview": "#!/bin/sh\n[ \"$1\" == \"\" ] && exit\ncd beast\n./go&&\ncd ..&&\nmkdir startracker-production&&\ncp -r beast/ startracker-product"
},
{
"path": "doc/gen_interleave.py",
"chars": 3834,
"preview": "from __future__ import print_function\nimport random\n\n#This script is based on \n#https://stackoverflow.com/questions/1024"
},
{
"path": "doc/ost_comm_test.c",
"chars": 5131,
"preview": "#include <stdio.h>\n#include <stdlib.h>\n#include <string.h>\n#include <unistd.h>\n#include <sys/socket.h>\n#include <netinet"
},
{
"path": "doc/viz_q.m",
"chars": 610,
"preview": "%Extract the X, Y and Z coordinates\n%M=vertcat(sqrt(.5)*[1 0 0;-1 0 0;0 1 0;0 -1 0;0 0 1;0 0 -1],sqrt(1/3)*[1 1 0;1 -1 0"
},
{
"path": "setup.sh",
"chars": 444,
"preview": "#!/bin/bash\n\n# requires docker to be installed\n\n# build the Dockerfile to include the current director and have internet"
},
{
"path": "starsToStruc.py",
"chars": 1462,
"preview": "import ctypes\nimport socket \n\nfrom io import StringIO, BytesIO\n\nclass stars_to_struct():\n fields = [(\"stars\", ctypes."
},
{
"path": "startracker.py",
"chars": 17862,
"preview": "from __future__ import print_function\nfrom time import time\nimport sys, traceback\nimport socket,select, os, gc\nimport cv"
},
{
"path": "tests/Makefile",
"chars": 80,
"preview": "CC = g++\n\nall: $(OBJ)\n\t$(CC) -std=c++11 -Wall -Ofast -g -pg test.c -o test -lm\n\n"
},
{
"path": "tests/calibrate.py",
"chars": 7390,
"preview": "from __future__ import print_function\nfrom os import listdir,system,environ\nfrom os.path import isfile, join\nimport cv2\n"
},
{
"path": "tests/science_cam_may8_0.05sec_gain40/calibration.txt",
"chars": 261,
"preview": "IMG_X=1392\nIMG_Y=1040\nPIXSCALE=15.7768356032\nDB_REDUNDANCY=1\nDOUBLE_STAR_PX=3.5\nREQUIRED_STARS=5\nMAX_FALSE_STARS=2\nBASE_"
},
{
"path": "tests/science_cam_may8_0.05sec_gain40/calibration_data/.gitignore",
"chars": 108,
"preview": "# ignore all the calibration outputs in this directory, but don't ignore this .gitignore file\n*\n!.gitignore\n"
},
{
"path": "tests/science_cam_may8_0.05sec_gain40/input.csv",
"chars": 290937,
"preview": "1332.66135414,1005.65868251,9.27684107053,668.988734129,830.457341566,9.76312036221,1086.81114937,464.955892187,7.774282"
},
{
"path": "tests/science_cam_may8_0.05sec_gain40/result.csv",
"chars": 41728,
"preview": "5120,6667,6238,7790,6285,5832,8565,8452,5804,6579,7399,6650,6632,6580,8066,6473,7044,7729,8081,6904,6548,5668,6542,7246,"
},
{
"path": "tests/science_cam_may8_0.05sec_gain40/result_real.csv",
"chars": 41286,
"preview": "5120,6667,6238,7790,6285,5832,8565,8452,5804,6579,7399,6650,6632,6580,8066,6473,7044,7729,8081,6904,6548,5668,6542,7246,"
},
{
"path": "tests/score.py",
"chars": 919,
"preview": "from __future__ import print_function\nimport sys\nstars=open(\"hip_main.dat\",\"r\").readlines()\nresult=open(sys.argv[1],\"r\")"
},
{
"path": "tests/simulator.py",
"chars": 19937,
"preview": "#!/usr/bin/python\n# coding: utf-8\n\n# Copyright (c) 2016 Joerg H. Mueller <nexyon@gmail.com>\n# \n# Permission is hereby gr"
},
{
"path": "tests/test.c",
"chars": 5647,
"preview": "/****************************************************************************\n * Copyright (c) 2016 Joerg H. Mueller <ne"
},
{
"path": "tests/unit_test.sh",
"chars": 2427,
"preview": "#!/bin/bash\n\nCALIBRATE=0\nREGENERATE=0\nESA_TEST=0\nIMG_TEST=0\n\n#PYTHON=\"/usr/bin/python2.7\"\nPYTHON=\"/usr/bin/python3.10\"\n\n"
}
]
About this extraction
This page contains the full source code of the UBNanosatLab/openstartracker GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 30 files (481.2 KB), approximately 215.0k tokens, and a symbol index with 184 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.