Compare commits

...

16 Commits

Author SHA1 Message Date
fa305a7cc0 fix encoders 2026-03-11 10:05:02 +03:00
205a190820 some fixes, sill have troubles with dummy socket/fd 2026-03-06 12:20:10 +03:00
7c2aaf1cb0 add serial/socket plugin example 2026-02-27 18:31:22 +03:00
54778dcf9a add pre-pre-alpha 2026-02-27 12:05:40 +03:00
Edward Emelianov
31752b58cc polltest 2026-01-26 22:27:51 +03:00
09642743a6 add some bash scripts 2026-01-26 17:16:49 +03:00
a80347643f fixed for new vesrion of usefull_macros 2026-01-26 16:54:50 +03:00
Edward Emelianov
50cbaea550 some work done 2026-01-24 00:57:11 +03:00
c8449c916a fixed for no-connect error 2026-01-20 09:27:06 +03:00
74d9ebb75f .. 2025-12-08 21:04:06 +03:00
Edward Emelianov
2e9241f079 time 2025-11-01 19:54:18 +03:00
2aa8502796 . 2025-11-01 15:39:55 +03:00
f6edc12b01 fixed time 2025-11-01 15:02:11 +03:00
27a7388164 OK 2025-09-26 14:57:24 +03:00
730629e933 found another manual 2025-09-25 17:44:45 +03:00
b77cb2277b starting of 'SILA' tool 2025-09-25 17:27:48 +03:00
89 changed files with 3565 additions and 540 deletions

3
.gitignore vendored
View File

@@ -23,3 +23,6 @@
*.so *.so
*.so.* *.so.*
# build dirs
mk/
build/

View File

@@ -49,7 +49,7 @@ static glob_pars const Gdefault = {
* Define command line options by filling structure: * Define command line options by filling structure:
* name has_arg flag val type argptr help * name has_arg flag val type argptr help
*/ */
static myoption cmdlnopts[] = { static sl_option_t cmdlnopts[] = {
// common options // common options
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")}, {"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")},
{"device", NEED_ARG, NULL, 'd', arg_string, APTR(&G.device), _("serial device name (default: )" DEFAULT_DEV ")")}, {"device", NEED_ARG, NULL, 'd', arg_string, APTR(&G.device), _("serial device name (default: )" DEFAULT_DEV ")")},
@@ -75,10 +75,10 @@ glob_pars *parse_args(int argc, char **argv){
char helpstring[1024], *hptr = helpstring; char helpstring[1024], *hptr = helpstring;
snprintf(hptr, hlen, "Usage: %%s [args]\n\n\tWhere args are:\n"); snprintf(hptr, hlen, "Usage: %%s [args]\n\n\tWhere args are:\n");
// format of help: "Usage: progname [args]\n" // format of help: "Usage: progname [args]\n"
change_helpstring(helpstring); sl_helpstring(helpstring);
// parse arguments // parse arguments
parseargs(&argc, &argv, cmdlnopts); sl_parseargs(&argc, &argv, cmdlnopts);
if(help) showhelp(-1, cmdlnopts); if(help) sl_showhelp(-1, cmdlnopts);
if(argc > 0){ if(argc > 0){
WARNX("Ignore %d unknown parameters: "); WARNX("Ignore %d unknown parameters: ");
for (i = 0; i < argc; i++) for (i = 0; i < argc; i++)

View File

@@ -57,7 +57,7 @@ static void dumpRchanges(rg11 *new, rg11 *old){
int start = 1; int start = 1;
for(int i = 0; i < RREGNUM; ++i){ for(int i = 0; i < RREGNUM; ++i){
if(o[i] != n[i]){ if(o[i] != n[i]){
sl_putlogt(start, globlog, LOGLEVEL_MSG, "%s=%d", regname(i), n[i]); sl_putlogt(start, sl_globlog, LOGLEVEL_MSG, "%s=%d", regname(i), n[i]);
DBG("%s=%d", regname(i), n[i]); DBG("%s=%d", regname(i), n[i]);
if(start) start = 0; if(start) start = 0;
} }
@@ -68,7 +68,7 @@ static void dumpRchanges(rg11 *new, rg11 *old){
uint8_t f = 1; uint8_t f = 1;
for(int i = 0; i < RGBITNUM; ++i, f <<= 1){ for(int i = 0; i < RGBITNUM; ++i, f <<= 1){
if(xOr & f){ if(xOr & f){
sl_putlogt(start, globlog, LOGLEVEL_MSG, "%s=%d", rgbitname(i), (new->RGBits & f) ? 1 : 0); sl_putlogt(start, sl_globlog, LOGLEVEL_MSG, "%s=%d", rgbitname(i), (new->RGBits & f) ? 1 : 0);
DBG("%s=%d", rgbitname(i), (new->RGBits & f) ? 1 : 0); DBG("%s=%d", rgbitname(i), (new->RGBits & f) ? 1 : 0);
if(start) start = 0; if(start) start = 0;
} }
@@ -82,7 +82,7 @@ static void dumpSchanges(slowregs *new, slowregs *old){
int start = 1; int start = 1;
for(int i = 0; i < SREGNUM; ++i){ for(int i = 0; i < SREGNUM; ++i){
if(o[i] != n[i]){ if(o[i] != n[i]){
sl_putlogt(start, globlog, LOGLEVEL_MSG, "%s=%d", slowname(i), n[i]); sl_putlogt(start, sl_globlog, LOGLEVEL_MSG, "%s=%d", slowname(i), n[i]);
DBG("%s=%d", slowname(i), n[i]); DBG("%s=%d", slowname(i), n[i]);
if(start) start = 0; if(start) start = 0;
} }
@@ -147,12 +147,12 @@ static void puttotable(rg11 *R, slowregs *S){
} }
int main(int argc, char **argv){ int main(int argc, char **argv){
initial_setup(); sl_init();
char *self = strdup(argv[0]); char *self = strdup(argv[0]);
G = parse_args(argc, argv); G = parse_args(argc, argv);
if(G->timeout < 5) ERRX("Timeout should be not less than 5 seconds"); if(G->timeout < 5) ERRX("Timeout should be not less than 5 seconds");
if(!G->logfile && !G->outfile) ERRX("Point at least log or output file name"); if(!G->logfile && !G->outfile) ERRX("Point at least log or output file name");
check4running(self, G->pidfile); sl_check4running(self, G->pidfile);
if(!hydreon_open(G->device)) return 1; if(!hydreon_open(G->device)) return 1;
if(G->logfile) OPENLOG(G->logfile, LOGLEVEL_ANY, 0); if(G->logfile) OPENLOG(G->logfile, LOGLEVEL_ANY, 0);
if(G->outfile){ if(G->outfile){
@@ -166,9 +166,9 @@ int main(int argc, char **argv){
signal(SIGINT, signals); // ctrl+C - quit signal(SIGINT, signals); // ctrl+C - quit
signal(SIGQUIT, signals); // ctrl+\ - quit signal(SIGQUIT, signals); // ctrl+\ - quit
signal(SIGTSTP, SIG_IGN); // ignore ctrl+Z signal(SIGTSTP, SIG_IGN); // ignore ctrl+Z
double t0 = dtime(); double t0 = sl_dtime();
puttotable(NULL, NULL); puttotable(NULL, NULL);
while(dtime() - t0 < (double)G->timeout){ // dump only changes while(sl_dtime() - t0 < (double)G->timeout){ // dump only changes
if(!hydreon_getpacket(&Rregs, &Sregs)) continue; if(!hydreon_getpacket(&Rregs, &Sregs)) continue;
int changes = FALSE; int changes = FALSE;
if(memcmp(&Rregs, &oRregs, RREGNUM + 1)){ // Rregs changed -> log changes if(memcmp(&Rregs, &oRregs, RREGNUM + 1)){ // Rregs changed -> log changes
@@ -182,7 +182,7 @@ int main(int argc, char **argv){
changes = TRUE; changes = TRUE;
} }
if(changes) puttotable(&Rregs, &Sregs); if(changes) puttotable(&Rregs, &Sregs);
t0 = dtime(); t0 = sl_dtime();
} }
signals(-1); // never reached signals(-1); // never reached
return 0; return 0;

View File

@@ -20,7 +20,7 @@
#include "hydreon.h" #include "hydreon.h"
static TTY_descr *dev = NULL; static sl_tty_t *dev = NULL;
// regular registers names // regular registers names
static const char* rregnames[RREGNUM] = { static const char* rregnames[RREGNUM] = {
@@ -121,7 +121,7 @@ int hydreon_getpacket(rg11 *Rregs, slowregs *Sregs){
if(!dev) return 0; if(!dev) return 0;
static int buflen = 0; static int buflen = 0;
static char strbuf[BUFLEN]; static char strbuf[BUFLEN];
int l = read_tty(dev); int l = sl_tty_read(dev);
if(l < 1) return FALSE; if(l < 1) return FALSE;
char s = dev->buf[0]; char s = dev->buf[0];
if(s == 's'){ // start of new packet -> encode old if(s == 's'){ // start of new packet -> encode old
@@ -146,13 +146,13 @@ int hydreon_getpacket(rg11 *Rregs, slowregs *Sregs){
* @return TRUE or FALSE if failed * @return TRUE or FALSE if failed
*/ */
int hydreon_open(const char *devname){ int hydreon_open(const char *devname){
dev = new_tty((char*)devname, 1200, 1); dev = sl_tty_new((char*)devname, 1200, 1);
if(!dev) return FALSE; if(!dev) return FALSE;
dev = tty_open(dev, 1); dev = sl_tty_open(dev, 1);
if(!dev) return FALSE; if(!dev) return FALSE;
return TRUE; return TRUE;
} }
void hydreon_close(){ void hydreon_close(){
if(dev) close_tty(&dev); if(dev) sl_tty_close(&dev);
} }

View File

@@ -29,6 +29,7 @@ PIDController_t *pid_create(const PIDpar_t *gain, size_t Iarrsz){
if(!gain || Iarrsz < 3) return NULL; if(!gain || Iarrsz < 3) return NULL;
PIDController_t *pid = (PIDController_t*)calloc(1, sizeof(PIDController_t)); PIDController_t *pid = (PIDController_t*)calloc(1, sizeof(PIDController_t));
pid->gain = *gain; pid->gain = *gain;
DBG("Created PID with P=%g, I=%g, D=%g\n", gain->P, gain->I, gain->D);
pid->pidIarrSize = Iarrsz; pid->pidIarrSize = Iarrsz;
pid->pidIarray = (double*)calloc(Iarrsz, sizeof(double)); pid->pidIarray = (double*)calloc(Iarrsz, sizeof(double));
return pid; return pid;
@@ -83,49 +84,51 @@ typedef struct{
* @return calculated new speed or -1 for max speed * @return calculated new speed or -1 for max speed
*/ */
static double getspeed(const coordval_t *tagpos, PIDpair_t *pidpair, axisdata_t *axis){ static double getspeed(const coordval_t *tagpos, PIDpair_t *pidpair, axisdata_t *axis){
if(tagpos->t < axis->position.t || tagpos->t - axis->position.t > MCC_PID_MAX_DT){ double dt = timediff(&tagpos->t, &axis->position.t);
DBG("target time: %g, axis time: %g - too big! (%g)", tagpos->t, axis->position.t, MCC_PID_MAX_DT); if(dt < 0 || dt > Conf.PIDMaxDt){
DBG("target time: %ld, axis time: %ld - too big! (tag-ax=%g)", tagpos->t.tv_sec, axis->position.t.tv_sec, dt);
return axis->speed.val; // data is too old or wrong return axis->speed.val; // data is too old or wrong
} }
double error = tagpos->val - axis->position.val, fe = fabs(error); double error = tagpos->val - axis->position.val, fe = fabs(error);
DBG("error: %g", error);
PIDController_t *pid = NULL; PIDController_t *pid = NULL;
switch(axis->state){ switch(axis->state){
case AXIS_SLEWING: case AXIS_SLEWING:
if(fe < MCC_MAX_POINTING_ERR){ if(fe < Conf.MaxPointingErr){
axis->state = AXIS_POINTING; axis->state = AXIS_POINTING;
DBG("--> Pointing"); DBG("--> Pointing");
pid = pidpair->PIDC; pid = pidpair->PIDC;
}else{ }else{
DBG("Slewing..."); DBG("Slewing...");
return -1.; // max speed for given axis return NAN; // max speed for given axis
} }
break; break;
case AXIS_POINTING: case AXIS_POINTING:
if(fe < MCC_MAX_GUIDING_ERR){ if(fe < Conf.MaxFinePointingErr){
axis->state = AXIS_GUIDING; axis->state = AXIS_GUIDING;
DBG("--> Guiding"); DBG("--> Guiding");
pid = pidpair->PIDV; pid = pidpair->PIDV;
}else if(fe > MCC_MAX_POINTING_ERR){ }else if(fe > Conf.MaxPointingErr){
DBG("--> Slewing"); DBG("--> Slewing");
axis->state = AXIS_SLEWING; axis->state = AXIS_SLEWING;
return -1.; return NAN;
} else pid = pidpair->PIDC; } else pid = pidpair->PIDC;
break; break;
case AXIS_GUIDING: case AXIS_GUIDING:
pid = pidpair->PIDV; pid = pidpair->PIDV;
if(fe > MCC_MAX_GUIDING_ERR){ if(fe > Conf.MaxFinePointingErr){
DBG("--> Pointing"); DBG("--> Pointing");
axis->state = AXIS_POINTING; axis->state = AXIS_POINTING;
pid = pidpair->PIDC; pid = pidpair->PIDC;
}else if(fe < MCC_MAX_ATTARGET_ERR){ }else if(fe < Conf.MaxGuidingErr){
DBG("At target"); DBG("At target");
// TODO: we can point somehow that we are at target or introduce new axis state // TODO: we can point somehow that we are at target or introduce new axis state
}else DBG("Current error: %g", fe); }else DBG("Current error: %g", fe);
break; break;
case AXIS_STOPPED: // start pointing to target; will change speed next time case AXIS_STOPPED: // start pointing to target; will change speed next time
DBG("AXIS STOPPED!!!!"); DBG("AXIS STOPPED!!!! --> Slewing");
axis->state = AXIS_SLEWING; axis->state = AXIS_SLEWING;
return -1.; return getspeed(tagpos, pidpair, axis);
case AXIS_ERROR: case AXIS_ERROR:
DBG("Can't move from erroneous state"); DBG("Can't move from erroneous state");
return 0.; return 0.;
@@ -134,16 +137,16 @@ static double getspeed(const coordval_t *tagpos, PIDpair_t *pidpair, axisdata_t
DBG("WTF? Where is a PID?"); DBG("WTF? Where is a PID?");
return axis->speed.val; return axis->speed.val;
} }
if(tagpos->t < pid->prevT || tagpos->t - pid->prevT > MCC_PID_MAX_DT){ double dtpid = timediff(&tagpos->t, &pid->prevT);
if(dtpid < 0 || dtpid > Conf.PIDMaxDt){
DBG("time diff too big: clear PID"); DBG("time diff too big: clear PID");
pid_clear(pid); pid_clear(pid);
} }
double dt = tagpos->t - pid->prevT; if(dtpid > Conf.PIDMaxDt) dtpid = Conf.PIDCycleDt;
if(dt > MCC_PID_MAX_DT) dt = MCC_PID_CYCLE_TIME;
pid->prevT = tagpos->t; pid->prevT = tagpos->t;
//DBG("CALC PID (er=%g, dt=%g)", error, dt); DBG("CALC PID (er=%g, dt=%g), state=%d", error, dtpid, axis->state);
double tagspeed = pid_calculate(pid, error, dt); double tagspeed = pid_calculate(pid, error, dtpid);
if(axis->state == AXIS_GUIDING) return axis->speed.val + tagspeed; // velocity-based if(axis->state == AXIS_GUIDING) return axis->speed.val + tagspeed / dtpid; // velocity-based
return tagspeed; // coordinate-based return tagspeed; // coordinate-based
} }
@@ -153,22 +156,23 @@ static double getspeed(const coordval_t *tagpos, PIDpair_t *pidpair, axisdata_t
* @param endpoint - stop point (some far enough point to stop in case of hang) * @param endpoint - stop point (some far enough point to stop in case of hang)
* @return error code * @return error code
*/ */
mcc_errcodes_t correct2(const coordval_pair_t *target, const coordpair_t *endpoint){ mcc_errcodes_t correct2(const coordval_pair_t *target){
static PIDpair_t pidX = {0}, pidY = {0}; static PIDpair_t pidX = {0}, pidY = {0};
if(!pidX.PIDC){ if(!pidX.PIDC){
pidX.PIDC = pid_create(&Conf.XPIDC, MCC_PID_CYCLE_TIME / MCC_PID_REFRESH_DT); pidX.PIDC = pid_create(&Conf.XPIDC, Conf.PIDCycleDt / Conf.PIDRefreshDt);
if(!pidX.PIDC) return MCC_E_FATAL; if(!pidX.PIDC) return MCC_E_FATAL;
pidX.PIDV = pid_create(&Conf.XPIDV, MCC_PID_CYCLE_TIME / MCC_PID_REFRESH_DT); pidX.PIDV = pid_create(&Conf.XPIDV, Conf.PIDCycleDt / Conf.PIDRefreshDt);
if(!pidX.PIDV) return MCC_E_FATAL; if(!pidX.PIDV) return MCC_E_FATAL;
} }
if(!pidY.PIDC){ if(!pidY.PIDC){
pidY.PIDC = pid_create(&Conf.YPIDC, MCC_PID_CYCLE_TIME / MCC_PID_REFRESH_DT); pidY.PIDC = pid_create(&Conf.YPIDC, Conf.PIDCycleDt / Conf.PIDRefreshDt);
if(!pidY.PIDC) return MCC_E_FATAL; if(!pidY.PIDC) return MCC_E_FATAL;
pidY.PIDV = pid_create(&Conf.YPIDV, MCC_PID_CYCLE_TIME / MCC_PID_REFRESH_DT); pidY.PIDV = pid_create(&Conf.YPIDV, Conf.PIDCycleDt / Conf.PIDRefreshDt);
if(!pidY.PIDV) return MCC_E_FATAL; if(!pidY.PIDV) return MCC_E_FATAL;
} }
mountdata_t m; mountdata_t m;
coordpair_t tagspeed; coordpair_t tagspeed; // absolute value of speed
double Xsign = 1., Ysign = 1.; // signs of speed (for target calculation)
if(MCC_E_OK != Mount.getMountData(&m)) return MCC_E_FAILED; if(MCC_E_OK != Mount.getMountData(&m)) return MCC_E_FAILED;
axisdata_t axis; axisdata_t axis;
DBG("state: %d/%d", m.Xstate, m.Ystate); DBG("state: %d/%d", m.Xstate, m.Ystate);
@@ -176,18 +180,42 @@ mcc_errcodes_t correct2(const coordval_pair_t *target, const coordpair_t *endpoi
axis.position = m.encXposition; axis.position = m.encXposition;
axis.speed = m.encXspeed; axis.speed = m.encXspeed;
tagspeed.X = getspeed(&target->X, &pidX, &axis); tagspeed.X = getspeed(&target->X, &pidX, &axis);
if(tagspeed.X < 0. || tagspeed.X > MCC_MAX_X_SPEED) tagspeed.X = MCC_MAX_X_SPEED; if(isnan(tagspeed.X)){ // max speed
if(target->X.val < axis.position.val) Xsign = -1.;
tagspeed.X = Xlimits.max.speed;
}else{
if(tagspeed.X < 0.){ tagspeed.X = -tagspeed.X; Xsign = -1.; }
if(tagspeed.X > Xlimits.max.speed) tagspeed.X = Xlimits.max.speed;
}
axis_status_t xstate = axis.state; axis_status_t xstate = axis.state;
axis.state = m.Ystate; axis.state = m.Ystate;
axis.position = m.encYposition; axis.position = m.encYposition;
axis.speed = m.encYspeed; axis.speed = m.encYspeed;
tagspeed.Y = getspeed(&target->Y, &pidY, &axis); tagspeed.Y = getspeed(&target->Y, &pidY, &axis);
if(tagspeed.Y < 0. || tagspeed.Y > MCC_MAX_Y_SPEED) tagspeed.Y = MCC_MAX_Y_SPEED; if(isnan(tagspeed.Y)){ // max speed
if(target->Y.val < axis.position.val) Ysign = -1.;
tagspeed.Y = Ylimits.max.speed;
}else{
if(tagspeed.Y < 0.){ tagspeed.Y = -tagspeed.Y; Ysign = -1.; }
if(tagspeed.Y > Ylimits.max.speed) tagspeed.Y = Ylimits.max.speed;
}
axis_status_t ystate = axis.state; axis_status_t ystate = axis.state;
if(m.Xstate != xstate || m.Ystate != ystate){ if(m.Xstate != xstate || m.Ystate != ystate){
DBG("State changed"); DBG("State changed");
setStat(xstate, ystate); setStat(xstate, ystate);
} }
DBG("TAG speeds: %g/%g", tagspeed.X, tagspeed.Y); coordpair_t endpoint;
return Mount.moveWspeed(endpoint, &tagspeed); // allow at least PIDMaxDt moving with target speed
double dv = fabs(tagspeed.X - m.encXspeed.val);
double adder = dv/Xlimits.max.accel * (m.encXspeed.val + dv / 2.) // distanse with changing speed
+ Conf.PIDMaxDt * tagspeed.X // PIDMaxDt const speed moving
+ tagspeed.X * tagspeed.X / Xlimits.max.accel / 2.; // stopping
endpoint.X = m.encXposition.val + Xsign * adder;
dv = fabs(tagspeed.Y - m.encYspeed.val);
adder = dv/Ylimits.max.accel * (m.encYspeed.val + dv / 2.)
+ Conf.PIDMaxDt * tagspeed.Y
+ tagspeed.Y * tagspeed.Y / Ylimits.max.accel / 2.;
endpoint.Y = m.encYposition.val + Ysign * adder;
DBG("TAG speeds: %g/%g (deg/s); TAG pos: %g/%g (deg)", tagspeed.X/M_PI*180., tagspeed.Y/M_PI*180., endpoint.X/M_PI*180., endpoint.Y/M_PI*180.);
return Mount.moveWspeed(&endpoint, &tagspeed);
} }

View File

@@ -27,7 +27,7 @@ typedef struct {
double prev_error; // Previous error double prev_error; // Previous error
double integral; // Integral term double integral; // Integral term
double *pidIarray; // array for Integral double *pidIarray; // array for Integral
double prevT; // time of previous correction struct timespec prevT; // time of previous correction
size_t pidIarrSize; // it's size size_t pidIarrSize; // it's size
size_t curIidx; // and index of current element size_t curIidx; // and index of current element
} PIDController_t; } PIDController_t;
@@ -37,4 +37,4 @@ void pid_clear(PIDController_t *pid);
void pid_delete(PIDController_t **pid); void pid_delete(PIDController_t **pid);
double pid_calculate(PIDController_t *pid, double error, double dt); double pid_calculate(PIDController_t *pid, double error, double dt);
mcc_errcodes_t correct2(const coordval_pair_t *target, const coordpair_t *endpoint); mcc_errcodes_t correct2(const coordval_pair_t *target);

View File

@@ -1,5 +1,7 @@
Dramp.c Dramp.c
Dramp.h Dramp.h
PID.c
PID.h
Sramp.c Sramp.c
Sramp.h Sramp.h
Tramp.c Tramp.c

View File

@@ -1,3 +1,3 @@
1. PID: slew2 fix encoders opening for several tries
2. add model & config "model ON" encoderthread2() - change main cycle (remove pause, read data independently, ask for new only after timeout after last request)
Read HW config even in model mode

View File

@@ -34,7 +34,9 @@ typedef struct{
static hardware_configuration_t HW = {0}; static hardware_configuration_t HW = {0};
static parameters G = {0}; static parameters G = {
.conffile = "servo.conf",
};
static sl_option_t cmdlnopts[] = { static sl_option_t cmdlnopts[] = {
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&G.help), "show this help"}, {"help", NO_ARGS, NULL, 'h', arg_int, APTR(&G.help), "show this help"},
@@ -53,7 +55,7 @@ static sl_option_t confopts[] = {
static void dumpaxis(char axis, axis_config_t *c){ static void dumpaxis(char axis, axis_config_t *c){
#define STRUCTPAR(p) (c)->p #define STRUCTPAR(p) (c)->p
#define DUMP(par) do{printf("%c%s=%g\n", axis, #par, STRUCTPAR(par));}while(0) #define DUMP(par) do{printf("%c%s=%.10g\n", axis, #par, STRUCTPAR(par));}while(0)
#define DUMPD(par) do{printf("%c%s=%g\n", axis, #par, RAD2DEG(STRUCTPAR(par)));}while(0) #define DUMPD(par) do{printf("%c%s=%g\n", axis, #par, RAD2DEG(STRUCTPAR(par)));}while(0)
DUMPD(accel); DUMPD(accel);
DUMPD(backlash); DUMPD(backlash);
@@ -64,6 +66,8 @@ static void dumpaxis(char axis, axis_config_t *c){
DUMP(outplimit); DUMP(outplimit);
DUMP(currlimit); DUMP(currlimit);
DUMP(intlimit); DUMP(intlimit);
DUMP(motor_stepsperrev);
DUMP(axis_stepsperrev);
#undef DUMP #undef DUMP
#undef DUMPD #undef DUMPD
} }

View File

@@ -24,25 +24,32 @@
static conf_t Config = { static conf_t Config = {
.MountDevPath = "/dev/ttyUSB0", .MountDevPath = "/dev/ttyUSB0",
.MountDevSpeed = 19200, .MountDevSpeed = 19200,
.EncoderXDevPath = "/dev/encoderX0", .EncoderXDevPath = "/dev/encoder_X0",
.EncoderYDevPath = "/dev/encoderY0", .EncoderYDevPath = "/dev/encoder_Y0",
.EncoderDevSpeed = 153000, .EncoderDevSpeed = 153000,
.MountReqInterval = 0.1, .MountReqInterval = 0.1,
.EncoderReqInterval = 0.05, .EncoderReqInterval = 0.001,
.SepEncoder = 2, .SepEncoder = 2,
.EncoderSpeedInterval = 0.1, .EncoderSpeedInterval = 0.05,
.XPIDC.P = 0.8, .EncodersDisagreement = 1e-5, // 2''
.PIDMaxDt = 1.,
.PIDRefreshDt = 0.1,
.PIDCycleDt = 5.,
.XPIDC.P = 0.5,
.XPIDC.I = 0.1, .XPIDC.I = 0.1,
.XPIDC.D = 0.3, .XPIDC.D = 0.2,
.XPIDV.P = 1., .XPIDV.P = 0.09,
.XPIDV.I = 0.01, .XPIDV.I = 0.0,
.XPIDV.D = 0.2, .XPIDV.D = 0.05,
.YPIDC.P = 0.8, .YPIDC.P = 0.5,
.YPIDC.I = 0.1, .YPIDC.I = 0.1,
.YPIDC.D = 0.3, .YPIDC.D = 0.2,
.YPIDV.P = 0.5, .YPIDV.P = 0.09,
.YPIDV.I = 0.2, .YPIDV.I = 0.0,
.YPIDV.D = 0.5, .YPIDV.D = 0.05,
.MaxPointingErr = 0.13962634,
.MaxFinePointingErr = 0.026179939,
.MaxGuidingErr = 4.8481368e-7,
}; };
static sl_option_t opts[] = { static sl_option_t opts[] = {
@@ -50,13 +57,17 @@ static sl_option_t opts[] = {
{"MountDevSpeed", NEED_ARG, NULL, 0, arg_int, APTR(&Config.MountDevSpeed), "serial speed of mount device"}, {"MountDevSpeed", NEED_ARG, NULL, 0, arg_int, APTR(&Config.MountDevSpeed), "serial speed of mount device"},
{"EncoderDevPath", NEED_ARG, NULL, 0, arg_string, APTR(&Config.EncoderDevPath), "path to encoder device"}, {"EncoderDevPath", NEED_ARG, NULL, 0, arg_string, APTR(&Config.EncoderDevPath), "path to encoder device"},
{"EncoderDevSpeed", NEED_ARG, NULL, 0, arg_int, APTR(&Config.EncoderDevSpeed), "serial speed of encoder device"}, {"EncoderDevSpeed", NEED_ARG, NULL, 0, arg_int, APTR(&Config.EncoderDevSpeed), "serial speed of encoder device"},
{"MountReqInterval",NEED_ARG, NULL, 0, arg_double, APTR(&Config.MountReqInterval), "interval of mount requests (not less than 0.05s)"}, {"SepEncoder", NEED_ARG, NULL, 0, arg_int, APTR(&Config.SepEncoder), "encoder is separate device (1 - one device, 2 - two devices)"},
{"EncoderReqInterval",NEED_ARG, NULL, 0, arg_double, APTR(&Config.EncoderReqInterval),"interval of encoder requests (in case of sep=2)"},
{"SepEncoder", NO_ARGS, NULL, 0, arg_int, APTR(&Config.SepEncoder), "encoder is separate device (1 - one device, 2 - two devices)"},
{"EncoderXDevPath", NEED_ARG, NULL, 0, arg_string, APTR(&Config.EncoderXDevPath), "path to X encoder (/dev/encoderX0)"}, {"EncoderXDevPath", NEED_ARG, NULL, 0, arg_string, APTR(&Config.EncoderXDevPath), "path to X encoder (/dev/encoderX0)"},
{"EncoderYDevPath", NEED_ARG, NULL, 0, arg_string, APTR(&Config.EncoderYDevPath), "path to Y encoder (/dev/encoderY0)"}, {"EncoderYDevPath", NEED_ARG, NULL, 0, arg_string, APTR(&Config.EncoderYDevPath), "path to Y encoder (/dev/encoderY0)"},
{"EncodersDisagreement", NEED_ARG,NULL, 0, arg_double, APTR(&Config.EncodersDisagreement),"acceptable disagreement between motor and axis encoders"},
{"MountReqInterval",NEED_ARG, NULL, 0, arg_double, APTR(&Config.MountReqInterval), "interval of mount requests (not less than 0.05s)"},
{"EncoderReqInterval",NEED_ARG, NULL, 0, arg_double, APTR(&Config.EncoderReqInterval),"interval of encoder requests (in case of sep=2)"},
{"EncoderSpeedInterval", NEED_ARG,NULL, 0, arg_double, APTR(&Config.EncoderSpeedInterval),"interval of speed calculations, s"}, {"EncoderSpeedInterval", NEED_ARG,NULL, 0, arg_double, APTR(&Config.EncoderSpeedInterval),"interval of speed calculations, s"},
{"RunModel", NEED_ARG, NULL, 0, arg_int, APTR(&Config.RunModel), "instead of real hardware run emulation"}, {"RunModel", NEED_ARG, NULL, 0, arg_int, APTR(&Config.RunModel), "instead of real hardware run emulation"},
{"PIDMaxDt", NEED_ARG, NULL, 0, arg_double, APTR(&Config.PIDMaxDt), "maximal PID refresh time interval (if larger all old data will be cleared)"},
{"PIDRefreshDt", NEED_ARG, NULL, 0, arg_double, APTR(&Config.PIDRefreshDt), "normal PID refresh interval by master process"},
{"PIDCycleDt", NEED_ARG, NULL, 0, arg_double, APTR(&Config.PIDCycleDt), "PID I cycle time (analog of \"RC\" for PID on opamps)"},
{"XPIDCP", NEED_ARG, NULL, 0, arg_double, APTR(&Config.XPIDC.P), "P of X PID (coordinate driven)"}, {"XPIDCP", NEED_ARG, NULL, 0, arg_double, APTR(&Config.XPIDC.P), "P of X PID (coordinate driven)"},
{"XPIDCI", NEED_ARG, NULL, 0, arg_double, APTR(&Config.XPIDC.I), "I of X PID (coordinate driven)"}, {"XPIDCI", NEED_ARG, NULL, 0, arg_double, APTR(&Config.XPIDC.I), "I of X PID (coordinate driven)"},
{"XPIDCD", NEED_ARG, NULL, 0, arg_double, APTR(&Config.XPIDC.D), "D of X PID (coordinate driven)"}, {"XPIDCD", NEED_ARG, NULL, 0, arg_double, APTR(&Config.XPIDC.D), "D of X PID (coordinate driven)"},
@@ -69,6 +80,12 @@ static sl_option_t opts[] = {
{"YPIDVP", NEED_ARG, NULL, 0, arg_double, APTR(&Config.YPIDV.P), "P of Y PID (velocity driven)"}, {"YPIDVP", NEED_ARG, NULL, 0, arg_double, APTR(&Config.YPIDV.P), "P of Y PID (velocity driven)"},
{"YPIDVI", NEED_ARG, NULL, 0, arg_double, APTR(&Config.YPIDV.I), "I of Y PID (velocity driven)"}, {"YPIDVI", NEED_ARG, NULL, 0, arg_double, APTR(&Config.YPIDV.I), "I of Y PID (velocity driven)"},
{"YPIDVD", NEED_ARG, NULL, 0, arg_double, APTR(&Config.YPIDV.D), "D of Y PID (velocity driven)"}, {"YPIDVD", NEED_ARG, NULL, 0, arg_double, APTR(&Config.YPIDV.D), "D of Y PID (velocity driven)"},
{"MaxPointingErr", NEED_ARG, NULL, 0, arg_double, APTR(&Config.MaxPointingErr), "if angle < this, change state from \"slewing\" to \"pointing\" (coarse pointing): 8 degrees"},
{"MaxFinePointingErr",NEED_ARG, NULL, 0, arg_double, APTR(&Config.MaxFinePointingErr), "if angle < this, chane state from \"pointing\" to \"guiding\" (fine poinging): 1.5 deg"},
{"MaxGuidingErr", NEED_ARG, NULL, 0, arg_double, APTR(&Config.MaxGuidingErr), "if error less than this value we suppose that target is captured and guiding is good (true guiding): 0.1''"},
{"XEncZero", NEED_ARG, NULL, 0, arg_int, APTR(&Config.XEncZero), "X axis encoder approximate zero position"},
{"YEncZero", NEED_ARG, NULL, 0, arg_int, APTR(&Config.YEncZero), "Y axis encoder approximate zero position"},
// {"",NEED_ARG, NULL, 0, arg_double, APTR(&Config.), ""},
end_option end_option
}; };
@@ -93,5 +110,19 @@ void dumpConf(){
} }
void confHelp(){ void confHelp(){
sl_showhelp(-1, opts); sl_conf_showhelp(-1, opts);
}
const char* errcodes[MCC_E_AMOUNT] = {
[MCC_E_OK] = "OK",
[MCC_E_FATAL] = "Fatal error",
[MCC_E_BADFORMAT] = "Wrong data format",
[MCC_E_ENCODERDEV] = "Encoder error",
[MCC_E_MOUNTDEV] = "Mount error",
[MCC_E_FAILED] = "Failed to run"
};
// return string with error code
const char *EcodeStr(mcc_errcodes_t e){
if(e >= MCC_E_AMOUNT) return "Wrong error code";
return errcodes[e];
} }

View File

@@ -25,3 +25,4 @@
void confHelp(); void confHelp();
conf_t *readServoConf(const char *filename); conf_t *readServoConf(const char *filename);
void dumpConf(); void dumpConf();
const char *EcodeStr(mcc_errcodes_t e);

View File

@@ -23,6 +23,9 @@
#include "dump.h" #include "dump.h"
#include "simpleconv.h" #include "simpleconv.h"
// starting dump time (to conform different logs)
static struct timespec dumpT0 = {0};
#if 0 #if 0
// amount of elements used for encoders' data filtering // amount of elements used for encoders' data filtering
#define NFILT (10) #define NFILT (10)
@@ -59,6 +62,12 @@ static double filter(double val, int idx){
} }
#endif #endif
// return starting time of dump
void dumpt0(struct timespec *t){
if(t) *t = dumpT0;
}
/** /**
* @brief logmnt - log mount data into file * @brief logmnt - log mount data into file
* @param fcoords - file to dump * @param fcoords - file to dump
@@ -67,17 +76,13 @@ static double filter(double val, int idx){
void logmnt(FILE *fcoords, mountdata_t *m){ void logmnt(FILE *fcoords, mountdata_t *m){
if(!fcoords) return; if(!fcoords) return;
//DBG("LOG %s", m ? "data" : "header"); //DBG("LOG %s", m ? "data" : "header");
static double t0 = -1.;
if(!m){ // write header if(!m){ // write header
fprintf(fcoords, "# time Xmot(deg) Ymot(deg) Xenc(deg) Yenc(deg) VX(d/s) VY(d/s) millis\n"); fprintf(fcoords, " time Xmot(deg) Ymot(deg) Xenc(deg) Yenc(deg) VX(d/s) VY(d/s) millis\n");
return; return;
} }else if(dumpT0.tv_sec == 0) dumpT0 = m->encXposition.t;
double tnow = (m->encXposition.t + m->encYposition.t) / 2.;
if(t0 < 0.) t0 = tnow;
double t = tnow - t0;
// write data // write data
fprintf(fcoords, "%12.6f %10.6f %10.6f %10.6f %10.6f %10.6f %10.6f %10u\n", fprintf(fcoords, "%12.6f %10.6f %10.6f %10.6f %10.6f %10.6f %10.6f %10u\n",
t, RAD2DEG(m->motXposition.val), RAD2DEG(m->motYposition.val), Mount.timeDiff(&m->encXposition.t, &dumpT0), RAD2DEG(m->motXposition.val), RAD2DEG(m->motYposition.val),
RAD2DEG(m->encXposition.val), RAD2DEG(m->encYposition.val), RAD2DEG(m->encXposition.val), RAD2DEG(m->encYposition.val),
RAD2DEG(m->encXspeed.val), RAD2DEG(m->encYspeed.val), RAD2DEG(m->encXspeed.val), RAD2DEG(m->encYspeed.val),
m->millis); m->millis);
@@ -103,16 +108,17 @@ void dumpmoving(FILE *fcoords, double t, int N){
LOGWARN("Can't get mount data"); LOGWARN("Can't get mount data");
} }
uint32_t mdmillis = mdata.millis; uint32_t mdmillis = mdata.millis;
double enct = (mdata.encXposition.t + mdata.encYposition.t) / 2.; struct timespec encXt = mdata.encXposition.t;
int ctr = -1; int ctr = -1;
double xlast = mdata.motXposition.val, ylast = mdata.motYposition.val; double xlast = mdata.motXposition.val, ylast = mdata.motYposition.val;
double t0 = Mount.currentT(); double t0 = Mount.timeFromStart();
while(Mount.currentT() - t0 < t && ctr < N){ while(Mount.timeFromStart() - t0 < t && ctr < N){
usleep(1000); usleep(1000);
if(MCC_E_OK != Mount.getMountData(&mdata)){ WARNX("Can't get data"); continue;} if(MCC_E_OK != Mount.getMountData(&mdata)){ WARNX("Can't get data"); continue;}
double tmsr = (mdata.encXposition.t + mdata.encYposition.t) / 2.; //double tmsr = (mdata.encXposition.t + mdata.encYposition.t) / 2.;
if(tmsr == enct) continue; struct timespec msrt = mdata.encXposition.t;
enct = tmsr; if(msrt.tv_nsec == encXt.tv_nsec) continue;
encXt = msrt;
if(fcoords) logmnt(fcoords, &mdata); if(fcoords) logmnt(fcoords, &mdata);
if(mdata.millis == mdmillis) continue; if(mdata.millis == mdmillis) continue;
//DBG("ctr=%d, motpos=%g/%g", ctr, mdata.motXposition.val, mdata.motYposition.val); //DBG("ctr=%d, motpos=%g/%g", ctr, mdata.motXposition.val, mdata.motYposition.val);
@@ -123,7 +129,7 @@ void dumpmoving(FILE *fcoords, double t, int N){
ctr = 0; ctr = 0;
}else ++ctr; }else ++ctr;
} }
DBG("Exit dumping; tend=%g, tmon=%g", t, Mount.currentT() - t0); DBG("Exit dumping; tend=%g, tmon=%g", t, Mount.timeFromStart() - t0);
} }
/** /**
@@ -134,17 +140,15 @@ void waitmoving(int N){
mountdata_t mdata; mountdata_t mdata;
int ctr = -1; int ctr = -1;
uint32_t millis = 0; uint32_t millis = 0;
double xlast = 0., ylast = 0.; //double xlast = 0., ylast = 0.;
DBG("Wait moving for %d stopped times", N);
while(ctr < N){ while(ctr < N){
usleep(10000); usleep(10000);
if(MCC_E_OK != Mount.getMountData(&mdata)){ WARNX("Can't get data"); continue;} if(MCC_E_OK != Mount.getMountData(&mdata)){ WARNX("Can't get data"); continue;}
if(mdata.millis == millis) continue; if(mdata.millis == millis) continue;
millis = mdata.millis; millis = mdata.millis;
if(mdata.motXposition.val != xlast || mdata.motYposition.val != ylast){ if(mdata.Xstate != AXIS_STOPPED || mdata.Ystate != AXIS_STOPPED) ctr = 0;
xlast = mdata.motXposition.val; else ++ctr;
ylast = mdata.motYposition.val;
ctr = 0;
}else ++ctr;
} }
} }

View File

@@ -27,3 +27,4 @@ void dumpmoving(FILE *fcoords, double t, int N);
void waitmoving(int N); void waitmoving(int N);
int getPos(coordval_pair_t *mot, coordval_pair_t *enc); int getPos(coordval_pair_t *mot, coordval_pair_t *enc);
void chk0(int ncycles); void chk0(int ncycles);
void dumpt0(struct timespec *t);

View File

@@ -73,6 +73,7 @@ int main(int argc, char **argv){
conf_t *Config = readServoConf(G.conffile); conf_t *Config = readServoConf(G.conffile);
if(!Config){ if(!Config){
dumpConf(); dumpConf();
confHelp();
return 1; return 1;
} }
if(G.coordsoutput){ if(G.coordsoutput){

View File

@@ -139,8 +139,10 @@ static mcc_errcodes_t return2zero(){
short_command_t cmd = {0}; short_command_t cmd = {0};
DBG("Try to move to zero"); DBG("Try to move to zero");
cmd.Xmot = 0.; cmd.Ymot = 0.; cmd.Xmot = 0.; cmd.Ymot = 0.;
cmd.Xspeed = MCC_MAX_X_SPEED; coordpair_t maxspd;
cmd.Yspeed = MCC_MAX_Y_SPEED; if(MCC_E_OK != Mount.getMaxSpeed(&maxspd)) return MCC_E_FAILED;
cmd.Xspeed = maxspd.X;
cmd.Yspeed = maxspd.Y;
/*cmd.xychange = 1; /*cmd.xychange = 1;
cmd.XBits = 100; cmd.XBits = 100;
cmd.YBits = 20;*/ cmd.YBits = 20;*/
@@ -216,7 +218,7 @@ int main(int argc, char **argv){
sleep(5); sleep(5);
// return to zero and wait // return to zero and wait
green("Return 2 zero and wait\n"); green("Return 2 zero and wait\n");
if(!return2zero()) ERRX("Can't return"); if(MCC_E_OK != return2zero()) ERRX("Can't return");
Wait(0., 0); Wait(0., 0);
Wait(0., 1); Wait(0., 1);
// wait moving ends // wait moving ends

View File

@@ -83,7 +83,7 @@ void waithalf(double t){
uint32_t millis = 0; uint32_t millis = 0;
double xlast = 0., ylast = 0.; double xlast = 0., ylast = 0.;
while(ctr < 5){ while(ctr < 5){
if(Mount.currentT() >= t) return; if(Mount.timeFromStart() >= t) return;
usleep(1000); usleep(1000);
if(MCC_E_OK != Mount.getMountData(&mdata)){ WARNX("Can't get data"); continue;} if(MCC_E_OK != Mount.getMountData(&mdata)){ WARNX("Can't get data"); continue;}
if(mdata.millis == millis) continue; if(mdata.millis == millis) continue;
@@ -110,16 +110,28 @@ int main(int argc, char **argv){
return 1; return 1;
} }
if(G.coordsoutput){ if(G.coordsoutput){
if(!(fcoords = fopen(G.coordsoutput, "w"))) if(!(fcoords = fopen(G.coordsoutput, "w"))){
ERRX("Can't open %s", G.coordsoutput); WARNX("Can't open %s", G.coordsoutput);
return 1;
}
}else fcoords = stdout; }else fcoords = stdout;
if(G.Ncycles < 7) ERRX("Ncycles should be >7"); if(G.Ncycles < 2){
WARNX("Ncycles should be >2");
return 1;
}
double absamp = fabs(G.amplitude); double absamp = fabs(G.amplitude);
if(absamp < 0.01 || absamp > 45.) if(absamp < 0.01 || absamp > 45.){
ERRX("Amplitude should be from 0.01 to 45 degrees"); WARNX("Amplitude should be from 0.01 to 45 degrees");
if(G.period < 0.1 || G.period > 900.) return 1;
ERRX("Period should be from 0.1 to 900s"); }
if(G.Nswings < 1) ERRX("Nswings should be more than 0"); if(G.period < 0.1 || G.period > 900.){
WARNX("Period should be from 0.1 to 900s");
return 1;
}
if(G.Nswings < 1){
WARNX("Nswings should be more than 0");
return 1;
}
conf_t *Config = readServoConf(G.conffile); conf_t *Config = readServoConf(G.conffile);
if(!Config){ if(!Config){
dumpConf(); dumpConf();
@@ -146,24 +158,24 @@ int main(int argc, char **argv){
}else{ }else{
tagX = 0.; tagY = DEG2RAD(G.amplitude); tagX = 0.; tagY = DEG2RAD(G.amplitude);
} }
double t = Mount.currentT(), t0 = t; double t = Mount.timeFromStart(), t0 = t;
coordpair_t tag = {.X = tagX, .Y = tagY}, rtag = {.X = -tagX, .Y = -tagY}; coordpair_t tag = {.X = tagX, .Y = tagY}, rtag = {.X = -tagX, .Y = -tagY};
double divide = 2.; double divide = 2.;
for(int i = 0; i < G.Nswings; ++i){ for(int i = 0; i < G.Nswings; ++i){
Mount.moveTo(&tag); Mount.moveTo(&tag);
DBG("CMD: %g", Mount.currentT()-t0); DBG("CMD: %g", Mount.timeFromStart()-t0);
t += G.period / divide; t += G.period / divide;
divide = 1.; divide = 1.;
waithalf(t); waithalf(t);
DBG("Moved to +, t=%g", t-t0); DBG("Moved to +, t=%g", t-t0);
DBG("CMD: %g", Mount.currentT()-t0); DBG("CMD: %g", Mount.timeFromStart()-t0);
Mount.moveTo(&rtag); Mount.moveTo(&rtag);
t += G.period; t += G.period;
waithalf(t); waithalf(t);
DBG("Moved to -, t=%g", t-t0); DBG("Moved to -, t=%g", t-t0);
DBG("CMD: %g", Mount.currentT()-t0); DBG("CMD: %g", Mount.timeFromStart()-t0);
} }
green("Move to zero @ %g\n", Mount.currentT()); green("Move to zero @ %g\n", Mount.timeFromStart());
tag = (coordpair_t){0}; tag = (coordpair_t){0};
// be sure to move @ 0,0 // be sure to move @ 0,0
if(MCC_E_OK != Mount.moveTo(&tag)){ if(MCC_E_OK != Mount.moveTo(&tag)){

View File

@@ -61,12 +61,13 @@ static FILE* fcoords = NULL;
static pthread_t dthr; static pthread_t dthr;
void signals(int sig){ void signals(int sig){
pthread_cancel(dthr);
if(sig){ if(sig){
signal(sig, SIG_IGN); signal(sig, SIG_IGN);
DBG("Get signal %d, quit.\n", sig); DBG("Get signal %d, quit.\n", sig);
} }
DBG("Quit");
Mount.quit(); Mount.quit();
DBG("close");
if(fcoords) fclose(fcoords); if(fcoords) fclose(fcoords);
exit(sig); exit(sig);
} }
@@ -90,11 +91,10 @@ int main(int _U_ argc, char _U_ **argv){
if(MCC_E_OK != Mount.init(Config)) ERRX("Can't init mount"); if(MCC_E_OK != Mount.init(Config)) ERRX("Can't init mount");
coordval_pair_t M, E; coordval_pair_t M, E;
if(!getPos(&M, &E)) ERRX("Can't get current position"); if(!getPos(&M, &E)) ERRX("Can't get current position");
printf("Current time: %.10f\n", Mount.timeFromStart());
if(G.coordsoutput){ if(G.coordsoutput){
if(!G.wait) green("When logging I should wait until moving ends; added '-w'"); if(!G.wait) green("When logging I should wait until moving ends; added '-w'\n");
G.wait = 1; G.wait = 1;
}
if(G.coordsoutput){
if(!(fcoords = fopen(G.coordsoutput, "w"))) if(!(fcoords = fopen(G.coordsoutput, "w")))
ERRX("Can't open %s", G.coordsoutput); ERRX("Can't open %s", G.coordsoutput);
logmnt(fcoords, NULL); logmnt(fcoords, NULL);
@@ -120,7 +120,11 @@ int main(int _U_ argc, char _U_ **argv){
} }
printf("Moving to X=%gdeg, Y=%gdeg\n", G.X, G.Y); printf("Moving to X=%gdeg, Y=%gdeg\n", G.X, G.Y);
tag.X = DEG2RAD(G.X); tag.Y = DEG2RAD(G.Y); tag.X = DEG2RAD(G.X); tag.Y = DEG2RAD(G.Y);
Mount.moveTo(&tag); mcc_errcodes_t e = Mount.moveTo(&tag);
if(MCC_E_OK != e){
WARNX("Cant go to given coordinates: %s\n", EcodeStr(e));
goto out;
}
if(G.wait){ if(G.wait){
sleep(1); sleep(1);
waitmoving(G.Ncycles); waitmoving(G.Ncycles);
@@ -132,7 +136,9 @@ out:
if(G.coordsoutput) pthread_join(dthr, NULL); if(G.coordsoutput) pthread_join(dthr, NULL);
DBG("QUIT"); DBG("QUIT");
if(G.wait){ if(G.wait){
if(getPos(&M, NULL)) printf("Mount position: X=%g, Y=%g\n", RAD2DEG(M.X.val), RAD2DEG(M.Y.val)); usleep(250000); // pause to refresh coordinates
if(getPos(&M, &E)) printf("Mount position: X=%g, Y=%g; encoders: X=%g, Y=%g\n", RAD2DEG(M.X.val), RAD2DEG(M.Y.val),
RAD2DEG(E.X.val), RAD2DEG(E.Y.val));
Mount.quit(); Mount.quit();
} }
return 0; return 0;

View File

@@ -44,6 +44,7 @@ typedef struct{
char *conffile; char *conffile;
} parameters; } parameters;
static conf_t *Config = NULL;
static FILE *fcoords = NULL, *errlog = NULL; static FILE *fcoords = NULL, *errlog = NULL;
static pthread_t dthr; static pthread_t dthr;
static parameters G = { static parameters G = {
@@ -75,7 +76,6 @@ static sl_option_t cmdlnopts[] = {
}; };
void signals(int sig){ void signals(int sig){
pthread_cancel(dthr);
if(sig){ if(sig){
signal(sig, SIG_IGN); signal(sig, SIG_IGN);
DBG("Get signal %d, quit.\n", sig); DBG("Get signal %d, quit.\n", sig);
@@ -97,35 +97,35 @@ static void runtraectory(traectory_fn tfn){
if(!tfn) return; if(!tfn) return;
coordval_pair_t telXY; coordval_pair_t telXY;
coordval_pair_t target; coordval_pair_t target;
coordpair_t traectXY, endpoint; coordpair_t traectXY;
endpoint.X = G.Xmax, endpoint.Y = G.Ymax; double tlast = 0., tstart = Mount.timeFromStart();
double t0 = Mount.currentT(), tlast = 0.; long tlastXnsec = 0, tlastYnsec = 0;
double tlastX = 0., tlastY = 0.; struct timespec tcur, t0 = {0};
dumpt0(&t0);
while(1){ while(1){
if(!telpos(&telXY)){ if(!telpos(&telXY)){
WARNX("No next telescope position"); WARNX("No next telescope position");
return; return;
} }
if(telXY.X.t == tlastX && telXY.Y.t == tlastY) continue; // last measure - don't mind if(!Mount.currentT(&tcur)) continue;
DBG("\n\nTELPOS: %g'/%g' measured @ %g/%g", RAD2AMIN(telXY.X.val), RAD2AMIN(telXY.Y.val), telXY.X.t, telXY.Y.t); if(telXY.X.t.tv_nsec == tlastXnsec && telXY.Y.t.tv_nsec == tlastYnsec) continue; // last measure - don't mind
tlastX = telXY.X.t; tlastY = telXY.Y.t; DBG("\n\nTELPOS: %g'/%g' (%.6f/%.6f)", RAD2AMIN(telXY.X.val), RAD2AMIN(telXY.Y.val), RAD2DEG(telXY.X.val), RAD2DEG(telXY.Y.val));
double t = Mount.currentT(); tlastXnsec = telXY.X.t.tv_nsec; tlastYnsec = telXY.Y.t.tv_nsec;
if(fabs(telXY.X.val) > G.Xmax || fabs(telXY.Y.val) > G.Ymax || t - t0 > G.tmax) break; double t = Mount.timeFromStart();
if(fabs(telXY.X.val) > G.Xmax || fabs(telXY.Y.val) > G.Ymax || t - tstart > G.tmax) break;
if(!traectory_point(&traectXY, t)) break; if(!traectory_point(&traectXY, t)) break;
target.X.val = traectXY.X; target.Y.val = traectXY.Y; target.X.val = traectXY.X; target.Y.val = traectXY.Y;
target.X.t = target.Y.t = t; target.X.t = target.Y.t = tcur;
// check whether we should change direction if(t0.tv_nsec == 0 && t0.tv_sec == 0) dumpt0(&t0);
if(telXY.X.val > traectXY.X) endpoint.X = -G.Xmax; else{
else if(telXY.X.val < traectXY.X) endpoint.X = G.Xmax; //DBG("target: %g'/%g'", RAD2AMIN(traectXY.X), RAD2AMIN(traectXY.Y));
if(telXY.Y.val > traectXY.Y) endpoint.Y = -G.Ymax; DBG("%g: dX=%.4f'', dY=%.4f''", t-tstart, RAD2ASEC(traectXY.X-telXY.X.val), RAD2ASEC(traectXY.Y-telXY.Y.val));
else if(telXY.Y.val < traectXY.Y) endpoint.Y = G.Ymax; //DBG("Correct to: %g/%g with EP %g/%g", RAD2DEG(target.X.val), RAD2DEG(target.Y.val), RAD2DEG(endpoint.X), RAD2DEG(endpoint.Y));
DBG("target: %g'/%g'", RAD2AMIN(traectXY.X), RAD2AMIN(traectXY.Y));
DBG("%g: dX=%.4f'', dY=%.4f''", t-t0, RAD2ASEC(traectXY.X-telXY.X.val), RAD2ASEC(traectXY.Y-telXY.Y.val));
DBG("Correct to: %g/%g with EP %g/%g", RAD2DEG(target.X.val), RAD2DEG(target.Y.val), RAD2DEG(endpoint.X), RAD2DEG(endpoint.Y));
if(errlog) if(errlog)
fprintf(errlog, "%10.4g %10.4g %10.4g\n", t, RAD2ASEC(traectXY.X-telXY.X.val), RAD2ASEC(traectXY.Y-telXY.Y.val)); fprintf(errlog, "%10.4f %10.4f %10.4f\n", Mount.timeDiff(&telXY.X.t, &t0), RAD2ASEC(traectXY.X-telXY.X.val), RAD2ASEC(traectXY.Y-telXY.Y.val));
if(MCC_E_OK != Mount.correctTo(&target, &endpoint)) WARNX("Error of correction!"); }
while((t = Mount.currentT()) - tlast < MCC_PID_REFRESH_DT) usleep(50); if(MCC_E_OK != Mount.correctTo(&target)) WARNX("Error of correction!");
while((t = Mount.timeFromStart()) - tlast < Config->PIDRefreshDt) usleep(500);
tlast = t; tlast = t;
} }
WARNX("No next traectory point or emulation ends"); WARNX("No next traectory point or emulation ends");
@@ -151,7 +151,7 @@ int main(int argc, char **argv){
if(!(fcoords = fopen(G.coordsoutput, "w"))) if(!(fcoords = fopen(G.coordsoutput, "w")))
ERRX("Can't open %s", G.coordsoutput); ERRX("Can't open %s", G.coordsoutput);
}else fcoords = stdout; }else fcoords = stdout;
conf_t *Config = readServoConf(G.conffile); Config = readServoConf(G.conffile);
if(!Config || G.dumpconf){ if(!Config || G.dumpconf){
dumpConf(); dumpConf();
return 1; return 1;

View File

@@ -1,4 +1,4 @@
Current configuration: # Current configuration
MountDevPath=/dev/ttyUSB0 MountDevPath=/dev/ttyUSB0
MountDevSpeed=19200 MountDevSpeed=19200
EncoderDevPath=(null) EncoderDevPath=(null)

View File

@@ -41,7 +41,7 @@ int init_traectory(traectory_fn f, coordpair_t *XY0){
if(!f || !XY0) return FALSE; if(!f || !XY0) return FALSE;
cur_traectory = f; cur_traectory = f;
XYstart = *XY0; XYstart = *XY0;
tstart = Mount.currentT(); tstart = Mount.timeFromStart();
mountdata_t mdata; mountdata_t mdata;
int ntries = 0; int ntries = 0;
for(; ntries < 10; ++ntries){ for(; ntries < 10; ++ntries){
@@ -76,6 +76,7 @@ int telpos(coordval_pair_t *curpos){
} }
if(ntries == 10) return FALSE; if(ntries == 10) return FALSE;
coordval_pair_t pt; coordval_pair_t pt;
//DBG("\n\nTELPOS: %g'/%g' measured @ %.6f", RAD2AMIN(mdata.encXposition.val), RAD2AMIN(mdata.encYposition.val), mdata.encXposition.t);
pt.X.val = mdata.encXposition.val; pt.X.val = mdata.encXposition.val;
pt.Y.val = mdata.encYposition.val; pt.Y.val = mdata.encYposition.val;
pt.X.t = mdata.encXposition.t; pt.X.t = mdata.encXposition.t;

View File

@@ -1,10 +1,10 @@
<?xml version="1.0" encoding="UTF-8"?> <?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE QtCreatorProject> <!DOCTYPE QtCreatorProject>
<!-- Written by QtCreator 17.0.0, 2025-07-30T17:30:52. --> <!-- Written by QtCreator 18.0.1, 2026-01-26T22:24:32. -->
<qtcreator> <qtcreator>
<data> <data>
<variable>EnvironmentId</variable> <variable>EnvironmentId</variable>
<value type="QByteArray">{cf63021e-ef53-49b0-b03b-2f2570cdf3b6}</value> <value type="QByteArray">{7bd84e39-ca37-46d3-be9d-99ebea85bc0d}</value>
</data> </data>
<data> <data>
<variable>ProjectExplorer.Project.ActiveTarget</variable> <variable>ProjectExplorer.Project.ActiveTarget</variable>
@@ -40,9 +40,9 @@
<value type="int" key="EditorConfiguration.PaddingMode">1</value> <value type="int" key="EditorConfiguration.PaddingMode">1</value>
<value type="int" key="EditorConfiguration.PreferAfterWhitespaceComments">0</value> <value type="int" key="EditorConfiguration.PreferAfterWhitespaceComments">0</value>
<value type="bool" key="EditorConfiguration.PreferSingleLineComments">false</value> <value type="bool" key="EditorConfiguration.PreferSingleLineComments">false</value>
<value type="bool" key="EditorConfiguration.ScrollWheelZooming">false</value> <value type="bool" key="EditorConfiguration.ScrollWheelZooming">true</value>
<value type="bool" key="EditorConfiguration.ShowMargin">false</value> <value type="bool" key="EditorConfiguration.ShowMargin">false</value>
<value type="int" key="EditorConfiguration.SmartBackspaceBehavior">1</value> <value type="int" key="EditorConfiguration.SmartBackspaceBehavior">0</value>
<value type="bool" key="EditorConfiguration.SmartSelectionChanging">true</value> <value type="bool" key="EditorConfiguration.SmartSelectionChanging">true</value>
<value type="bool" key="EditorConfiguration.SpacesForTabs">true</value> <value type="bool" key="EditorConfiguration.SpacesForTabs">true</value>
<value type="int" key="EditorConfiguration.TabKeyBehavior">0</value> <value type="int" key="EditorConfiguration.TabKeyBehavior">0</value>
@@ -51,10 +51,10 @@
<value type="bool" key="EditorConfiguration.UseIndenter">false</value> <value type="bool" key="EditorConfiguration.UseIndenter">false</value>
<value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value> <value type="int" key="EditorConfiguration.Utf8BomBehavior">1</value>
<value type="bool" key="EditorConfiguration.addFinalNewLine">true</value> <value type="bool" key="EditorConfiguration.addFinalNewLine">true</value>
<value type="bool" key="EditorConfiguration.cleanIndentation">true</value> <value type="bool" key="EditorConfiguration.cleanIndentation">false</value>
<value type="bool" key="EditorConfiguration.cleanWhitespace">true</value> <value type="bool" key="EditorConfiguration.cleanWhitespace">true</value>
<value type="QString" key="EditorConfiguration.ignoreFileTypes">*.md, *.MD, Makefile</value> <value type="QString" key="EditorConfiguration.ignoreFileTypes">*.md, *.MD, Makefile</value>
<value type="bool" key="EditorConfiguration.inEntireDocument">true</value> <value type="bool" key="EditorConfiguration.inEntireDocument">false</value>
<value type="bool" key="EditorConfiguration.skipTrailingWhitespace">true</value> <value type="bool" key="EditorConfiguration.skipTrailingWhitespace">true</value>
<value type="bool" key="EditorConfiguration.tintMarginArea">true</value> <value type="bool" key="EditorConfiguration.tintMarginArea">true</value>
</valuemap> </valuemap>
@@ -79,13 +79,14 @@
<value type="bool" key="ClangTools.AnalyzeOpenFiles">true</value> <value type="bool" key="ClangTools.AnalyzeOpenFiles">true</value>
<value type="bool" key="ClangTools.BuildBeforeAnalysis">true</value> <value type="bool" key="ClangTools.BuildBeforeAnalysis">true</value>
<value type="QString" key="ClangTools.DiagnosticConfig">Builtin.DefaultTidyAndClazy</value> <value type="QString" key="ClangTools.DiagnosticConfig">Builtin.DefaultTidyAndClazy</value>
<value type="int" key="ClangTools.ParallelJobs">4</value> <value type="int" key="ClangTools.ParallelJobs">8</value>
<value type="bool" key="ClangTools.PreferConfigFile">true</value> <value type="bool" key="ClangTools.PreferConfigFile">true</value>
<valuelist type="QVariantList" key="ClangTools.SelectedDirs"/> <valuelist type="QVariantList" key="ClangTools.SelectedDirs"/>
<valuelist type="QVariantList" key="ClangTools.SelectedFiles"/> <valuelist type="QVariantList" key="ClangTools.SelectedFiles"/>
<valuelist type="QVariantList" key="ClangTools.SuppressedDiagnostics"/> <valuelist type="QVariantList" key="ClangTools.SuppressedDiagnostics"/>
<value type="bool" key="ClangTools.UseGlobalSettings">true</value> <value type="bool" key="ClangTools.UseGlobalSettings">true</value>
</valuemap> </valuemap>
<value type="int" key="RcSync">0</value>
</valuemap> </valuemap>
</data> </data>
<data> <data>
@@ -95,12 +96,12 @@
<value type="bool" key="HasPerBcDcs">true</value> <value type="bool" key="HasPerBcDcs">true</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{91347f2c-5221-46a7-80b1-0a054ca02f79}</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{65a14f9e-e008-4c1b-89df-4eaa4774b6e3}</value>
<value type="qlonglong" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value> <value type="qlonglong" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value>
<value type="qlonglong" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value> <value type="qlonglong" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
<value type="qlonglong" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value> <value type="qlonglong" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0"> <valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0">
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/home/eddy/Docs/SAO/10micron/C-sources/erfa_functions</value> <value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/tmp/robo5/mountcontrol.git/LibSidServo</value>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0"> <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0"> <valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0">
<valuelist type="QVariantList" key="GenericProjectManager.GenericMakeStep.BuildTargets"> <valuelist type="QVariantList" key="GenericProjectManager.GenericMakeStep.BuildTargets">
@@ -110,8 +111,8 @@
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericMakeStep</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericMakeStep</value>
</valuemap> </valuemap>
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">1</value> <value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Сборка</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Сборка</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Build</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Build</value>
</valuemap> </valuemap>
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1"> <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.1">
@@ -123,8 +124,8 @@
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericMakeStep</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericMakeStep</value>
</valuemap> </valuemap>
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">1</value> <value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">1</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Очистка</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Очистка</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Clean</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Clean</value>
</valuemap> </valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value> <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">2</value>
@@ -132,15 +133,15 @@
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.CustomParsers"/> <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.CustomParsers"/>
<value type="bool" key="ProjectExplorer.BuildConfiguration.ParseStandardOutput">false</value> <value type="bool" key="ProjectExplorer.BuildConfiguration.ParseStandardOutput">false</value>
<valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/> <valuelist type="QVariantList" key="ProjectExplorer.BuildConfiguration.UserEnvironmentChanges"/>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">По умолчанию</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Default</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericBuildConfiguration</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">GenericProjectManager.GenericBuildConfiguration</value>
<value type="qlonglong" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value> <value type="qlonglong" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value>
<value type="qlonglong" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value> <value type="qlonglong" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value>
<valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0"> <valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0"> <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">0</value> <value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Развёртывание</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Развёртывание</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Deploy</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
</valuemap> </valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value> <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
@@ -164,8 +165,10 @@
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.CustomExecutableRunConfiguration</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.CustomExecutableRunConfiguration</value>
<value type="QString" key="ProjectExplorer.RunConfiguration.BuildKey"></value> <value type="QString" key="ProjectExplorer.RunConfiguration.BuildKey"></value>
<value type="bool" key="ProjectExplorer.RunConfiguration.Customized">false</value> <value type="bool" key="ProjectExplorer.RunConfiguration.Customized">false</value>
<value type="QString" key="ProjectExplorer.RunConfiguration.UniqueId"></value>
<value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value> <value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
<value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value> <value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
<value type="QString" key="RunConfiguration.WorkingDirectory.default">%{RunConfig:Executable:Path}</value>
</valuemap> </valuemap>
<value type="qlonglong" key="ProjectExplorer.Target.RunConfigurationCount">1</value> <value type="qlonglong" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
</valuemap> </valuemap>
@@ -173,8 +176,8 @@
<valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0"> <valuemap type="QVariantMap" key="ProjectExplorer.Target.DeployConfiguration.0">
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0"> <valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0">
<value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">0</value> <value type="qlonglong" key="ProjectExplorer.BuildStepList.StepsCount">0</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Развёртывание</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Deploy</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Развёртывание</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Deploy</value>
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.BuildSteps.Deploy</value>
</valuemap> </valuemap>
<value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value> <value type="int" key="ProjectExplorer.BuildConfiguration.BuildStepListCount">1</value>
@@ -198,8 +201,10 @@
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.CustomExecutableRunConfiguration</value> <value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">ProjectExplorer.CustomExecutableRunConfiguration</value>
<value type="QString" key="ProjectExplorer.RunConfiguration.BuildKey"></value> <value type="QString" key="ProjectExplorer.RunConfiguration.BuildKey"></value>
<value type="bool" key="ProjectExplorer.RunConfiguration.Customized">false</value> <value type="bool" key="ProjectExplorer.RunConfiguration.Customized">false</value>
<value type="QString" key="ProjectExplorer.RunConfiguration.UniqueId"></value>
<value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value> <value type="bool" key="RunConfiguration.UseCppDebuggerAuto">true</value>
<value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value> <value type="bool" key="RunConfiguration.UseQmlDebuggerAuto">true</value>
<value type="QString" key="RunConfiguration.WorkingDirectory.default">%{RunConfig:Executable:Path}</value>
</valuemap> </valuemap>
<value type="qlonglong" key="ProjectExplorer.Target.RunConfigurationCount">1</value> <value type="qlonglong" key="ProjectExplorer.Target.RunConfigurationCount">1</value>
</valuemap> </valuemap>
@@ -208,10 +213,6 @@
<variable>ProjectExplorer.Project.TargetCount</variable> <variable>ProjectExplorer.Project.TargetCount</variable>
<value type="qlonglong">1</value> <value type="qlonglong">1</value>
</data> </data>
<data>
<variable>ProjectExplorer.Project.Updater.FileVersion</variable>
<value type="int">22</value>
</data>
<data> <data>
<variable>Version</variable> <variable>Version</variable>
<value type="int">22</value> <value type="int">22</value>

View File

@@ -22,6 +22,7 @@ examples/traectories.h
main.h main.h
movingmodel.c movingmodel.c
movingmodel.h movingmodel.h
polltest/main.c
ramp.c ramp.c
ramp.h ramp.h
serial.h serial.h

View File

@@ -25,6 +25,7 @@
#include <time.h> #include <time.h>
#include <stdio.h> #include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
#include <unistd.h>
#include "main.h" #include "main.h"
#include "movingmodel.h" #include "movingmodel.h"
@@ -32,40 +33,82 @@
#include "ssii.h" #include "ssii.h"
#include "PID.h" #include "PID.h"
// adder for monotonic time by realtime: inited any call of init()
static struct timespec timeadder = {0}, // adder of CLOCK_REALTIME to CLOCK_MONOTONIC
t0 = {0}, // curtime() for initstarttime() call
starttime = {0}; // starting time by monotonic (for timefromstart())
conf_t Conf = {0}; conf_t Conf = {0};
// parameters for model // parameters for model
static movemodel_t *Xmodel, *Ymodel; static movemodel_t *Xmodel, *Ymodel;
// limits for model and/or real mount (in latter case data should be read from mount on init)
// radians, rad/sec, rad/sec^2 // radians, rad/sec, rad/sec^2
static limits_t // max speeds (rad/s): xs=10 deg/s, ys=8 deg/s
// accelerations: xa=12.6 deg/s^2, ya= 9.5 deg/s^2
limits_t
Xlimits = { Xlimits = {
.min = {.coord = -3.1241, .speed = 1e-10, .accel = 1e-6}, .min = {.coord = -3.1241, .speed = 1e-10, .accel = 1e-6},
.max = {.coord = 3.1241, .speed = MCC_MAX_X_SPEED, .accel = MCC_X_ACCELERATION}}, .max = {.coord = 3.1241, .speed = 0.174533, .accel = 0.219911}},
Ylimits = { Ylimits = {
.min = {.coord = -3.1241, .speed = 1e-10, .accel = 1e-6}, .min = {.coord = -3.1241, .speed = 1e-10, .accel = 1e-6},
.max = {.coord = 3.1241, .speed = MCC_MAX_Y_SPEED, .accel = MCC_Y_ACCELERATION}} .max = {.coord = 3.1241, .speed = 0.139626, .accel = 0.165806}}
; ;
static mcc_errcodes_t shortcmd(short_command_t *cmd); static mcc_errcodes_t shortcmd(short_command_t *cmd);
static mcc_errcodes_t get_hwconf(hardware_configuration_t *hwConfig);
/** /**
* @brief nanotime - monotonic time from first run * @brief curtime - monotonic time from first run
* @return time in seconds * @param t - struct timespec by CLOCK_MONOTONIC but with setpoint by CLOCK_REALTIME on observations start
* @return TRUE if all OK
* FIXME: double -> struct timespec; on init: init t0 by CLOCK_REALTIME
*/ */
double nanotime(){ int curtime(struct timespec *t){
static struct timespec *start = NULL;
struct timespec now; struct timespec now;
if(!start){ if(clock_gettime(CLOCK_MONOTONIC, &now)) return FALSE;
start = malloc(sizeof(struct timespec)); now.tv_sec += timeadder.tv_sec;
if(!start) return -1.; now.tv_nsec += timeadder.tv_nsec;
if(clock_gettime(CLOCK_MONOTONIC, start)) return -1.; if(now.tv_nsec > 999999999L){
++now.tv_sec;
now.tv_nsec -= 1000000000L;
} }
if(t) *t = now;
return TRUE;
}
// init starttime; @return TRUE if all OK
static int initstarttime(){
struct timespec start;
if(clock_gettime(CLOCK_MONOTONIC, &starttime)) return FALSE;
if(clock_gettime(CLOCK_REALTIME, &start)) return FALSE;
timeadder.tv_sec = start.tv_sec - starttime.tv_sec;
timeadder.tv_nsec = start.tv_nsec - starttime.tv_nsec;
if(timeadder.tv_nsec < 0){
--timeadder.tv_sec;
timeadder.tv_nsec += 1000000000L;
}
curtime(&t0);
return TRUE;
}
// return difference (in seconds) between time1 and time0
double timediff(const struct timespec *time1, const struct timespec *time0){
if(!time1 || !time0) return -1.;
return (time1->tv_sec - time0->tv_sec) + (time1->tv_nsec - time0->tv_nsec) / 1e9;
}
// difference between given time and last initstarttime() call
double timediff0(const struct timespec *time1){
return timediff(time1, &t0);
}
// time from last initstarttime() call
double timefromstart(){
struct timespec now;
if(clock_gettime(CLOCK_MONOTONIC, &now)) return -1.; if(clock_gettime(CLOCK_MONOTONIC, &now)) return -1.;
double nd = ((double)now.tv_nsec - (double)start->tv_nsec) * 1e-9; return (now.tv_sec - starttime.tv_sec) + (now.tv_nsec - starttime.tv_nsec) / 1e9;
double sd = (double)now.tv_sec - (double)start->tv_sec;
return sd + nd;
} }
/** /**
* @brief quit - close all opened and return to default state * @brief quit - close all opened and return to default state
* TODO: close serial devices even in "model" mode
*/ */
static void quit(){ static void quit(){
if(Conf.RunModel) return; if(Conf.RunModel) return;
@@ -75,25 +118,19 @@ static void quit(){
DBG("Exit"); DBG("Exit");
} }
void getModData(mountdata_t *mountdata){ void getModData(coordpair_t *c, movestate_t *xst, movestate_t *yst){
if(!mountdata || !Xmodel || !Ymodel) return; if(!c || !Xmodel || !Ymodel) return;
static double oldmt = -100.; // old `millis measurement` time double tnow = timefromstart();
static uint32_t oldmillis = 0;
double tnow = nanotime();
moveparam_t Xp, Yp; moveparam_t Xp, Yp;
movestate_t Xst = Xmodel->get_state(Xmodel, &Xp); movestate_t Xst = Xmodel->get_state(Xmodel, &Xp);
//DBG("Xstate = %d", Xst); //DBG("Xstate = %d", Xst);
if(Xst == ST_MOVE) Xst = Xmodel->proc_move(Xmodel, &Xp, tnow); if(Xst == ST_MOVE) Xst = Xmodel->proc_move(Xmodel, &Xp, tnow);
movestate_t Yst = Ymodel->get_state(Ymodel, &Yp); movestate_t Yst = Ymodel->get_state(Ymodel, &Yp);
if(Yst == ST_MOVE) Yst = Ymodel->proc_move(Ymodel, &Yp, tnow); if(Yst == ST_MOVE) Yst = Ymodel->proc_move(Ymodel, &Yp, tnow);
mountdata->motXposition.t = mountdata->encXposition.t = mountdata->motYposition.t = mountdata->encYposition.t = tnow; c->X = Xp.coord;
mountdata->motXposition.val = mountdata->encXposition.val = Xp.coord; c->Y = Yp.coord;
mountdata->motYposition.val = mountdata->encYposition.val = Yp.coord; if(xst) *xst = Xst;
getXspeed(); getYspeed(); if(yst) *yst = Yst;
if(tnow - oldmt > Conf.MountReqInterval){
oldmillis = mountdata->millis = (uint32_t)(tnow * 1e3);
oldmt = tnow;
}else mountdata->millis = oldmillis;
} }
/** /**
@@ -142,7 +179,6 @@ double LS_calc_slope(less_square_t *l, double x, double t){
return (numerator / denominator); return (numerator / denominator);
} }
/** /**
* @brief init - open serial devices and do other job * @brief init - open serial devices and do other job
* @param c - initial configuration * @param c - initial configuration
@@ -151,15 +187,20 @@ double LS_calc_slope(less_square_t *l, double x, double t){
static mcc_errcodes_t init(conf_t *c){ static mcc_errcodes_t init(conf_t *c){
FNAME(); FNAME();
if(!c) return MCC_E_BADFORMAT; if(!c) return MCC_E_BADFORMAT;
if(!initstarttime()) return MCC_E_FAILED;
Conf = *c; Conf = *c;
mcc_errcodes_t ret = MCC_E_OK; mcc_errcodes_t ret = MCC_E_OK;
Xmodel = model_init(&Xlimits); Xmodel = model_init(&Xlimits);
Ymodel = model_init(&Ylimits); Ymodel = model_init(&Ylimits);
if(Conf.MountReqInterval > 1. || Conf.MountReqInterval < 0.05){
DBG("Bad value of MountReqInterval");
ret = MCC_E_BADFORMAT;
}
if(Conf.RunModel){ if(Conf.RunModel){
if(!Xmodel || !Ymodel || !openMount()) return MCC_E_FAILED; if(!Xmodel || !Ymodel || !openMount()) return MCC_E_FAILED;
return MCC_E_OK; return MCC_E_OK;
} }
if(!Conf.MountDevPath || Conf.MountDevSpeed < 1200){ if(!Conf.MountDevPath || Conf.MountDevSpeed < MOUNT_BAUDRATE_MIN){
DBG("Define mount device path and speed"); DBG("Define mount device path and speed");
ret = MCC_E_BADFORMAT; ret = MCC_E_BADFORMAT;
}else if(!openMount()){ }else if(!openMount()){
@@ -175,41 +216,47 @@ static mcc_errcodes_t init(conf_t *c){
ret = MCC_E_ENCODERDEV; ret = MCC_E_ENCODERDEV;
} }
} }
if(Conf.MountReqInterval > 1. || Conf.MountReqInterval < 0.05){ // TODO: read hardware configuration on init
DBG("Bad value of MountReqInterval");
ret = MCC_E_BADFORMAT;
}
if(Conf.EncoderSpeedInterval < Conf.EncoderReqInterval * MCC_CONF_MIN_SPEEDC || Conf.EncoderSpeedInterval > MCC_CONF_MAX_SPEEDINT){ if(Conf.EncoderSpeedInterval < Conf.EncoderReqInterval * MCC_CONF_MIN_SPEEDC || Conf.EncoderSpeedInterval > MCC_CONF_MAX_SPEEDINT){
DBG("Wrong speed interval"); DBG("Wrong speed interval");
ret = MCC_E_BADFORMAT; ret = MCC_E_BADFORMAT;
} }
//uint8_t buf[1024];
//data_t d = {.buf = buf, .len = 0, .maxlen = 1024};
if(!SSrawcmd(CMD_EXITACM, NULL)) ret = MCC_E_FAILED; if(!SSrawcmd(CMD_EXITACM, NULL)) ret = MCC_E_FAILED;
if(ret != MCC_E_OK) return ret; if(ret != MCC_E_OK) return ret;
return updateMotorPos(); // read HW config to update constants
hardware_configuration_t HW;
if(MCC_E_OK != get_hwconf(&HW)) return MCC_E_FAILED;
// make a pause for actual encoder's values
double t0 = timefromstart();
while(timefromstart() - t0 < Conf.EncoderReqInterval) usleep(1000);
mcc_errcodes_t e = updateMotorPos();
// and refresh data after updating
DBG("Wait for next mount reading");
t0 = timefromstart();
while(timefromstart() - t0 < Conf.MountReqInterval * 3.) usleep(1000);
return e;
} }
// check coordinates (rad) and speeds (rad/s); return FALSE if failed // check coordinates (rad) and speeds (rad/s); return FALSE if failed
// TODO fix to real limits!!! // TODO fix to real limits!!!
static int chkX(double X){ static int chkX(double X){
if(X > 2.*M_PI || X < -2.*M_PI) return FALSE; if(X > Xlimits.max.coord || X < Xlimits.min.coord) return FALSE;
return TRUE; return TRUE;
} }
static int chkY(double Y){ static int chkY(double Y){
if(Y > 2.*M_PI || Y < -2.*M_PI) return FALSE; if(Y > Ylimits.max.coord || Y < Ylimits.min.coord) return FALSE;
return TRUE; return TRUE;
} }
static int chkXs(double s){ static int chkXs(double s){
if(s < 0. || s > MCC_MAX_X_SPEED) return FALSE; if(s < Xlimits.min.speed || s > Xlimits.max.speed) return FALSE;
return TRUE; return TRUE;
} }
static int chkYs(double s){ static int chkYs(double s){
if(s < 0. || s > MCC_MAX_Y_SPEED) return FALSE; if(s < Ylimits.min.speed || s > Ylimits.max.speed) return FALSE;
return TRUE; return TRUE;
} }
// set SLEWING state if axis was stopped later // set SLEWING state if axis was stopped
static void setslewingstate(){ static void setslewingstate(){
//FNAME(); //FNAME();
mountdata_t d; mountdata_t d;
@@ -225,19 +272,6 @@ static void setslewingstate(){
}else DBG("CAN't GET MOUNT DATA!"); }else DBG("CAN't GET MOUNT DATA!");
} }
/*
static mcc_errcodes_t slew2(const coordpair_t *target, slewflags_t flags){
(void)target;
(void)flags;
//if(Conf.RunModel) return ... ;
if(MCC_E_OK != updateMotorPos()) return MCC_E_FAILED;
//...
setStat(AXIS_SLEWING, AXIS_SLEWING);
//...
return MCC_E_FAILED;
}
*/
/** /**
* @brief move2 - simple move to given point and stop * @brief move2 - simple move to given point and stop
* @param X - new X coordinate (radians: -pi..pi) or NULL * @param X - new X coordinate (radians: -pi..pi) or NULL
@@ -252,12 +286,13 @@ static mcc_errcodes_t move2(const coordpair_t *target){
DBG("x,y: %g, %g", target->X, target->Y); DBG("x,y: %g, %g", target->X, target->Y);
cmd.Xmot = target->X; cmd.Xmot = target->X;
cmd.Ymot = target->Y; cmd.Ymot = target->Y;
cmd.Xspeed = MCC_MAX_X_SPEED; cmd.Xspeed = Xlimits.max.speed;
cmd.Yspeed = MCC_MAX_Y_SPEED; cmd.Yspeed = Ylimits.max.speed;
mcc_errcodes_t r = shortcmd(&cmd); /*mcc_errcodes_t r = shortcmd(&cmd);
if(r != MCC_E_OK) return r; if(r != MCC_E_OK) return r;
setslewingstate(); setslewingstate();
return MCC_E_OK; return MCC_E_OK;*/
return shortcmd(&cmd);
} }
/** /**
@@ -286,6 +321,7 @@ static mcc_errcodes_t move2s(const coordpair_t *target, const coordpair_t *speed
if(!target || !speed) return MCC_E_BADFORMAT; if(!target || !speed) return MCC_E_BADFORMAT;
if(!chkX(target->X) || !chkY(target->Y)) return MCC_E_BADFORMAT; if(!chkX(target->X) || !chkY(target->Y)) return MCC_E_BADFORMAT;
if(!chkXs(speed->X) || !chkYs(speed->Y)) return MCC_E_BADFORMAT; if(!chkXs(speed->X) || !chkYs(speed->Y)) return MCC_E_BADFORMAT;
// updateMotorPos() here can make a problem; TODO: remove?
if(MCC_E_OK != updateMotorPos()) return MCC_E_FAILED; if(MCC_E_OK != updateMotorPos()) return MCC_E_FAILED;
short_command_t cmd = {0}; short_command_t cmd = {0};
cmd.Xmot = target->X; cmd.Xmot = target->X;
@@ -305,7 +341,7 @@ static mcc_errcodes_t move2s(const coordpair_t *target, const coordpair_t *speed
static mcc_errcodes_t emstop(){ static mcc_errcodes_t emstop(){
FNAME(); FNAME();
if(Conf.RunModel){ if(Conf.RunModel){
double curt = nanotime(); double curt = timefromstart();
Xmodel->emergency_stop(Xmodel, curt); Xmodel->emergency_stop(Xmodel, curt);
Ymodel->emergency_stop(Ymodel, curt); Ymodel->emergency_stop(Ymodel, curt);
return MCC_E_OK; return MCC_E_OK;
@@ -317,7 +353,7 @@ static mcc_errcodes_t emstop(){
static mcc_errcodes_t stop(){ static mcc_errcodes_t stop(){
FNAME(); FNAME();
if(Conf.RunModel){ if(Conf.RunModel){
double curt = nanotime(); double curt = timefromstart();
Xmodel->stop(Xmodel, curt); Xmodel->stop(Xmodel, curt);
Ymodel->stop(Ymodel,curt); Ymodel->stop(Ymodel,curt);
return MCC_E_OK; return MCC_E_OK;
@@ -334,7 +370,7 @@ static mcc_errcodes_t stop(){
static mcc_errcodes_t shortcmd(short_command_t *cmd){ static mcc_errcodes_t shortcmd(short_command_t *cmd){
if(!cmd) return MCC_E_BADFORMAT; if(!cmd) return MCC_E_BADFORMAT;
if(Conf.RunModel){ if(Conf.RunModel){
double curt = nanotime(); double curt = timefromstart();
moveparam_t param = {0}; moveparam_t param = {0};
param.coord = cmd->Xmot; param.speed = cmd->Xspeed; param.coord = cmd->Xmot; param.speed = cmd->Xspeed;
if(!model_move2(Xmodel, &param, curt)) return MCC_E_FAILED; if(!model_move2(Xmodel, &param, curt)) return MCC_E_FAILED;
@@ -366,7 +402,7 @@ static mcc_errcodes_t shortcmd(short_command_t *cmd){
static mcc_errcodes_t longcmd(long_command_t *cmd){ static mcc_errcodes_t longcmd(long_command_t *cmd){
if(!cmd) return MCC_E_BADFORMAT; if(!cmd) return MCC_E_BADFORMAT;
if(Conf.RunModel){ if(Conf.RunModel){
double curt = nanotime(); double curt = timefromstart();
moveparam_t param = {0}; moveparam_t param = {0};
param.coord = cmd->Xmot; param.speed = cmd->Xspeed; param.coord = cmd->Xmot; param.speed = cmd->Xspeed;
if(!model_move2(Xmodel, &param, curt)) return MCC_E_FAILED; if(!model_move2(Xmodel, &param, curt)) return MCC_E_FAILED;
@@ -393,6 +429,7 @@ static mcc_errcodes_t get_hwconf(hardware_configuration_t *hwConfig){
if(!hwConfig) return MCC_E_BADFORMAT; if(!hwConfig) return MCC_E_BADFORMAT;
if(Conf.RunModel) return MCC_E_FAILED; if(Conf.RunModel) return MCC_E_FAILED;
SSconfig config; SSconfig config;
DBG("Read HW configuration");
if(!cmdC(&config, FALSE)) return MCC_E_FAILED; if(!cmdC(&config, FALSE)) return MCC_E_FAILED;
// Convert acceleration (ticks per loop^2 to rad/s^2) // Convert acceleration (ticks per loop^2 to rad/s^2)
hwConfig->Xconf.accel = X_MOTACC2RS(config.Xconf.accel); hwConfig->Xconf.accel = X_MOTACC2RS(config.Xconf.accel);
@@ -432,8 +469,8 @@ static mcc_errcodes_t get_hwconf(hardware_configuration_t *hwConfig){
// Copy ticks per revolution // Copy ticks per revolution
hwConfig->Xsetpr = __bswap_32(config.Xsetpr); hwConfig->Xsetpr = __bswap_32(config.Xsetpr);
hwConfig->Ysetpr = __bswap_32(config.Ysetpr); hwConfig->Ysetpr = __bswap_32(config.Ysetpr);
hwConfig->Xmetpr = __bswap_32(config.Xmetpr) / 4; // as documentation said, real ticks are 4 times less hwConfig->Xmetpr = __bswap_32(config.Xmetpr); // as documentation said, real ticks are 4 times less
hwConfig->Ymetpr = __bswap_32(config.Ymetpr) / 4; hwConfig->Ymetpr = __bswap_32(config.Ymetpr);
// Convert slew rates (ticks per loop to rad/s) // Convert slew rates (ticks per loop to rad/s)
hwConfig->Xslewrate = X_MOTSPD2RS(config.Xslewrate); hwConfig->Xslewrate = X_MOTSPD2RS(config.Xslewrate);
hwConfig->Yslewrate = Y_MOTSPD2RS(config.Yslewrate); hwConfig->Yslewrate = Y_MOTSPD2RS(config.Yslewrate);
@@ -451,6 +488,30 @@ static mcc_errcodes_t get_hwconf(hardware_configuration_t *hwConfig){
hwConfig->locsspeed = (double)config.locsspeed * M_PI / (180.0 * 3600.0); hwConfig->locsspeed = (double)config.locsspeed * M_PI / (180.0 * 3600.0);
// Convert backlash speed (ticks per loop to rad/s) // Convert backlash speed (ticks per loop to rad/s)
hwConfig->backlspd = X_MOTSPD2RS(config.backlspd); hwConfig->backlspd = X_MOTSPD2RS(config.backlspd);
// now read text commands
int64_t i64;
double Xticks, Yticks;
DBG("SERIAL");
// motor's encoder ticks per rev
if(!SSgetint(CMD_MEPRX, &i64)) return MCC_E_FAILED;
Xticks = ((double) i64); // divide by 4 as these values stored ???
if(!SSgetint(CMD_MEPRY, &i64)) return MCC_E_FAILED;
Yticks = ((double) i64);
X_ENC_ZERO = Conf.XEncZero;
Y_ENC_ZERO = Conf.YEncZero;
DBG("xyrev: %d/%d", config.xbits.motrev, config.ybits.motrev);
X_MOT_STEPSPERREV = hwConfig->Xconf.motor_stepsperrev = Xticks; // (config.xbits.motrev) ? -Xticks : Xticks;
Y_MOT_STEPSPERREV = hwConfig->Yconf.motor_stepsperrev = Yticks; //(config.ybits.motrev) ? -Yticks : Yticks;
DBG("zero: %d/%d; motsteps: %.10g/%.10g", X_ENC_ZERO, Y_ENC_ZERO, X_MOT_STEPSPERREV, Y_MOT_STEPSPERREV);
// axis encoder ticks per rev
if(!SSgetint(CMD_AEPRX, &i64)) return MCC_E_FAILED;
Xticks = (double) i64;
if(!SSgetint(CMD_AEPRY, &i64)) return MCC_E_FAILED;
Yticks = (double) i64;
DBG("xyencrev: %d/%d", config.xbits.encrev, config.ybits.encrev);
X_ENC_STEPSPERREV = hwConfig->Xconf.axis_stepsperrev = (config.xbits.encrev) ? -Xticks : Xticks;
Y_ENC_STEPSPERREV = hwConfig->Yconf.axis_stepsperrev = (config.ybits.encrev) ? -Yticks : Yticks;
DBG("encsteps: %.10g/%.10g", X_ENC_STEPSPERREV, Y_ENC_STEPSPERREV);
return MCC_E_OK; return MCC_E_OK;
} }
@@ -506,17 +567,37 @@ static mcc_errcodes_t write_hwconf(hardware_configuration_t *hwConfig){
config.Ysetpr = __bswap_32(hwConfig->Ysetpr); config.Ysetpr = __bswap_32(hwConfig->Ysetpr);
config.Xmetpr = __bswap_32(hwConfig->Xmetpr); config.Xmetpr = __bswap_32(hwConfig->Xmetpr);
config.Ymetpr = __bswap_32(hwConfig->Ymetpr); config.Ymetpr = __bswap_32(hwConfig->Ymetpr);
// todo - also write text params
// TODO - next // TODO - next
(void) config; (void) config;
return MCC_E_OK; return MCC_E_OK;
} }
// getters of max/min speed and acceleration
mcc_errcodes_t maxspeed(coordpair_t *v){
if(!v) return MCC_E_BADFORMAT;
v->X = Xlimits.max.speed;
v->Y = Ylimits.max.speed;
return MCC_E_OK;
}
mcc_errcodes_t minspeed(coordpair_t *v){
if(!v) return MCC_E_BADFORMAT;
v->X = Xlimits.min.speed;
v->Y = Ylimits.min.speed;
return MCC_E_OK;
}
mcc_errcodes_t acceleration(coordpair_t *a){
if(!a) return MCC_E_BADFORMAT;
a->X = Xlimits.max.accel;
a->Y = Ylimits.max.accel;
return MCC_E_OK;
}
// init mount class // init mount class
mount_t Mount = { mount_t Mount = {
.init = init, .init = init,
.quit = quit, .quit = quit,
.getMountData = getMD, .getMountData = getMD,
// .slewTo = slew2,
.moveTo = move2, .moveTo = move2,
.moveWspeed = move2s, .moveWspeed = move2s,
.setSpeed = setspeed, .setSpeed = setspeed,
@@ -526,7 +607,13 @@ mount_t Mount = {
.longCmd = longcmd, .longCmd = longcmd,
.getHWconfig = get_hwconf, .getHWconfig = get_hwconf,
.saveHWconfig = write_hwconf, .saveHWconfig = write_hwconf,
.currentT = nanotime, .currentT = curtime,
.timeFromStart = timefromstart,
.timeDiff = timediff,
.timeDiff0 = timediff0,
.correctTo = correct2, .correctTo = correct2,
.getMaxSpeed = maxspeed,
.getMinSpeed = minspeed,
.getAcceleration = acceleration,
}; };

View File

@@ -24,11 +24,16 @@
#include <stdlib.h> #include <stdlib.h>
#include "movingmodel.h"
#include "sidservo.h" #include "sidservo.h"
extern conf_t Conf; extern conf_t Conf;
double nanotime(); extern limits_t Xlimits, Ylimits;
void getModData(mountdata_t *mountdata); int curtime(struct timespec *t);
double timediff(const struct timespec *time1, const struct timespec *time0);
double timediff0(const struct timespec *time1);
double timefromstart();
void getModData(coordpair_t *c, movestate_t *xst, movestate_t *yst);
typedef struct{ typedef struct{
double *x, *t, *t2, *xt; // arrays of coord/time and multiply double *x, *t, *t2, *xt; // arrays of coord/time and multiply
double xsum, tsum, t2sum, xtsum; // sums of coord/time and their multiply double xsum, tsum, t2sum, xtsum; // sums of coord/time and their multiply
@@ -42,10 +47,6 @@ double LS_calc_slope(less_square_t *l, double x, double t);
// unused arguments of functions // unused arguments of functions
#define _U_ __attribute__((__unused__)) #define _U_ __attribute__((__unused__))
// break absent in `case`
#define FALLTHRU __attribute__ ((fallthrough))
// and synonym for FALLTHRU
#define NOBREAKHERE __attribute__ ((fallthrough))
// weak functions // weak functions
#define WEAK __attribute__ ((weak)) #define WEAK __attribute__ ((weak))

View File

@@ -60,9 +60,14 @@ movemodel_t *model_init(limits_t *l){
int model_move2(movemodel_t *model, moveparam_t *target, double t){ int model_move2(movemodel_t *model, moveparam_t *target, double t){
if(!target || !model) return FALSE; if(!target || !model) return FALSE;
DBG("MOVE to %g at speed %g", target->coord, target->speed); DBG("MOVE to %g (deg) at speed %g (deg/s)", target->coord/M_PI*180., target->speed/M_PI*180.);
// only positive velocity // only positive velocity
if(target->speed < 0.) target->speed = -target->speed; if(target->speed < 0.) target->speed = -target->speed;
if(fabs(target->speed) < model->Min.speed){
DBG("STOP");
model->stop(model, t);
return TRUE;
}
// don't mind about acceleration - user cannot set it now // don't mind about acceleration - user cannot set it now
return model->calculate(model, target, t); return model->calculate(model, target, t);
} }

View File

@@ -44,7 +44,7 @@ typedef struct{
typedef struct{ typedef struct{
moveparam_t min; moveparam_t min;
moveparam_t max; moveparam_t max;
double acceleration; //double acceleration;
} limits_t; } limits_t;
typedef enum{ typedef enum{

View File

@@ -0,0 +1,237 @@
/*
* This file is part of the libsidservo project.
* Copyright 2026 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <fcntl.h>
#include <poll.h>
#include <signal.h>
#include <stdlib.h>
#include <string.h>
#include <sys/ioctl.h>
#include <usefull_macros.h>
#define XYBUFSZ (2048)
struct{
int help;
char *Xpath;
char *Ypath;
double dt;
} G = {
.Xpath = "/dev/encoder_X0",
.Ypath = "/dev/encoder_Y0",
.dt = 0.001,
};
sl_option_t options[] = {
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&G.help), "show this help"},
{"Xpath", NEED_ARG, NULL, 'X', arg_string, APTR(&G.Xpath), "path to X encoder"},
{"Ypath", NEED_ARG, NULL, 'Y', arg_string, APTR(&G.Ypath), "path to Y encoder"},
{"dt", NEED_ARG, NULL, 'd', arg_double, APTR(&G.dt), "request interval (1e-4..10s)"},
};
typedef struct{
char buf[XYBUFSZ+1];
int len;
} buf_t;
static int Xfd = -1, Yfd = -1;
void signals(int sig){
if(sig){
signal(sig, SIG_IGN);
DBG("Get signal %d, quit.\n", sig);
}
DBG("close");
if(Xfd > 0){ close(Xfd); Xfd = -1; }
if(Yfd > 0){ close(Yfd); Yfd = -1; }
exit(sig);
}
static int op(const char *nm){
int fd = open(nm, O_RDWR|O_NOCTTY|O_NONBLOCK);
if(fd < 0) ERR("Can't open %s", nm);
struct termios2 tty;
if(ioctl(fd, TCGETS2, &tty)) ERR("Can't read TTY settings");
tty.c_lflag = 0; // ~(ICANON | ECHO | ECHOE | ISIG)
tty.c_iflag = 0; // don't do any changes in input stream
tty.c_oflag = 0; // don't do any changes in output stream
tty.c_cflag = BOTHER | CS8 | CREAD | CLOCAL; // other speed, 8bit, RW, ignore line ctrl
tty.c_ispeed = 1000000;
tty.c_ospeed = 1000000;
if(ioctl(fd, TCSETS2, &tty)) ERR("Can't set TTY settings");
// try to set exclusive
if(ioctl(fd, TIOCEXCL)){DBG("Can't make exclusive");}
return fd;
}
static int eolcnt(buf_t *buf){
if(!buf) return -1;
int cnt = 0;
for(int i = 0; i < buf->len; ++i)
if(buf->buf[i] == '\n') ++cnt;
return cnt;
}
// move last record (if any) into head of buffer
static void movelast(buf_t *buf){
FNAME();
if(!buf) return;
DBG("buf was: %s", buf->buf);
int cnt = eolcnt(buf);
char *E = strrchr(buf->buf, '\n');
int idx = -1;
if(E){
idx = ++E - buf->buf; // position of symbol after '\n'
}else{
buf->len = strlen(buf->buf);
DBG("leave as is (%s)", buf->buf);
return;
}
DBG("cnt=%d, idx=%d", cnt, idx);
switch(cnt){
case 0: // EOL not found - clear buf
buf->len = 0;
break;
case 1: // only one record - move all after '\n'
if(idx > 0 && idx < XYBUFSZ){
buf->len = XYBUFSZ - idx;
memmove(buf->buf, E, buf->len);
}else buf->len = 0;
break;
default: // more than one record - move
{
int i = idx - 2;
for(; i > -1; --i)
if(buf->buf[i] == '\n') break;
++i;
buf->len = XYBUFSZ - i;
memmove(buf->buf, &buf->buf[i], buf->len);
}
}
buf->buf[buf->len] = 0;
DBG("MOVED; now buf[%d]=%s", buf->len, buf->buf);
}
// write to buffer next data portion; return FALSE in case of error
static int readstrings(buf_t *buf, int fd){
if(!buf){WARNX("Empty buffer"); return FALSE;}
int L = XYBUFSZ - buf->len;
if(L == 0){
DBG("len: %d", buf->len);
movelast(buf);
L = XYBUFSZ - buf->len;
}
int got = read(fd, &buf->buf[buf->len], L);
if(got < 0){
WARN("read()");
return FALSE;
}else if(got == 0) return TRUE;
buf->len += got;
buf->buf[buf->len] = 0;
DBG("buf[%d]: %s", buf->len, buf->buf);
return TRUE;
}
// return TRUE if got, FALSE if no data found
static int getdata(buf_t *buf, long *out){
if(!buf) return -1;
// read record between last '\n' and previous (or start of string)
int cnt = eolcnt(buf);
if(cnt < 1) return FALSE;
char *last = strrchr(buf->buf, '\n');
if(!last) return FALSE; // WTF?
*last = 0;
char *prev = buf->buf;
if(cnt > 1) prev = strrchr(buf->buf, '\n') + 1;
if(!prev) prev = buf->buf; // ??
if(out) *out = atol(prev);
int l = strlen(++last);
if(l < XYBUFSZ){
buf->len = l;
if(l){
memmove(buf->buf, last, l);
DBG("moved: %s", buf->buf);
}else DBG("empty line");
}else{
buf->len = 0;
DBG("buffer clear");
}
return TRUE;
}
// try to write '\n' asking new data portion; return FALSE if failed
static int asknext(int fd){
FNAME();
if(fd < 0) return FALSE;
int i = 0;
for(; i < 5; ++i){
int l = write(fd, "\n", 1);
DBG("l=%d", l);
if(1 == l) return TRUE;
usleep(100);
}
DBG("5 tries... failed!");
return FALSE;
}
int main(int argc, char **argv){
buf_t xbuf, ybuf;
long xlast, ylast;
double xtlast, ytlast;
sl_init();
sl_parseargs(&argc, &argv, options);
if(G.help) sl_showhelp(-1, options);
if(G.dt < 1e-4) ERRX("dx too small");
if(G.dt > 10.) ERRX("dx too big");
Xfd = op(G.Xpath);
Yfd = op(G.Ypath);
struct pollfd pfds[2];
pfds[0].fd = Xfd; pfds[0].events = POLLIN;
pfds[1].fd = Yfd; pfds[1].events = POLLIN;
double t0x, t0y, tstart;
asknext(Xfd); asknext(Yfd);
t0x = t0y = tstart = sl_dtime();
DBG("Start");
do{ // main cycle
if(poll(pfds, 2, 1) < 0){
WARN("poll()");
break;
}
if(pfds[0].revents && POLLIN){
if(!readstrings(&xbuf, Xfd)) break;
}
if(pfds[1].revents && POLLIN){
if(!readstrings(&ybuf, Yfd)) break;
}
double curt = sl_dtime();
if(getdata(&xbuf, &xlast)) xtlast = curt;
if(curt - t0x >= G.dt){ // get last records
if(curt - xtlast < 1.5*G.dt)
printf("%-14.4fX=%ld\n", xtlast-tstart, xlast);
if(!asknext(Xfd)) break;
t0x = (curt - t0x < 2.*G.dt) ? t0x + G.dt : curt;
}
curt = sl_dtime();
if(getdata(&ybuf, &ylast)) ytlast = curt;
if(curt - t0y >= G.dt){ // get last records
if(curt - ytlast < 1.5*G.dt)
printf("%-14.4fY=%ld\n", ytlast-tstart, ylast);
if(!asknext(Yfd)) break;
t0y = (curt - t0y < 2.*G.dt) ? t0y + G.dt : curt;
}
}while(Xfd > 0 && Yfd > 0);
DBG("OOps: disconnected");
signals(0);
return 0;
}

View File

@@ -23,12 +23,14 @@
#include "main.h" #include "main.h"
#include "ramp.h" #include "ramp.h"
/*
#ifdef EBUG #ifdef EBUG
#undef DBG #undef DBG
#define DBG(...) #define DBG(...)
#undef FNAME
#define FNAME()
#endif #endif
*/
static double coord_tolerance = COORD_TOLERANCE_DEFAULT; static double coord_tolerance = COORD_TOLERANCE_DEFAULT;
static void emstop(movemodel_t *m, double _U_ t){ static void emstop(movemodel_t *m, double _U_ t){
@@ -120,7 +122,7 @@ static void unlockedcalc(movemodel_t *m, moveparam_t *x, double t){
} }
}else{ }else{
// if we are here, we have the worst case: change speed direction // if we are here, we have the worst case: change speed direction
DBG("Hardest case: change speed direction"); // DBG("Hardest case: change speed direction");
// now we should calculate coordinate at which model stops and biuld new trapezium from that point // now we should calculate coordinate at which model stops and biuld new trapezium from that point
double x0 = m->curparams.coord, v0 = m->curparams.speed; double x0 = m->curparams.coord, v0 = m->curparams.speed;
double xstop = x0 + sign_v0 * abs_dx_stop, tstop = t + abs_v0 / abs_a; double xstop = x0 + sign_v0 * abs_dx_stop, tstop = t + abs_v0 / abs_a;
@@ -132,7 +134,7 @@ static void unlockedcalc(movemodel_t *m, moveparam_t *x, double t){
m->Times[STAGE_ACCEL] = t; m->Times[STAGE_ACCEL] = t;
m->Params[STAGE_ACCEL].coord = x0; m->Params[STAGE_ACCEL].coord = x0;
m->Params[STAGE_ACCEL].speed = v0; m->Params[STAGE_ACCEL].speed = v0;
DBG("NOW t[0]=%g, X[0]=%g, V[0]=%g", t, x0, v0); // DBG("NOW t[0]=%g, X[0]=%g, V[0]=%g", t, x0, v0);
return; return;
} }
m->state = ST_MOVE; m->state = ST_MOVE;
@@ -210,11 +212,10 @@ static movestate_t proc(movemodel_t *m, moveparam_t *next, double t){
if(m->movingstage == STAGE_STOPPED){ if(m->movingstage == STAGE_STOPPED){
m->curparams.coord = m->Params[STAGE_STOPPED].coord; m->curparams.coord = m->Params[STAGE_STOPPED].coord;
pthread_mutex_unlock(&m->mutex); pthread_mutex_unlock(&m->mutex);
DBG("REACHED STOPping stage @ t=%g", t); /* DBG("REACHED STOPping stage @ t=%g", t);
for(int s = STAGE_STOPPED; s >= 0; --s){ for(int s = STAGE_STOPPED; s >= 0; --s){
DBG("T[%d]=%g, ", s, m->Times[s]); DBG("T[%d]=%g, ", s, m->Times[s]);
} }*/
fflush(stdout);
emstop(m, t); emstop(m, t);
goto ret; goto ret;
} }

View File

@@ -20,6 +20,7 @@
#include <errno.h> #include <errno.h>
#include <fcntl.h> #include <fcntl.h>
#include <math.h> #include <math.h>
#include <poll.h>
#include <pthread.h> #include <pthread.h>
#include <signal.h> #include <signal.h>
#include <stdint.h> #include <stdint.h>
@@ -48,7 +49,7 @@ static pthread_mutex_t mntmutex = PTHREAD_MUTEX_INITIALIZER,
// encoders thread and mount thread // encoders thread and mount thread
static pthread_t encthread, mntthread; static pthread_t encthread, mntthread;
// max timeout for 1.5 bytes of encoder and 2 bytes of mount - for `select` // max timeout for 1.5 bytes of encoder and 2 bytes of mount - for `select`
static struct timeval encRtmout = {.tv_sec = 0, .tv_usec = 50000}, mntRtmout = {.tv_sec = 0, .tv_usec = 50000}; static struct timeval encRtmout = {.tv_sec = 0, .tv_usec = 100}, mntRtmout = {.tv_sec = 0, .tv_usec = 50000};
// encoders raw data // encoders raw data
typedef struct __attribute__((packed)){ typedef struct __attribute__((packed)){
uint8_t magick; uint8_t magick;
@@ -64,18 +65,13 @@ void getXspeed(){
ls = LS_init(Conf.EncoderSpeedInterval / Conf.EncoderReqInterval); ls = LS_init(Conf.EncoderSpeedInterval / Conf.EncoderReqInterval);
if(!ls) return; if(!ls) return;
} }
double speed = LS_calc_slope(ls, mountdata.encXposition.val, mountdata.encXposition.t); double dt = timediff0(&mountdata.encXposition.t);
if(fabs(speed) < 1.5 * MCC_MAX_X_SPEED){ double speed = LS_calc_slope(ls, mountdata.encXposition.val, dt);
if(fabs(speed) < 1.5 * Xlimits.max.speed){
mountdata.encXspeed.val = speed; mountdata.encXspeed.val = speed;
mountdata.encXspeed.t = mountdata.encXposition.t; mountdata.encXspeed.t = mountdata.encXposition.t;
} }
//DBG("Xspeed=%g", mountdata.encXspeed.val); //DBG("Xspeed=%g", mountdata.encXspeed.val);
#if 0
mountdata.encXspeed.val = (mountdata.encXposition.val - lastXenc.val) / (t - lastXenc.t);
mountdata.encXspeed.t = (lastXenc.t + mountdata.encXposition.t) / 2.;
lastXenc.val = mountdata.encXposition.val;
lastXenc.t = t;
#endif
} }
void getYspeed(){ void getYspeed(){
static less_square_t *ls = NULL; static less_square_t *ls = NULL;
@@ -83,17 +79,12 @@ void getYspeed(){
ls = LS_init(Conf.EncoderSpeedInterval / Conf.EncoderReqInterval); ls = LS_init(Conf.EncoderSpeedInterval / Conf.EncoderReqInterval);
if(!ls) return; if(!ls) return;
} }
double speed = LS_calc_slope(ls, mountdata.encYposition.val, mountdata.encYposition.t); double dt = timediff0(&mountdata.encYposition.t);
if(fabs(speed) < 1.5 * MCC_MAX_Y_SPEED){ double speed = LS_calc_slope(ls, mountdata.encYposition.val, dt);
if(fabs(speed) < 1.5 * Ylimits.max.speed){
mountdata.encYspeed.val = speed; mountdata.encYspeed.val = speed;
mountdata.encYspeed.t = mountdata.encYposition.t; mountdata.encYspeed.t = mountdata.encYposition.t;
} }
#if 0
mountdata.encYspeed.val = (mountdata.encYposition.val - lastYenc.val) / (t - lastYenc.t);
mountdata.encYspeed.t = (lastYenc.t + mountdata.encYposition.t) / 2.;
lastYenc.val = mountdata.encYposition.val;
lastYenc.t = t;
#endif
} }
/** /**
@@ -101,7 +92,8 @@ void getYspeed(){
* @param databuf - input buffer with 13 bytes of data * @param databuf - input buffer with 13 bytes of data
* @param t - time when databuf[0] got * @param t - time when databuf[0] got
*/ */
static void parse_encbuf(uint8_t databuf[ENC_DATALEN], double t){ static void parse_encbuf(uint8_t databuf[ENC_DATALEN], struct timespec *t){
if(!t) return;
enc_t *edata = (enc_t*) databuf; enc_t *edata = (enc_t*) databuf;
/* /*
#ifdef EBUG #ifdef EBUG
@@ -136,18 +128,17 @@ static void parse_encbuf(uint8_t databuf[ENC_DATALEN], double t){
return; return;
} }
pthread_mutex_lock(&datamutex); pthread_mutex_lock(&datamutex);
mountdata.encXposition.val = X_ENC2RAD(edata->encX); mountdata.encXposition.val = Xenc2rad(edata->encX);
mountdata.encYposition.val = Y_ENC2RAD(edata->encY); mountdata.encYposition.val = Yenc2rad(edata->encY);
DBG("Got positions X/Y= %.6g / %.6g", mountdata.encXposition.val, mountdata.encYposition.val); DBG("Got positions X/Y= %.6g / %.6g", mountdata.encXposition.val, mountdata.encYposition.val);
mountdata.encXposition.t = t; mountdata.encXposition.t = *t;
mountdata.encYposition.t = t; mountdata.encYposition.t = *t;
//if(t - lastXenc.t > Conf.EncoderSpeedInterval) getXspeed();
//if(t - lastYenc.t > Conf.EncoderSpeedInterval) getYspeed();
getXspeed(); getYspeed(); getXspeed(); getYspeed();
pthread_mutex_unlock(&datamutex); pthread_mutex_unlock(&datamutex);
//DBG("time = %zd+%zd/1e6, X=%g deg, Y=%g deg", tv->tv_sec, tv->tv_usec, mountdata.encposition.X*180./M_PI, mountdata.encposition.Y*180./M_PI); //DBG("time = %zd+%zd/1e6, X=%g deg, Y=%g deg", tv->tv_sec, tv->tv_usec, mountdata.encposition.X*180./M_PI, mountdata.encposition.Y*180./M_PI);
} }
#if 0
/** /**
* @brief getencval - get uint64_t data from encoder * @brief getencval - get uint64_t data from encoder
* @param fd - encoder fd * @param fd - encoder fd
@@ -155,33 +146,53 @@ static void parse_encbuf(uint8_t databuf[ENC_DATALEN], double t){
* @param t - measurement time * @param t - measurement time
* @return amount of data read or 0 if problem * @return amount of data read or 0 if problem
*/ */
static int getencval(int fd, double *val, double *t){ static int getencval(int fd, double *val, struct timespec *t){
if(fd < 0) return FALSE; if(fd < 0){
DBG("Encoder fd < 0!");
return FALSE;
}
char buf[128]; char buf[128];
int got = 0, Lmax = 127; int got = 0, Lmax = 127;
double t0 = nanotime(); double t0 = timefromstart();
//DBG("start: %.6g", t0);
do{ do{
fd_set rfds; fd_set rfds;
FD_ZERO(&rfds); FD_ZERO(&rfds);
FD_SET(fd, &rfds); FD_SET(fd, &rfds);
struct timeval tv = encRtmout; struct timeval tv = encRtmout;
int retval = select(fd + 1, &rfds, NULL, NULL, &tv); int retval = select(fd + 1, &rfds, NULL, NULL, &tv);
if(!retval) continue; if(!retval){
//DBG("select()==0 - timeout, %.6g", timefromstart());
break;
}
if(retval < 0){ if(retval < 0){
if(errno == EINTR) continue; if(errno == EINTR){
DBG("EINTR");
continue;
}
DBG("select() < 0");
return 0; return 0;
} }
if(FD_ISSET(fd, &rfds)){ if(FD_ISSET(fd, &rfds)){
ssize_t l = read(fd, &buf[got], Lmax); ssize_t l = read(fd, &buf[got], Lmax);
if(l < 1) return 0; // disconnected ?? if(l < 1){
DBG("read() < 0");
return 0; // disconnected ??
}
got += l; Lmax -= l; got += l; Lmax -= l;
buf[got] = 0; buf[got] = 0;
} else continue; } else continue;
if(strchr(buf, '\n')) break; if(buf[got-1] == '\n') break; // got EOL as last symbol
}while(Lmax && nanotime() - t0 < Conf.EncoderReqInterval); }while(Lmax && timefromstart() - t0 < Conf.EncoderReqInterval / 5.);
if(got == 0) return 0; // WTF? if(got == 0){
//DBG("No data from encoder, tfs=%.6g", timefromstart());
return 0;
}
char *estr = strrchr(buf, '\n'); char *estr = strrchr(buf, '\n');
if(!estr) return 0; if(!estr){
DBG("No EOL");
return 0;
}
*estr = 0; *estr = 0;
char *bgn = strrchr(buf, '\n'); char *bgn = strrchr(buf, '\n');
if(bgn) ++bgn; if(bgn) ++bgn;
@@ -193,9 +204,11 @@ static int getencval(int fd, double *val, double *t){
return 0; // wrong number return 0; // wrong number
} }
if(val) *val = (double) data; if(val) *val = (double) data;
if(t) *t = t0; if(t){ if(!curtime(t)){ DBG("Can't get time"); return 0; }}
return got; return got;
} }
#endif
// try to read 1 byte from encoder; return -1 if nothing to read or -2 if device seems to be disconnected // try to read 1 byte from encoder; return -1 if nothing to read or -2 if device seems to be disconnected
static int getencbyte(){ static int getencbyte(){
if(encfd[0] < 0) return -1; if(encfd[0] < 0) return -1;
@@ -257,8 +270,6 @@ static void clrmntbuf(){
if(mntfd < 0) return; if(mntfd < 0) return;
uint8_t byte; uint8_t byte;
fd_set rfds; fd_set rfds;
//double t0 = nanotime();
//int n = 0;
do{ do{
FD_ZERO(&rfds); FD_ZERO(&rfds);
FD_SET(mntfd, &rfds); FD_SET(mntfd, &rfds);
@@ -272,10 +283,8 @@ static void clrmntbuf(){
if(FD_ISSET(mntfd, &rfds)){ if(FD_ISSET(mntfd, &rfds)){
ssize_t l = read(mntfd, &byte, 1); ssize_t l = read(mntfd, &byte, 1);
if(l != 1) break; if(l != 1) break;
//++n;
} else break; } else break;
}while(1); }while(1);
//DBG("Cleared by %g (got %d bytes)", nanotime() - t0, n);
} }
// main encoder thread (for separate encoder): read next data and make parsing // main encoder thread (for separate encoder): read next data and make parsing
@@ -283,7 +292,7 @@ static void *encoderthread1(void _U_ *u){
if(Conf.SepEncoder != 1) return NULL; if(Conf.SepEncoder != 1) return NULL;
uint8_t databuf[ENC_DATALEN]; uint8_t databuf[ENC_DATALEN];
int wridx = 0, errctr = 0; int wridx = 0, errctr = 0;
double t = 0.; struct timespec tcur;
while(encfd[0] > -1 && errctr < MAX_ERR_CTR){ while(encfd[0] > -1 && errctr < MAX_ERR_CTR){
int b = getencbyte(); int b = getencbyte();
if(b == -2) ++errctr; if(b == -2) ++errctr;
@@ -294,15 +303,16 @@ static void *encoderthread1(void _U_ *u){
if((uint8_t)b == ENC_MAGICK){ if((uint8_t)b == ENC_MAGICK){
// DBG("Got magic -> start filling packet"); // DBG("Got magic -> start filling packet");
databuf[wridx++] = (uint8_t) b; databuf[wridx++] = (uint8_t) b;
t = nanotime();
} }
continue; continue;
}else databuf[wridx++] = (uint8_t) b; }else databuf[wridx++] = (uint8_t) b;
if(wridx == ENC_DATALEN){ if(wridx == ENC_DATALEN){
parse_encbuf(databuf, t); if(curtime(&tcur)){
parse_encbuf(databuf, &tcur);
wridx = 0; wridx = 0;
} }
} }
}
if(encfd[0] > -1){ if(encfd[0] > -1){
close(encfd[0]); close(encfd[0]);
encfd[0] = -1; encfd[0] = -1;
@@ -310,49 +320,131 @@ static void *encoderthread1(void _U_ *u){
return NULL; return NULL;
} }
#define XYBUFSZ (128)
typedef struct{
char buf[XYBUFSZ+1];
int len;
} buf_t;
// write to buffer next data portion; return FALSE in case of error
static int readstrings(buf_t *buf, int fd){
FNAME();
if(!buf){DBG("Empty buffer"); return FALSE;}
int L = XYBUFSZ - buf->len;
if(L == 0){
DBG("buffer overfull: %d!", buf->len);
char *lastn = strrchr(buf->buf, '\n');
if(lastn){
fprintf(stderr, "BUFOVR: _%s_", buf->buf);
++lastn;
buf->len = XYBUFSZ - (lastn - buf->buf);
DBG("Memmove %d", buf->len);
memmove(lastn, buf->buf, buf->len);
buf->buf[buf->len] = 0;
}else buf->len = 0;
L = XYBUFSZ - buf->len;
}
int got = read(fd, &buf->buf[buf->len], L);
if(got < 0){
DBG("read()");
return FALSE;
}else if(got == 0){ DBG("NO data"); return TRUE; }
buf->len += got;
buf->buf[buf->len] = 0;
DBG("buf[%d]: %s", buf->len, buf->buf);
return TRUE;
}
// return TRUE if got, FALSE if no data found
static int getdata(buf_t *buf, long *out){
if(!buf || buf->len < 1) return FALSE;
// read record between last '\n' and previous (or start of string)
char *last = &buf->buf[buf->len - 1];
//DBG("buf: _%s_", buf->buf);
if(*last != '\n') return FALSE;
*last = 0;
//DBG("buf: _%s_", buf->buf);
char *prev = strrchr(buf->buf, '\n');
if(!prev) prev = buf->buf;
else{
fprintf(stderr, "MORETHANONE: _%s_", buf->buf);
++prev; // after last '\n'
}
if(out) *out = atol(prev);
// clear buffer
buf->len = 0;
return TRUE;
}
// try to write '\n' asking new data portion; return FALSE if failed
static int asknext(int fd){
FNAME();
if(fd < 0) return FALSE;
int i = 0;
for(; i < 5; ++i){
int l = write(fd, "\n", 1);
//DBG("l=%d", l);
if(1 == l) return TRUE;
usleep(100);
}
DBG("5 tries... failed!");
return FALSE;
}
// main encoder thread for separate encoders as USB devices /dev/encoder_X0 and /dev/encoder_Y0 // main encoder thread for separate encoders as USB devices /dev/encoder_X0 and /dev/encoder_Y0
static void *encoderthread2(void _U_ *u){ static void *encoderthread2(void _U_ *u){
if(Conf.SepEncoder != 2) return NULL; if(Conf.SepEncoder != 2) return NULL;
DBG("Thread started"); DBG("Thread started");
struct pollfd pfds[2];
pfds[0].fd = encfd[0]; pfds[0].events = POLLIN;
pfds[1].fd = encfd[1]; pfds[1].events = POLLIN;
double t0[2], tstart;
buf_t strbuf[2];
long msrlast[2]; // last encoder data
double mtlast[2]; // last measurement time
asknext(encfd[0]); asknext(encfd[1]);
t0[0] = t0[1] = tstart = timefromstart();
int errctr = 0; int errctr = 0;
double t0 = nanotime(); do{ // main cycle
const char *req = "\n"; if(poll(pfds, 2, 0) < 0){
int need2ask = 0; // need or not to ask encoder for new data DBG("poll()");
while(encfd[0] > -1 && encfd[1] > -1 && errctr < MAX_ERR_CTR){ break;
if(need2ask){
if(1 != write(encfd[0], req, 1)) { ++errctr; continue; }
else if(1 != write(encfd[1], req, 1)) { ++errctr; continue; }
} }
double v, t; int got = 0;
if(getencval(encfd[0], &v, &t)){ for(int i = 0; i < 2; ++i){
mountdata.encXposition.val = X_ENC2RAD(v); if(pfds[i].revents && POLLIN){
//DBG("encX(%g) = %g", t, mountdata.encXposition.val); if(!readstrings(&strbuf[i], encfd[i])){
mountdata.encXposition.t = t; ++errctr;
//if(t - lastXenc.t > Conf.EncoderSpeedInterval) getXspeed(); break;
}
}
double curt = timefromstart();
if(getdata(&strbuf[i], &msrlast[i])) mtlast[i] = curt;
if(curt - t0[i] >= Conf.EncoderReqInterval){ // get last records
if(curt - mtlast[i] < 1.5*Conf.EncoderReqInterval){
pthread_mutex_lock(&datamutex);
if(i == 0){
mountdata.encXposition.val = Xenc2rad((double)msrlast[i]);
curtime(&mountdata.encXposition.t);
getXspeed(); getXspeed();
if(getencval(encfd[1], &v, &t)){ }else{
mountdata.encYposition.val = Y_ENC2RAD(v); mountdata.encYposition.val = Yenc2rad((double)msrlast[i]);
//DBG("encY(%g) = %g", t, mountdata.encYposition.val); curtime(&mountdata.encYposition.t);
mountdata.encYposition.t = t;
//if(t - lastYenc.t > Conf.EncoderSpeedInterval) getYspeed();
getYspeed(); getYspeed();
errctr = 0;
need2ask = 0;
} else {
if(need2ask) ++errctr;
else need2ask = 1;
continue;
} }
} else { pthread_mutex_unlock(&datamutex);
if(need2ask) ++errctr;
else need2ask = 1;
continue;
} }
while(nanotime() - t0 < Conf.EncoderReqInterval){ usleep(50); } if(!asknext(encfd[i])){
//DBG("DT=%g (RI=%g)", nanotime()-t0, Conf.EncoderReqInterval); ++errctr;
t0 = nanotime(); break;
} }
DBG("ERRCTR=%d", errctr); t0[i] = (curt - t0[i] < 2.*Conf.EncoderReqInterval) ? t0[i] + Conf.EncoderReqInterval : curt;
++got;
}
}
if(got == 2) errctr = 0;
}while(encfd[0] > -1 && encfd[1] > -1 && errctr < MAX_ERR_CTR);
DBG("\n\nEXIT: ERRCTR=%d", errctr);
for(int i = 0; i < 2; ++i){ for(int i = 0; i < 2; ++i){
if(encfd[i] > -1){ if(encfd[i] > -1){
close(encfd[i]); close(encfd[i]);
@@ -378,20 +470,67 @@ void data_free(data_t **x){
*x = NULL; *x = NULL;
} }
static void chkModStopped(double *prev, double cur, int *nstopped, axis_status_t *stat){
if(!prev || !nstopped || !stat) return;
if(isnan(*prev)){
*stat = AXIS_STOPPED;
DBG("START");
}else if(*stat != AXIS_STOPPED){
if(fabs(*prev - cur) < DBL_EPSILON && ++(*nstopped) > MOTOR_STOPPED_CNT){
*stat = AXIS_STOPPED;
DBG("AXIS stopped; prev=%g, cur=%g; nstopped=%d", *prev/M_PI*180., cur/M_PI*180., *nstopped);
}
}else if(*prev != cur){
DBG("AXIS moving");
*nstopped = 0;
}
*prev = cur;
}
// main mount thread // main mount thread
static void *mountthread(void _U_ *u){ static void *mountthread(void _U_ *u){
int errctr = 0; int errctr = 0;
uint8_t buf[2*sizeof(SSstat)]; uint8_t buf[2*sizeof(SSstat)];
SSstat *status = (SSstat*) buf; SSstat *status = (SSstat*) buf;
bzero(&mountdata, sizeof(mountdata)); bzero(&mountdata, sizeof(mountdata));
if(Conf.RunModel) while(1){ double t0 = timefromstart(), tstart = t0, tcur = t0;
pthread_mutex_lock(&datamutex); double oldmt = -100.; // old `millis measurement` time
static uint32_t oldmillis = 0;
if(Conf.RunModel){
double Xprev = NAN, Yprev = NAN; // previous coordinates
int xcnt = 0, ycnt = 0;
while(1){
coordpair_t c;
movestate_t xst, yst;
// now change data // now change data
getModData(&mountdata); getModData(&c, &xst, &yst);
struct timespec tnow;
if(!curtime(&tnow) || (tcur = timefromstart()) < 0.) continue;
pthread_mutex_lock(&datamutex);
mountdata.encXposition.t = mountdata.encYposition.t = tnow;
mountdata.encXposition.val = c.X;
mountdata.encYposition.val = c.Y;
//DBG("t=%g, X=%g, Y=%g", tnow, c.X.val, c.Y.val);
if(tcur - oldmt > Conf.MountReqInterval){
oldmillis = mountdata.millis = (uint32_t)((tcur - tstart) * 1e3);
mountdata.motYposition.t = mountdata.motXposition.t = tnow;
if(xst == ST_MOVE)
mountdata.motXposition.val = c.X + (c.X - mountdata.motXposition.val)*(drand48() - 0.5)/100.;
else
mountdata.motXposition.val = c.X;
if(yst == ST_MOVE)
mountdata.motYposition.val = c.Y + (c.Y - mountdata.motYposition.val)*(drand48() - 0.5)/100.;
else
mountdata.motYposition.val = c.Y;
oldmt = tcur;
}else mountdata.millis = oldmillis;
chkModStopped(&Xprev, c.X, &xcnt, &mountdata.Xstate);
chkModStopped(&Yprev, c.Y, &ycnt, &mountdata.Ystate);
getXspeed(); getYspeed();
pthread_mutex_unlock(&datamutex); pthread_mutex_unlock(&datamutex);
double t0 = nanotime(); while(timefromstart() - t0 < Conf.EncoderReqInterval) usleep(50);
while(nanotime() - t0 < Conf.EncoderReqInterval) usleep(50); t0 = timefromstart();
t0 = nanotime(); }
} }
// data to get // data to get
data_t d = {.buf = buf, .maxlen = sizeof(buf)}; data_t d = {.buf = buf, .maxlen = sizeof(buf)};
@@ -400,31 +539,8 @@ static void *mountthread(void _U_ *u){
if(!cmd_getstat) goto failed; if(!cmd_getstat) goto failed;
while(mntfd > -1 && errctr < MAX_ERR_CTR){ while(mntfd > -1 && errctr < MAX_ERR_CTR){
// read data to status // read data to status
double t0 = nanotime(); struct timespec tcur;
#if 0 if(!curtime(&tcur)) continue;
// 127 milliseconds to get answer on X/Y commands!!!
int64_t ans;
int ctr = 0;
if(SSgetint(CMD_MOTX, &ans)){
pthread_mutex_lock(&datamutex);
mountdata.motXposition.t = tgot;
mountdata.motXposition.val = X_MOT2RAD(ans);
pthread_mutex_unlock(&datamutex);
++ctr;
}
tgot = nanotime();
if(SSgetint(CMD_MOTY, &ans)){
pthread_mutex_lock(&datamutex);
mountdata.motXposition.t = tgot;
mountdata.motXposition.val = X_MOT2RAD(ans);
pthread_mutex_unlock(&datamutex);
++ctr;
}
if(ctr == 2){
mountdata.millis = (uint32_t)(1e3 * tgot);
DBG("Got both coords; millis=%d", mountdata.millis);
}
#endif
// 80 milliseconds to get answer on GETSTAT // 80 milliseconds to get answer on GETSTAT
if(!MountWriteRead(cmd_getstat, &d) || d.len != sizeof(SSstat)){ if(!MountWriteRead(cmd_getstat, &d) || d.len != sizeof(SSstat)){
#ifdef EBUG #ifdef EBUG
@@ -441,14 +557,13 @@ static void *mountthread(void _U_ *u){
errctr = 0; errctr = 0;
pthread_mutex_lock(&datamutex); pthread_mutex_lock(&datamutex);
// now change data // now change data
SSconvstat(status, &mountdata, t0); SSconvstat(status, &mountdata, &tcur);
pthread_mutex_unlock(&datamutex); pthread_mutex_unlock(&datamutex);
//DBG("GOT FULL stat by %g", nanotime() - t0);
// allow writing & getters // allow writing & getters
do{ do{
usleep(500); usleep(500);
}while(nanotime() - t0 < Conf.MountReqInterval); }while(timefromstart() - t0 < Conf.MountReqInterval);
t0 = nanotime(); t0 = timefromstart();
} }
data_free(&cmd_getstat); data_free(&cmd_getstat);
failed: failed:
@@ -464,8 +579,15 @@ static int ttyopen(const char *path, speed_t speed){
int fd = -1; int fd = -1;
struct termios2 tty; struct termios2 tty;
DBG("Try to open %s @ %d", path, speed); DBG("Try to open %s @ %d", path, speed);
if((fd = open(path, O_RDWR|O_NOCTTY)) < 0) return -1; if((fd = open(path, O_RDWR|O_NOCTTY)) < 0){
if(ioctl(fd, TCGETS2, &tty)){ close(fd); return -1; } DBG("Can't open device %s: %s", path, strerror(errno));
return -1;
}
if(ioctl(fd, TCGETS2, &tty)){
DBG("Can't read TTY settings");
close(fd);
return -1;
}
tty.c_lflag = 0; // ~(ICANON | ECHO | ECHOE | ISIG) tty.c_lflag = 0; // ~(ICANON | ECHO | ECHOE | ISIG)
tty.c_iflag = 0; // don't do any changes in input stream tty.c_iflag = 0; // don't do any changes in input stream
tty.c_oflag = 0; // don't do any changes in output stream tty.c_oflag = 0; // don't do any changes in output stream
@@ -474,7 +596,11 @@ static int ttyopen(const char *path, speed_t speed){
tty.c_ospeed = speed; tty.c_ospeed = speed;
//tty.c_cc[VMIN] = 0; // non-canonical mode //tty.c_cc[VMIN] = 0; // non-canonical mode
//tty.c_cc[VTIME] = 5; //tty.c_cc[VTIME] = 5;
if(ioctl(fd, TCSETS2, &tty)){ close(fd); return -1; } if(ioctl(fd, TCSETS2, &tty)){
DBG("Can't set TTY settings");
close(fd);
return -1;
}
DBG("Check speed: i=%d, o=%d", tty.c_ispeed, tty.c_ospeed); DBG("Check speed: i=%d, o=%d", tty.c_ispeed, tty.c_ospeed);
if(tty.c_ispeed != (speed_t) speed || tty.c_ospeed != (speed_t)speed){ close(fd); return -1; } if(tty.c_ispeed != (speed_t) speed || tty.c_ospeed != (speed_t)speed){ close(fd); return -1; }
// try to set exclusive // try to set exclusive
@@ -507,7 +633,7 @@ int openEncoder(){
if(encfd[i] < 0) return FALSE; if(encfd[i] < 0) return FALSE;
} }
encRtmout.tv_sec = 0; encRtmout.tv_sec = 0;
encRtmout.tv_usec = 1000; // 1ms encRtmout.tv_usec = 100000000 / Conf.EncoderDevSpeed;
if(pthread_create(&encthread, NULL, encoderthread2, NULL)){ if(pthread_create(&encthread, NULL, encoderthread2, NULL)){
for(int i = 0; i < 2; ++i){ for(int i = 0; i < 2; ++i){
close(encfd[i]); close(encfd[i]);
@@ -554,6 +680,7 @@ create_thread:
// close all opened serial devices and quit threads // close all opened serial devices and quit threads
void closeSerial(){ void closeSerial(){
// TODO: close devices in "model" mode too!
if(Conf.RunModel) return; if(Conf.RunModel) return;
if(mntfd > -1){ if(mntfd > -1){
DBG("Cancel mount thread"); DBG("Cancel mount thread");
@@ -572,7 +699,7 @@ void closeSerial(){
DBG("close encoder's fd"); DBG("close encoder's fd");
close(encfd[0]); close(encfd[0]);
encfd[0] = -1; encfd[0] = -1;
if(Conf.SepEncoder == 2){ if(Conf.SepEncoder == 2 && encfd[1] > -1){
close(encfd[1]); close(encfd[1]);
encfd[1] = -1; encfd[1] = -1;
} }
@@ -585,6 +712,8 @@ mcc_errcodes_t getMD(mountdata_t *d){
pthread_mutex_lock(&datamutex); pthread_mutex_lock(&datamutex);
*d = mountdata; *d = mountdata;
pthread_mutex_unlock(&datamutex); pthread_mutex_unlock(&datamutex);
//DBG("ENCpos: %.10g/%.10g", d->encXposition.val, d->encYposition.val);
//DBG("millis: %u, encxt: %zd (time: %zd)", d->millis, d->encXposition.t.tv_sec, time(NULL));
return MCC_E_OK; return MCC_E_OK;
} }
@@ -603,30 +732,24 @@ static int wr(const data_t *out, data_t *in, int needeol){
return FALSE; return FALSE;
} }
clrmntbuf(); clrmntbuf();
//double t0 = nanotime();
if(out){ if(out){
if(out->len != (size_t)write(mntfd, out->buf, out->len)){ if(out->len != (size_t)write(mntfd, out->buf, out->len)){
DBG("written bytes not equal to need"); DBG("written bytes not equal to need");
return FALSE; return FALSE;
} }
//DBG("Send to mount %zd bytes: %s", out->len, out->buf);
if(needeol){ if(needeol){
int g = write(mntfd, "\r", 1); // add EOL int g = write(mntfd, "\r", 1); // add EOL
(void) g; (void) g;
} }
usleep(50000); // add little pause so that the idiot has time to swallow
} }
//DBG("sent by %g", nanotime() - t0);
//uint8_t buf[256];
//data_t dumb = {.buf = buf, .maxlen = 256};
if(!in) return TRUE; if(!in) return TRUE;
//if(!in) in = &dumb; // even if user don't ask for answer, try to read to clear trash
in->len = 0; in->len = 0;
for(size_t i = 0; i < in->maxlen; ++i){ for(size_t i = 0; i < in->maxlen; ++i){
int b = getmntbyte(); int b = getmntbyte();
if(b < 0) break; // nothing to read -> go out if(b < 0) break; // nothing to read -> go out
in->buf[in->len++] = (uint8_t) b; in->buf[in->len++] = (uint8_t) b;
} }
//DBG("got %zd bytes by %g", in->len, nanotime() - t0);
while(getmntbyte() > -1); while(getmntbyte() > -1);
return TRUE; return TRUE;
} }
@@ -730,16 +853,23 @@ int cmdC(SSconfig *conf, int rw){
}else{ // read }else{ // read
data_t d; data_t d;
d.buf = (uint8_t *) conf; d.buf = (uint8_t *) conf;
d.len = 0; d.maxlen = 0;
ret = wr(rcmd, &d, 1);
DBG("write command: %s", ret ? "TRUE" : "FALSE");
if(!ret) goto rtn;
// make a huge pause for stupid SSII
usleep(100000);
d.len = 0; d.maxlen = sizeof(SSconfig); d.len = 0; d.maxlen = sizeof(SSconfig);
ret = wr(rcmd, &d, 1); ret = wr(rcmd, &d, 1);
DBG("wr returned %s; got %zd bytes of %zd", ret ? "TRUE" : "FALSE", d.len, d.maxlen); DBG("wr returned %s; got %zd bytes of %zd", ret ? "TRUE" : "FALSE", d.len, d.maxlen);
if(d.len != d.maxlen) return FALSE; if(d.len != d.maxlen){ ret = FALSE; goto rtn; }
// simplest checksum // simplest checksum
uint16_t sum = 0; uint16_t sum = 0;
for(uint32_t i = 0; i < sizeof(SSconfig)-2; ++i) sum += d.buf[i]; for(uint32_t i = 0; i < sizeof(SSconfig)-2; ++i) sum += d.buf[i];
if(sum != conf->checksum){ if(sum != conf->checksum){
DBG("got sum: %u, need: %u", conf->checksum, sum); DBG("got sum: %u, need: %u", conf->checksum, sum);
return FALSE; ret = FALSE;
goto rtn;
} }
} }
rtn: rtn:

View File

@@ -32,37 +32,13 @@ extern "C"
#include <stdint.h> #include <stdint.h>
#include <sys/time.h> #include <sys/time.h>
// acceptable position error - 0.1'' // minimal serial speed of mount device
#define MCC_POSITION_ERROR (5e-7) #define MOUNT_BAUDRATE_MIN (1200)
// acceptable disagreement between motor and axis encoders - 2''
#define MCC_ENCODERS_ERROR (1e-7)
// max speeds (rad/s): xs=10 deg/s, ys=8 deg/s
#define MCC_MAX_X_SPEED (0.174533)
#define MCC_MAX_Y_SPEED (0.139626)
// accelerations by both axis (for model); TODO: move speeds/accelerations into config?
// xa=12.6 deg/s^2, ya= 9.5 deg/s^2
#define MCC_X_ACCELERATION (0.219911)
#define MCC_Y_ACCELERATION (0.165806)
// max speed interval, seconds // max speed interval, seconds
#define MCC_CONF_MAX_SPEEDINT (2.) #define MCC_CONF_MAX_SPEEDINT (2.)
// minimal speed interval in parts of EncoderReqInterval // minimal speed interval in parts of EncoderReqInterval
#define MCC_CONF_MIN_SPEEDC (3.) #define MCC_CONF_MIN_SPEEDC (3.)
// PID I cycle time (analog of "RC" for PID on opamps)
#define MCC_PID_CYCLE_TIME (5.)
// maximal PID refresh time interval (if larger all old data will be cleared)
#define MCC_PID_MAX_DT (1.)
// normal PID refresh interval
#define MCC_PID_REFRESH_DT (0.1)
// boundary conditions for axis state: "slewing/pointing/guiding"
// if angle < MCC_MAX_POINTING_ERR, change state from "slewing" to "pointing": 5 degrees
//#define MCC_MAX_POINTING_ERR (0.20943951)
#define MCC_MAX_POINTING_ERR (0.08726646)
// if angle < MCC_MAX_GUIDING_ERR, chane state from "pointing" to "guiding": 1.5 deg
#define MCC_MAX_GUIDING_ERR (0.026179939)
// if error less than this value we suppose that target is captured and guiding is good: 0.1''
#define MCC_MAX_ATTARGET_ERR (4.8481368e-7)
// error codes // error codes
typedef enum{ typedef enum{
@@ -72,6 +48,7 @@ typedef enum{
MCC_E_ENCODERDEV, // encoder device error or can't open MCC_E_ENCODERDEV, // encoder device error or can't open
MCC_E_MOUNTDEV, // mount device error or can't open MCC_E_MOUNTDEV, // mount device error or can't open
MCC_E_FAILED, // failed to run command - protocol error MCC_E_FAILED, // failed to run command - protocol error
MCC_E_AMOUNT // Just amount of errors
} mcc_errcodes_t; } mcc_errcodes_t;
typedef struct{ typedef struct{
@@ -86,14 +63,23 @@ typedef struct{
int SepEncoder; // ==1 if encoder works as separate serial device, ==2 if there's new version with two devices int SepEncoder; // ==1 if encoder works as separate serial device, ==2 if there's new version with two devices
char* EncoderXDevPath; // paths to new controller devices char* EncoderXDevPath; // paths to new controller devices
char* EncoderYDevPath; char* EncoderYDevPath;
double EncodersDisagreement; // acceptable disagreement between motor and axis encoders
double MountReqInterval; // interval between subsequent mount requests (seconds) double MountReqInterval; // interval between subsequent mount requests (seconds)
double EncoderReqInterval; // interval between subsequent encoder requests (seconds) double EncoderReqInterval; // interval between subsequent encoder requests (seconds)
double EncoderSpeedInterval; // interval between speed calculations double EncoderSpeedInterval; // interval between speed calculations
int RunModel; // == 1 if you want to use model instead of real mount int RunModel; // == 1 if you want to use model instead of real mount
double PIDMaxDt; // maximal PID refresh time interval (if larger all old data will be cleared)
double PIDRefreshDt; // normal PID refresh interval
double PIDCycleDt; // PID I cycle time (analog of "RC" for PID on opamps)
PIDpar_t XPIDC; // gain parameters of PID for both axiss (C - coordinate driven, V - velocity driven) PIDpar_t XPIDC; // gain parameters of PID for both axiss (C - coordinate driven, V - velocity driven)
PIDpar_t XPIDV; PIDpar_t XPIDV;
PIDpar_t YPIDC; PIDpar_t YPIDC;
PIDpar_t YPIDV; PIDpar_t YPIDV;
double MaxPointingErr; // if angle < this, change state from "slewing" to "pointing" (coarse pointing): 8 degrees
double MaxFinePointingErr; // if angle < this, chane state from "pointing" to "guiding" (fine poinging): 1.5 deg
double MaxGuidingErr; // if error less than this value we suppose that target is captured and guiding is good (true guiding): 0.1''
int XEncZero; // encoders' zero position
int YEncZero;
} conf_t; } conf_t;
// coordinates/speeds in degrees or d/s: X, Y // coordinates/speeds in degrees or d/s: X, Y
@@ -104,7 +90,7 @@ typedef struct{
// coordinate/speed and time of last measurement // coordinate/speed and time of last measurement
typedef struct{ typedef struct{
double val; double val;
double t; struct timespec t;
} coordval_t; } coordval_t;
typedef struct{ typedef struct{
@@ -205,6 +191,9 @@ typedef struct{
double outplimit; // Output Limit, percent (0..100) double outplimit; // Output Limit, percent (0..100)
double currlimit; // Current Limit (A) double currlimit; // Current Limit (A)
double intlimit; // Integral Limit (???) double intlimit; // Integral Limit (???)
// these params are taken from mount by text commands (don't save negative values - better save these marks in xybits
double motor_stepsperrev;// encoder's steps per revolution: motor and axis
double axis_stepsperrev; // negative sign of these values means reverse direction
} __attribute__((packed)) axis_config_t; } __attribute__((packed)) axis_config_t;
// hardware configuration // hardware configuration
@@ -246,7 +235,7 @@ typedef struct{
void (*quit)(); // deinit void (*quit)(); // deinit
mcc_errcodes_t (*getMountData)(mountdata_t *d); // get last data mcc_errcodes_t (*getMountData)(mountdata_t *d); // get last data
// mcc_errcodes_t (*slewTo)(const coordpair_t *target, slewflags_t flags); // mcc_errcodes_t (*slewTo)(const coordpair_t *target, slewflags_t flags);
mcc_errcodes_t (*correctTo)(const coordval_pair_t *target, const coordpair_t *endpoint); mcc_errcodes_t (*correctTo)(const coordval_pair_t *target);
mcc_errcodes_t (*moveTo)(const coordpair_t *target); // move to given position and stop mcc_errcodes_t (*moveTo)(const coordpair_t *target); // move to given position and stop
mcc_errcodes_t (*moveWspeed)(const coordpair_t *target, const coordpair_t *speed); // move with given max speed mcc_errcodes_t (*moveWspeed)(const coordpair_t *target, const coordpair_t *speed); // move with given max speed
mcc_errcodes_t (*setSpeed)(const coordpair_t *tagspeed); // set speed mcc_errcodes_t (*setSpeed)(const coordpair_t *tagspeed); // set speed
@@ -256,7 +245,13 @@ typedef struct{
mcc_errcodes_t (*longCmd)(long_command_t *cmd); // send/get long command mcc_errcodes_t (*longCmd)(long_command_t *cmd); // send/get long command
mcc_errcodes_t (*getHWconfig)(hardware_configuration_t *c); // get hardware configuration mcc_errcodes_t (*getHWconfig)(hardware_configuration_t *c); // get hardware configuration
mcc_errcodes_t (*saveHWconfig)(hardware_configuration_t *c); // save hardware configuration mcc_errcodes_t (*saveHWconfig)(hardware_configuration_t *c); // save hardware configuration
double (*currentT)(); // current time int (*currentT)(struct timespec *t); // current time
double (*timeFromStart)(); // amount of seconds from last init
double (*timeDiff)(const struct timespec *time1, const struct timespec *time0); // difference of times
double (*timeDiff0)(const struct timespec *time1); // difference between current time and last init time
mcc_errcodes_t (*getMaxSpeed)(coordpair_t *v); // maximal speed by both axis
mcc_errcodes_t (*getMinSpeed)(coordpair_t *v); // minimal -//-
mcc_errcodes_t (*getAcceleration)(coordpair_t *a); // acceleration/deceleration
} mount_t; } mount_t;
extern mount_t Mount; extern mount_t Mount;

View File

@@ -18,6 +18,7 @@
#include <ctype.h> #include <ctype.h>
#include <inttypes.h> #include <inttypes.h>
#include <stdio.h>
#include <string.h> #include <string.h>
#include <unistd.h> #include <unistd.h>
@@ -25,6 +26,9 @@
#include "serial.h" #include "serial.h"
#include "ssii.h" #include "ssii.h"
int X_ENC_ZERO, Y_ENC_ZERO;
double X_MOT_STEPSPERREV = 1., Y_MOT_STEPSPERREV = 1., X_ENC_STEPSPERREV = 1., Y_ENC_STEPSPERREV = 1.;
uint16_t SScalcChecksum(uint8_t *buf, int len){ uint16_t SScalcChecksum(uint8_t *buf, int len){
uint16_t checksum = 0; uint16_t checksum = 0;
for(int i = 0; i < len; i++){ for(int i = 0; i < len; i++){
@@ -66,17 +70,18 @@ static void ChkStopped(const SSstat *s, mountdata_t *m){
* @param m (o) - output * @param m (o) - output
* @param t - measurement time * @param t - measurement time
*/ */
void SSconvstat(const SSstat *s, mountdata_t *m, double t){ void SSconvstat(const SSstat *s, mountdata_t *m, struct timespec *t){
if(!s || !m) return; if(!s || !m || !t) return;
m->motXposition.val = X_MOT2RAD(s->Xmot); m->motXposition.val = X_MOT2RAD(s->Xmot);
m->motYposition.val = Y_MOT2RAD(s->Ymot); m->motYposition.val = Y_MOT2RAD(s->Ymot);
ChkStopped(s, m); ChkStopped(s, m);
m->motXposition.t = m->motYposition.t = t; m->motXposition.t = m->motYposition.t = *t;
// fill encoder data from here, as there's no separate enc thread // fill encoder data from here, as there's no separate enc thread
if(!Conf.SepEncoder){ if(!Conf.SepEncoder){
m->encXposition.val = X_ENC2RAD(s->Xenc); m->encXposition.val = Xenc2rad(s->Xenc);
m->encYposition.val = Y_ENC2RAD(s->Yenc); DBG("encx: %g", m->encXposition.val);
m->encXposition.t = m->encYposition.t = t; m->encYposition.val = Yenc2rad(s->Yenc);
m->encXposition.t = m->encYposition.t = *t;
getXspeed(); getYspeed(); getXspeed(); getYspeed();
} }
m->keypad = s->keypad; m->keypad = s->keypad;
@@ -175,33 +180,39 @@ int SSstop(int emerg){
mcc_errcodes_t updateMotorPos(){ mcc_errcodes_t updateMotorPos(){
mountdata_t md = {0}; mountdata_t md = {0};
if(Conf.RunModel) return MCC_E_OK; if(Conf.RunModel) return MCC_E_OK;
double t0 = nanotime(), t = 0.; double t0 = timefromstart(), t = 0.;
struct timespec curt;
DBG("start @ %g", t0); DBG("start @ %g", t0);
do{ do{
t = nanotime(); t = timefromstart();
if(MCC_E_OK == getMD(&md)){ if(!curtime(&curt)){
if(md.encXposition.t == 0 || md.encYposition.t == 0){ usleep(10000);
DBG("Just started, t-t0 = %g!", t - t0);
sleep(1);
DBG("t-t0 = %g", nanotime() - t0);
//usleep(10000);
continue; continue;
} }
DBG("got; t pos x/y: %g/%g; tnow: %g", md.encXposition.t, md.encYposition.t, t); //DBG("XENC2RAD: %g (xez=%d, xesr=%.10g)", Xenc2rad(32424842), X_ENC_ZERO, X_ENC_STEPSPERREV);
if(MCC_E_OK == getMD(&md)){
if(md.encXposition.t.tv_sec == 0 || md.encYposition.t.tv_sec == 0){
DBG("Just started? t-t0 = %g!", t - t0);
usleep(10000);
continue;
}
if(md.Xstate != AXIS_STOPPED || md.Ystate != AXIS_STOPPED) return MCC_E_OK;
DBG("got; t pos x/y: %ld/%ld; tnow: %ld", md.encXposition.t.tv_sec, md.encYposition.t.tv_sec, curt.tv_sec);
mcc_errcodes_t OK = MCC_E_OK; mcc_errcodes_t OK = MCC_E_OK;
if(fabs(md.motXposition.val - md.encXposition.val) > MCC_ENCODERS_ERROR && md.Xstate == AXIS_STOPPED){ if(fabs(md.motXposition.val - md.encXposition.val) > Conf.EncodersDisagreement && md.Xstate == AXIS_STOPPED){
DBG("NEED to sync X: motors=%g, axiss=%g", md.motXposition.val, md.encXposition.val); DBG("NEED to sync X: motors=%g, axis=%g", md.motXposition.val, md.encXposition.val);
DBG("new motsteps: %d", X_RAD2MOT(md.encXposition.val));
if(!SSsetterI(CMD_MOTXSET, X_RAD2MOT(md.encXposition.val))){ if(!SSsetterI(CMD_MOTXSET, X_RAD2MOT(md.encXposition.val))){
DBG("Xpos sync failed!"); DBG("Xpos sync failed!");
OK = MCC_E_FAILED; OK = MCC_E_FAILED;
}else DBG("Xpos sync OK, Dt=%g", nanotime() - t0); }else DBG("Xpos sync OK, Dt=%g", t - t0);
} }
if(fabs(md.motYposition.val - md.encYposition.val) > MCC_ENCODERS_ERROR && md.Xstate == AXIS_STOPPED){ if(fabs(md.motYposition.val - md.encYposition.val) > Conf.EncodersDisagreement && md.Ystate == AXIS_STOPPED){
DBG("NEED to sync Y: motors=%g, axiss=%g", md.motYposition.val, md.encYposition.val); DBG("NEED to sync Y: motors=%g, axis=%g", md.motYposition.val, md.encYposition.val);
if(!SSsetterI(CMD_MOTYSET, Y_RAD2MOT(md.encYposition.val))){ if(!SSsetterI(CMD_MOTYSET, Y_RAD2MOT(md.encYposition.val))){
DBG("Ypos sync failed!"); DBG("Ypos sync failed!");
OK = MCC_E_FAILED; OK = MCC_E_FAILED;
}else DBG("Ypos sync OK, Dt=%g", nanotime() - t0); }else DBG("Ypos sync OK, Dt=%g", t - t0);
} }
if(MCC_E_OK == OK){ if(MCC_E_OK == OK){
DBG("Encoders synced"); DBG("Encoders synced");

View File

@@ -173,64 +173,72 @@
#define SITECH_LOOP_FREQUENCY (1953.) #define SITECH_LOOP_FREQUENCY (1953.)
// amount of consequent same coordinates to detect stop // amount of consequent same coordinates to detect stop
#define MOTOR_STOPPED_CNT (4) #define MOTOR_STOPPED_CNT (19)
// replace macros with global variables inited when config read
extern int X_ENC_ZERO, Y_ENC_ZERO;
extern double X_MOT_STEPSPERREV, Y_MOT_STEPSPERREV, X_ENC_STEPSPERREV, Y_ENC_STEPSPERREV;
// TODO: take it from settings? // TODO: take it from settings?
// steps per revolution (SSI - x4 - for SSI) // steps per revolution (SSI - x4 - for SSI)
#define X_MOT_STEPSPERREV_SSI (13312000.) // -> hwconf.Xconf.mot/enc_stepsperrev
//#define X_MOT_STEPSPERREV_SSI (13312000.)
// 13312000 / 4 = 3328000 // 13312000 / 4 = 3328000
#define X_MOT_STEPSPERREV (3328000.) //#define X_MOT_STEPSPERREV (3328000.)
#define Y_MOT_STEPSPERREV_SSI (17578668.) //#define Y_MOT_STEPSPERREV_SSI (17578668.)
// 17578668 / 4 = 4394667 // 17578668 / 4 = 4394667
#define Y_MOT_STEPSPERREV (4394667.) //#define Y_MOT_STEPSPERREV (4394667.)
// encoder per revolution // encoder per revolution
#define X_ENC_STEPSPERREV (67108864.) //#define X_ENC_STEPSPERREV (67108864.)
#define Y_ENC_STEPSPERREV (67108864.) //#define Y_ENC_STEPSPERREV (67108864.)
// encoder zero position // encoder zero position
#define X_ENC_ZERO (61245239) // -> conf.XEncZero/YEncZero
#define Y_ENC_ZERO (36999830) //#define X_ENC_ZERO (61245239)
// encoder reversed (no: +1) //#define Y_ENC_ZERO (36999830)
#define X_ENC_SIGN (-1.) // encoder reversed (no: +1) -> sign of ...stepsperrev
#define Y_ENC_SIGN (-1.) //#define X_ENC_SIGN (-1.)
//#define Y_ENC_SIGN (-1.)
// encoder position to radians and back // encoder position to radians and back
#define X_ENC2RAD(n) ang2half(X_ENC_SIGN * 2.*M_PI * ((double)((n)-X_ENC_ZERO)) / X_ENC_STEPSPERREV) #define Xenc2rad(n) ang2half(2.*M_PI * ((double)((n)-(X_ENC_ZERO))) / (X_ENC_STEPSPERREV))
#define Y_ENC2RAD(n) ang2half(Y_ENC_SIGN * 2.*M_PI * ((double)((n)-Y_ENC_ZERO)) / Y_ENC_STEPSPERREV) #define Yenc2rad(n) ang2half(2.*M_PI * ((double)((n)-(Y_ENC_ZERO))) / (Y_ENC_STEPSPERREV))
#define X_RAD2ENC(r) ((uint32_t)((r) / 2./M_PI * X_ENC_STEPSPERREV)) #define Xrad2enc(r) ((uint32_t)((r) / 2./M_PI * (X_ENC_STEPSPERREV)))
#define Y_RAD2ENC(r) ((uint32_t)((r) / 2./M_PI * Y_ENC_STEPSPERREV)) #define Yrad2enc(r) ((uint32_t)((r) / 2./M_PI * (Y_ENC_STEPSPERREV)))
// convert angle in radians to +-pi // convert angle in radians to +-pi
static inline double ang2half(double ang){ static inline __attribute__((always_inline)) double ang2half(double ang){
if(ang < -M_PI) ang += 2.*M_PI; if(ang < -M_PI) ang += 2.*M_PI;
else if(ang > M_PI) ang -= 2.*M_PI; else if(ang > M_PI) ang -= 2.*M_PI;
return ang; return ang;
} }
// convert to only positive: 0..2pi // convert to only positive: 0..2pi
static inline double ang2full(double ang){ static inline __attribute__((always_inline)) double ang2full(double ang){
if(ang < 0.) ang += 2.*M_PI; if(ang < 0.) ang += 2.*M_PI;
else if(ang > 2.*M_PI) ang -= 2.*M_PI; else if(ang > 2.*M_PI) ang -= 2.*M_PI;
return ang; return ang;
} }
// motor position to radians and back // motor position to radians and back
#define X_MOT2RAD(n) ang2half(2. * M_PI * ((double)(n)) / X_MOT_STEPSPERREV) #define X_MOT2RAD(n) ang2half(2. * M_PI * ((double)(n)) / (X_MOT_STEPSPERREV))
#define Y_MOT2RAD(n) ang2half(2. * M_PI * ((double)(n)) / Y_MOT_STEPSPERREV) #define Y_MOT2RAD(n) ang2half(2. * M_PI * ((double)(n)) / (Y_MOT_STEPSPERREV))
#define X_RAD2MOT(r) ((int32_t)((r) / (2. * M_PI) * X_MOT_STEPSPERREV)) #define X_RAD2MOT(r) ((int32_t)((r) / (2. * M_PI) * (X_MOT_STEPSPERREV)))
#define Y_RAD2MOT(r) ((int32_t)((r) / (2. * M_PI) * Y_MOT_STEPSPERREV)) #define Y_RAD2MOT(r) ((int32_t)((r) / (2. * M_PI) * (Y_MOT_STEPSPERREV)))
// motor speed in rad/s and back // motor speed in rad/s and back
#define X_MOTSPD2RS(n) (X_MOT2RAD(n) / 65536. * SITECH_LOOP_FREQUENCY) #define X_MOTSPD2RS(n) (X_MOT2RAD(n) / 65536. * (SITECH_LOOP_FREQUENCY))
#define Y_MOTSPD2RS(n) (Y_MOT2RAD(n) / 65536. * SITECH_LOOP_FREQUENCY) #define Y_MOTSPD2RS(n) (Y_MOT2RAD(n) / 65536. * (SITECH_LOOP_FREQUENCY))
#define X_RS2MOTSPD(r) ((int32_t)(X_RAD2MOT(r) * 65536. / SITECH_LOOP_FREQUENCY)) #define X_RS2MOTSPD(r) ((int32_t)(X_RAD2MOT(r) * 65536. / (SITECH_LOOP_FREQUENCY)))
#define Y_RS2MOTSPD(r) ((int32_t)(Y_RAD2MOT(r) * 65536. / SITECH_LOOP_FREQUENCY)) #define Y_RS2MOTSPD(r) ((int32_t)(Y_RAD2MOT(r) * 65536. / (SITECH_LOOP_FREQUENCY)))
// motor acceleration -//- // motor acceleration -//-
#define X_MOTACC2RS(n) (X_MOT2RAD(n) / 65536. * SITECH_LOOP_FREQUENCY * SITECH_LOOP_FREQUENCY) #define X_MOTACC2RS(n) (X_MOT2RAD(n) / 65536. * (SITECH_LOOP_FREQUENCY) * (SITECH_LOOP_FREQUENCY))
#define Y_MOTACC2RS(n) (Y_MOT2RAD(n) / 65536. * SITECH_LOOP_FREQUENCY * SITECH_LOOP_FREQUENCY) #define Y_MOTACC2RS(n) (Y_MOT2RAD(n) / 65536. * (SITECH_LOOP_FREQUENCY) * (SITECH_LOOP_FREQUENCY))
#define X_RS2MOTACC(r) ((int32_t)(X_RAD2MOT(r) * 65536. / SITECH_LOOP_FREQUENCY / SITECH_LOOP_FREQUENCY)) #define X_RS2MOTACC(r) ((int32_t)(X_RAD2MOT(r) * 65536. / (SITECH_LOOP_FREQUENCY) / (SITECH_LOOP_FREQUENCY)))
#define Y_RS2MOTACC(r) ((int32_t)(Y_RAD2MOT(r) * 65536. / SITECH_LOOP_FREQUENCY / SITECH_LOOP_FREQUENCY)) #define Y_RS2MOTACC(r) ((int32_t)(Y_RAD2MOT(r) * 65536. / (SITECH_LOOP_FREQUENCY) / (SITECH_LOOP_FREQUENCY)))
// adder time to seconds vice versa // adder time to seconds vice versa
#define ADDER2S(a) ((a) / SITECH_LOOP_FREQUENCY) #define ADDER2S(a) ((a) / (SITECH_LOOP_FREQUENCY))
#define S2ADDER(s) ((s) * SITECH_LOOP_FREQUENCY) #define S2ADDER(s) ((s) * (SITECH_LOOP_FREQUENCY))
// encoder's tolerance (ticks) // encoder's tolerance (ticks)
#define YencTOL (25.) #define YencTOL (25.)
@@ -331,7 +339,7 @@ typedef struct{
} __attribute__((packed)) SSconfig; } __attribute__((packed)) SSconfig;
uint16_t SScalcChecksum(uint8_t *buf, int len); uint16_t SScalcChecksum(uint8_t *buf, int len);
void SSconvstat(const SSstat *status, mountdata_t *mountdata, double t); void SSconvstat(const SSstat *status, mountdata_t *mountdata, struct timespec *t);
int SStextcmd(const char *cmd, data_t *answer); int SStextcmd(const char *cmd, data_t *answer);
int SSrawcmd(const char *cmd, data_t *answer); int SSrawcmd(const char *cmd, data_t *answer);
int SSgetint(const char *cmd, int64_t *ans); int SSgetint(const char *cmd, int64_t *ans);

View File

@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.0) cmake_minimum_required(VERSION 3.30)
set(PROJ PCS_create) set(PROJ PCS_create)
set(MINOR_VERSION "0") set(MINOR_VERSION "0")
set(MID_VERSION "1") set(MID_VERSION "1")

View File

@@ -321,7 +321,7 @@ static void printheader(){
} }
int main(int argc, char **argv) { int main(int argc, char **argv) {
initial_setup(); sl_init();
G = parse_args(argc, argv); G = parse_args(argc, argv);
if(G->pressure < 0.) ERRX("Pressure should be greater than zero"); if(G->pressure < 0.) ERRX("Pressure should be greater than zero");
if(G->temperature < -100. || G->temperature > 100.) ERRX("Temperature over the range -100..+100"); if(G->temperature < -100. || G->temperature > 100.) ERRX("Temperature over the range -100..+100");

View File

@@ -40,7 +40,7 @@ glob_pars const Gdefault = {
* Define command line options by filling structure: * Define command line options by filling structure:
* name has_arg flag val type argptr help * name has_arg flag val type argptr help
*/ */
static myoption cmdlnopts[] = { static sl_option_t cmdlnopts[] = {
// set 1 to param despite of its repeating number: // set 1 to param despite of its repeating number:
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")}, {"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")},
{"10m", NO_ARGS, NULL, 't', arg_int, APTR(&G.for10m), _("make output suitable for 10-micron mount")}, {"10m", NO_ARGS, NULL, 't', arg_int, APTR(&G.for10m), _("make output suitable for 10-micron mount")},
@@ -68,10 +68,10 @@ static myoption cmdlnopts[] = {
glob_pars *parse_args(int argc, char **argv){ glob_pars *parse_args(int argc, char **argv){
void *ptr = memcpy(&G, &Gdefault, sizeof(G)); assert(ptr); void *ptr = memcpy(&G, &Gdefault, sizeof(G)); assert(ptr);
// format of help: "Usage: progname [args]\n" // format of help: "Usage: progname [args]\n"
change_helpstring(_("Version: " PACKAGE_VERSION "\nUsage: %s [args] FITS_files\nMake PCS list for equatorial mount\n\tWhere args are:\n")); sl_helpstring(_("Version: " PACKAGE_VERSION "\nUsage: %s [args] FITS_files\nMake PCS list for equatorial mount\n\tWhere args are:\n"));
// parse arguments // parse arguments
parseargs(&argc, &argv, cmdlnopts); sl_parseargs(&argc, &argv, cmdlnopts);
if(help) showhelp(-1, cmdlnopts); if(help) sl_showhelp(-1, cmdlnopts);
G.nfiles = argc; G.nfiles = argc;
G.infiles = MALLOC(char*, argc); G.infiles = MALLOC(char*, argc);
for(int i = 0; i < argc; i++){ for(int i = 0; i < argc; i++){

View File

@@ -0,0 +1,59 @@
# run `make DEF=...` to add extra defines
PROGRAM := invertercmd
LDFLAGS := -fdata-sections -ffunction-sections -Wl,--gc-sections -Wl,--discard-all
LDFLAGS += -lusefull_macros
SRCS := $(wildcard *.c)
DEFINES := $(DEF) -D_GNU_SOURCE -D_XOPEN_SOURCE=1111
OBJDIR := mk
CFLAGS += -O2 -Wall -Wextra -Wno-trampolines
OBJS := $(addprefix $(OBJDIR)/, $(SRCS:%.c=%.o))
DEPS := $(OBJS:.o=.d)
TARGFILE := $(OBJDIR)/TARGET
CC = gcc
#TARGET := RELEASE
ifeq ($(shell test -e $(TARGFILE) && echo -n yes),yes)
TARGET := $(file < $(TARGFILE))
else
TARGET := RELEASE
endif
ifeq ($(TARGET), DEBUG)
.DEFAULT_GOAL := debug
endif
release: CFLAGS += -flto
release: LDFLAGS += -flto
release: $(PROGRAM)
debug: CFLAGS += -DEBUG -Werror
debug: TARGET := DEBUG
debug: $(PROGRAM)
$(TARGFILE): $(OBJDIR)
@echo -e "\t\tTARGET: $(TARGET)"
@echo "$(TARGET)" > $(TARGFILE)
$(PROGRAM) : $(TARGFILE) $(OBJS)
@echo -e "\t\tLD $(PROGRAM)"
$(CC) $(LDFLAGS) $(OBJS) -o $(PROGRAM)
$(OBJDIR):
@mkdir $(OBJDIR)
ifneq ($(MAKECMDGOALS),clean)
-include $(DEPS)
endif
$(OBJDIR)/%.o: %.c
@echo -e "\t\tCC $<"
$(CC) -MD -c $(LDFLAGS) $(CFLAGS) $(DEFINES) -o $@ $<
clean:
@echo -e "\t\tCLEAN"
@rm -rf $(OBJDIR) 2>/dev/null || true
xclean: clean
@rm -f $(PROGRAM)
.PHONY: clean xclean

Binary file not shown.

View File

@@ -0,0 +1 @@
Serial communications with SILA inverters

View File

@@ -0,0 +1,414 @@
/*
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <ctype.h>
#include <stdio.h>
#include <string.h>
#include <usefull_macros.h>
static sl_tty_t *dev = NULL;
static const char *wro = "(wrong parameter)";
typedef struct{
int help;
char *path;
char *customcmd;
char *getstatus;
int baudrate;
int status;
int settershelp;
} globopts;
typedef struct{
int all;
int help;
int rating;
int flag;
int status;
int mode;
int warning;
int deflt;
int bateq;
} statusinfo;
typedef void (*parsefn)(const char *answer);
static globopts G = {
.path = "/dev/ttyS0",
.baudrate = 2400,
};
static statusinfo S = {0};
static sl_option_t opts[] = {
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&G.help), "show this help"},
{"devpath", NEED_ARG, NULL, 'd', arg_string, APTR(&G.path), "path to device (default: /dev/ttyS0)"},
{"baudrate",NEED_ARG, NULL, 'b', arg_int, APTR(&G.baudrate), "baudrate (default: 2400)"},
{"cmd", NEED_ARG, NULL, 'c', arg_string, APTR(&G.customcmd), "custom command to send"},
{"status", NEED_ARG, NULL, 's', arg_string, APTR(&G.getstatus), "get status: comma-separated options (type 'help' for options)"},
{"helpsetters",NO_ARGS, NULL, 0, arg_int, APTR(&G.settershelp),"show help about setters"},
end_option
};
static sl_suboption_t sopts[] = {
{"all", NO_ARGS, arg_int, APTR(&S.all)},
{"help", NO_ARGS, arg_int, APTR(&S.help)},
{"rating", NO_ARGS, arg_int, APTR(&S.rating)},
{"flag", NO_ARGS, arg_int, APTR(&S.flag)},
{"status", NO_ARGS, arg_int, APTR(&S.status)},
{"mode", NO_ARGS, arg_int, APTR(&S.mode)},
{"warning", NO_ARGS, arg_int, APTR(&S.warning)},
{"default", NO_ARGS, arg_int, APTR(&S.deflt)},
{"bateq", NO_ARGS, arg_int, APTR(&S.bateq)},
end_suboption
};
static void gettershelp(){
fprintf(stderr, "Status parameters:\n");
fprintf(stderr, "all - show all information available\n");
fprintf(stderr, "rating - device rating information (QPIRI)\n");
fprintf(stderr, "flag - device flag status (QFLAG)\n");
fprintf(stderr, "status - device general status parameters (QPIGS)\n");
fprintf(stderr, "mode - device mode (QMOD)\n");
fprintf(stderr, "warning - warning status (QPIWS)\n");
fprintf(stderr, "default - default settings (QDI)\n");
fprintf(stderr, "bateq - battery equalization parameters (QBEQI)\n");
// fprintf(stderr, "\n");
}
static uint8_t *cal_crc(const char *cmd, int len){
static uint8_t CRC[4]; // 0 - hi, 1 - low, four bytes for quick zeroing
if(!cmd || len < 1) return 0;
const uint16_t crc_table[16] = {
0x0000,0x1021,0x2042,0x3063,0x4084,0x50a5,0x60c6,0x70e7,
0x8108,0x9129,0xa14a,0xb16b,0xc18c,0xd1ad,0xe1ce,0xf1ef
};
*((uint32_t*)CRC) = 0;
uint16_t crc = 0;
uint8_t *ptr = (uint8_t*)cmd;
while(len--){
uint8_t da = ((uint8_t)(crc >> 8)) >> 4;
crc <<= 4;
crc ^= crc_table[da ^ (*ptr >> 4)];
da = ((uint8_t)(crc >> 8)) >> 4;
crc <<= 4;
crc ^= crc_table[da ^ (*ptr & 0x0f)];
ptr++;
}
uint8_t bCRCLow = crc;
uint8_t bCRCHign= (uint8_t)(crc >> 8);
if(bCRCLow==0x28 || bCRCLow==0x0d || bCRCLow==0x0a) ++bCRCLow;
if(bCRCHign==0x28 || bCRCHign==0x0d || bCRCHign==0x0a) ++bCRCHign;
CRC[0] = bCRCHign; CRC[1] = bCRCLow; CRC[2] = '\r';
DBG("CRC: 0x%02X 0x%02X 0x%02X", CRC[0], CRC[1], CRC[2]);
return CRC;
}
static int sendcmd(const char *cmd){
if(!cmd || !*cmd || !dev) return 0;
int len = strlen(cmd);
uint8_t *CRC = cal_crc(cmd, len);
#ifdef EBUG
printf("COMMAND: ");
for(int i = 0; i < len; ++i) printf("0x%02X ", cmd[i]);
printf("\n");
#endif
if(sl_tty_write(dev->comfd, cmd, len)){
WARN("Can't write command");
return 0;
}
if(sl_tty_write(dev->comfd, (const char*) CRC, 3)){
WARN("Can't write CRC & STREND");
return 0;
}
DBG("Command %s sent", cmd);
return 1;
}
static char *rd(){
if(!dev) return NULL;
int got = sl_tty_read(dev);
if(got < 0) ERR("Can't read");
DBG("got %d bytes, buflen: %zd", got, dev->buflen);
if(dev->buflen < 3) return NULL;
uint8_t *CRC = cal_crc(dev->buf, dev->buflen - 3);
DBG("GOT CRC: 0x%02X 0x%02X", (uint8_t)dev->buf[dev->buflen-3], (uint8_t)dev->buf[dev->buflen-2]);
if(CRC[0] != (uint8_t)dev->buf[dev->buflen-3] || CRC[1] != (uint8_t)dev->buf[dev->buflen-2]){
WARNX("Bad CRC");
return NULL;
}
char *r = dev->buf + 1;
dev->buf[dev->buflen-3] = 0;
return r;
}
// 230.0 13.0 230.0 50.0 13.0 3000 3000 24.0 23.0 21.0 28.2 27.0 0 25 50 0 0 2 - 01 1 0 27.0 0 0
// b c d e f h i j1 k1 j2 k2 l o1 p1q0 o2p2q2r s t u v w x
static void ratingparsing(const char *str){
float b, c, d, e, f, j1, k1, j2, k2, l, v;
int h, i, o1, p1, q, o2, p2, q2, s, t, u, w, x;
char r;
int N = sscanf(str, "%f %f %f %f %f %d %d %f %f %f %f %f %d %d %d %d %d %d %c %d %d %d %f %d %d",
&b, &c, &d, &e, &f, &h, &i, &j1, &k1, &j2, &k2, &l, &o1, &p1, &q, &o2, &p2, &q2, &r, &s, &t,
&u, &v, &w, &x);
if(N != 25){ WARNX("Got not full answer (%d instead of 25): '%s'", N, str); return; }
printf("Grid rating voltage: %g\nGrid rating current: %g\nAC optuput rating voltage: %g\n", b, c, d);
printf("AC output rating frequency: %g\nAC output rating current: %g\nAC output rating apparent power: %d\n", e, f, h);
printf("AC output rating active power: %d\nBattery rating voltage: %g\nBattery recharge voltage: %g\n", i, j1, k1);
printf("Battery undervoltage: %g\nBattery bulk voltage: %g\nBattery float voltage: %g\n", j2, k2, l);
static const char *types[] = {"AGM", "Flooded", "User"};
printf("Battery type: %s\n", (o1 > -1 && o1 < 3) ? types[o1] : wro);
printf("Current max AC charging current: %d\nCurrent max charging current: %d\n", p1, q);
printf("Input voltage range: %s\n", o2 ? "UPS" : "Appliance");
static const char *oprio[] = {"Utility", "Solar", "SBU"};
printf("Output source priority: %s\n", (p2 > -1 && p2 < 3) ? oprio[p2] : wro);
static const char *sprio[] = {"Utility", "Solar", "Solar+Utility", "Only solar charging"};
printf("Charger source priority: %s\n", (q2 > -1 && q2 < 4) ? sprio[q2] : wro);
printf("Parallel max num: %c\n", r);
printf("Machine type: ");
switch(s){
case 0: printf("Grid tie"); break;
case 1: printf("Off grid"); break;
case 10: printf("Hybrid"); break;
default: printf("%s", wro);
}
printf("\nTopology: %s\n", (t) ? "transformer" : "transformerless");
printf("Output mode: %d\nBattery redischarge voltage: %g\n", u, v);
printf("PV OK condition for parallel: %s\n", (w) ? "Only all connected" : "At least one connected");
printf("PV power balance: %s\n", (x) ? "Sum of powers" : "Max charged current");
}
static const char *DEflags = "abjkuvxyz";
static const char *DEmeanings[] = {
"buzzer", "bypass", "power saving", "LCD display escape 1min", "overload restart",
"over temperature restart", "backlight on", "alarm on interrupt", "fault code record",
NULL
};
static void flagparsing(const char *str){
char c;
int first = 0;
while((c = *str++)){
if(c == 'D'){ green("\nDISABLED: "); first = 1; }
else if(c == 'E'){ red("ENABLED: "); first = 1; }
else{
const char *field = "unknown";
for(int i = 0; DEflags[i]; ++i){
if(DEflags[i] == c){ field = DEmeanings[i]; break; }
}
printf("%s%s", (first) ? "" : ", ", field);
first = 0;
}
}
printf("\n");
}
/**
* @brief showflags - display bitflags
* @param flags - string with flags ('1' / '0')
* @param meaning - array with meaning of each flag, starting from H bit, i.e. meaning[0] is lesser bit
* @param nfields - strlen of flags (or less), H first
*/
static void showflags(const char *flags, const char **meaning, int nfields){
for(int i = 0; i < nfields; ++i){
if(!meaning[i]) continue;
printf("\t%s: ", meaning[i]);
if(flags[i] == '1') red("on/yes\n");
else green("off/no\n");
}
}
// 230.0 50.0 232.0 50.0 0000 0000 000 409 26.99 000 100 0489 0000 000.0 00.00 00000 10011101 00 03 00000 100
// b c d e f g h i j k o t e1 u w p x [unknown shit]
static void statusparsing(const char *str){
float b, c, d, e, j, u, w;
int f, g, h, i, k, o, t, e1, p, S, H, I;
char x[9], T[4];
int N = sscanf(str, "%f %f %f %f %d %d %d %d %f %d %d %d %d %f %f %d %8s %d %d %d %3s",
&b, &c, &d, &e, &f, &g, &h, &i, &j, &k, &o, &t, &e1, &u, &w, &p, x, &S, &H, &I, T);
DBG("N=%d", N);
if(N >= 17){
printf("Grid voltage: %g\nGrid frequency: %g\nAC output voltage: %g\nAC output frequency: %g\n",
b, c, d, e);
printf("AC output apparent power: %d\nAC output active power: %d\nOutput load percent: %d\n", f, g, h);
printf("Bus voltage: %d\nBattery voltage: %g\nBattery charging current: %d\nBattery capacity: %d\n", i, j, k, o);
printf("Inverter heat sink temperature: %d\nPV input current for battery: %d\nPV input voltage 1: %g\n", t, e1, u);
printf("Battery voltage from SCC: %g\nBattery discharge current: %d\nDevice status:\n", w, p);
static const char *sf[] = {"SBU priority version", "configuration changed", "SCC firmware updated",
"Load status", "Steady batt voltage while charging", "Charging", "SCC charging", "AC charging"};
showflags(x, sf, 8);
if(N > 17){
printf("Battery offset for fans on: %d\nEEPROM version: %d\nPV charging power: %d\n", S, H, I);
printf("Inverter status:\n");
static const char *is[] = {"Charging to floating mode", "Switch", "Dustproof installed"};
showflags(T, is, 3);
}
}else WARNX("Get not full answer: %d instead of 17", N);
}
static void modeparsing(const char *str){
printf("Device mode: ");
switch(*str){
case 'B': printf("Battery"); break;
case 'F': printf("Fault"); break;
case 'H': printf("Power saving"); break;
case 'L': printf("Line"); break;
case 'P': printf("Power on"); break;
case 'S': printf("Standby"); break;
default: printf("Unknown");
}
printf("\n");
}
static void warningparsing(const char *str){
int l = strlen(str);
if(l < 32) WARNX("Non-full status! Data could be wrong");
static const char *wmsgs[] = {
NULL, "Inverter fault", "Bus over", "Bus under", "Bus soft fail", "Line fail", "OPV short",
"Inv voltage too low", "Inv voltage too high", "Over temperature", "Fan locked", "Battery voltage high",
"Battery low alarm", "Overcharge", "Battery under shutdown", "Battery derating", "Overload", "EEPROM fault",
"Inverter overcurrent", "Inverter soft fail", "Self test fail", "OP DC voltage over", "Bat open",
"Current sensor fail", "Battery short", "Power limit", "PV voltage high", "MPPT overload fault",
"MPPT overload warning", "Battery too low to charge", NULL, NULL
};
printf("Warning status:\n");
showflags(str, wmsgs, l);
}
static const char *endis(int val){
return (val) ? COLOR_RED "enable" COLOR_OLD : COLOR_GREEN "disable" COLOR_OLD;
}
// 230.0 50.0 0025 21.0 27.0 28.2 23.0 50 0 0 2 0 1 0 0 0 1 1 1 0 1 0 27.0 0 0 ()
// b c d e f g h i j k l m n o p q r s t u v w y x z a
static void defaultparsing(const char *str){
float b, c, e, f, g, h, y;
int d, i, j, k, l, m, n, o, p, q, r, s, t, u, v, w, x, z, a;
int N = sscanf(str, "%f %f %d %f %f %f %f %d %d %d %d %d %d %d %d %d %d %d %d %d %d %d %f %d %d %d",
&b, &c, &d, &e, &f, &g, &h, &i, &j, &k, &l, &m, &n, &o, &p, &q, &r, &s, &t, &u, &v, &w, &y, &x, &z, &a);
if(N < 25){WARNX("Wrong data format: %d fields instead of 25", N); return;}
printf("AC output voltage: %g\nAC output frequency: %g\nMax AC charging current: %d\n", b, c, d);
printf("Battery undervoltage: %g\nCharging float voltage: %g\nCharging bulk voltage: %g\n", e, f, g);
printf("Battery default recharge voltage: %g\nMax charging current: %d\nAC input voltage range: %s\n", h, i, (j) ? "UPS" : "appliance");
printf("Output source priority: %s\nCharger source priority: %s\n", (k) ? "solar first": "utility first", (l) ? "solar first" : "utility first");
printf("Battery type: %s\nBuzzer: %s\nPover saving: %s\n", (m) ? "other" : "AGM", endis(n), endis(o));
printf("Overload restart: %s\nOver temperature restart: %s\n", endis(p), endis(q));
printf("Backlight: %s\nAlarm on interrupt: %s\nFault code record: %s\n", endis(r), endis(s), endis(t));
printf("Overload bypass: %s\nLCD timeout escape: %s\nOutput mode: %d\n", endis(u), endis(v), w);
printf("Battery re-discharge voltage: %g\nPV OK condition for parallel: %s\n", y, (x) ? "all" : "any");
printf("PV power balance: %s\n", (z) ? "?" : "PV max current is charged current");
if(N == 26) printf("Max charging time @ CV stage: %s\n", (a) ? "?" : "automatically");
}
// 0 060 030 050 030 29.20 000 120 0 0000
// b c d e f g h i j k
static void equparsing(const char *str){
float g;
int b, c, d, e, f, h, i, j, k;
int N = sscanf(str, "%d %d %d %d %d %f%d %d %d %d", &b, &c, &d, &e, &f, &g, &h, &i, &j, &k);
if(N != 10){ WARNX("Not enougn parameters: got %d instead of 10\n", N); return; }
printf("Equalization: %s\n", endis(b));
printf("Eq. time: %d minutes\nEq. period: %d days\nEq. max current: %d\n", c, d, e);
printf("Eq. voltage: %g\nEq. over time: %d minutes\nEq. active status: %d\n", g, i, j);
}
static void printpar(const char *str){
printf("%s\n", str);
}
static void runparsing(const char *cmd, parsefn f){
if(sendcmd(cmd)){
char *got = rd();
if(got && *got){
f(got);
printf("\n");
} else red("Can't get data\n\n");
}
}
static void showstatus(){
green("\nModel name: "); runparsing("QMN", printpar);
if(S.all || S.rating) runparsing("QPIRI", ratingparsing);
if(S.all || S.flag) runparsing("QFLAG", flagparsing);
if(S.all || S.status) runparsing("QPIGS", statusparsing);
if(S.all || S.mode) runparsing("QMOD", modeparsing);
if(S.all || S.warning) runparsing("QPIWS", warningparsing);
if(S.all || S.deflt) runparsing("QDI", defaultparsing);
if(S.all || S.bateq) runparsing("QBEQI", equparsing);
}
static void showsettershelp(){
printf("\n\n");
red("Be carefull with setters! Think twice before changing something!!!\n\n");
printf("Here are setters...\n");
printf("PEx - enable status / DEx - disable status, where 'x':\n");
for(int i = 0; DEflags[i]; ++i) printf("\t%c - %s\n", DEflags[i], DEmeanings[i]);
printf("PF - set all control parameters to default\n");
printf("MCHGCx - max charging current (Amps)\n");
printf("MUCHGCx - utility max charging current\n");
printf("Fx - invertere output frequency\n");
printf("POPx - output source priority (0 - utility, 1 - solar, 2 - SBU)\n");
printf("PBCVx - battery re-charge voltage\n");
printf("PBDVx - battery re-discharge voltage\n");
printf("PCPx - inverter charging priority (0-3: utility first/solar first/solar+utility/solar only\n");
printf("PGRx - inverter grid voltage range (0 - appliance, 1 - UPS)\n");
printf("PBTx - battery type (0 - AGM, 1 - flooded)\n");
printf("PSDVx - battery cut-off voltage\n");
printf("PCVVx - CV (constant voltage) charging voltage\n");
printf("PBFTx - battery float charging voltage\n");
printf("PBEQEx - enable (1) or disable (0) battery equalization\n");
printf("PBEQT x - battery equalization time (minutes)\n");
printf("PBEQPx - battery equalization period (days)\n");
printf("PBEQVx - battery equalization voltage\n");
printf("PBEQOTx - battery equalization overtime (minutes)\n");
printf("PBEQAx - activate (1) or disactivate (0) battery equalization now\n");
printf("PCVTx - max charging time an CV stage\n");
printf("\n\nAnd some getters that aren't in `status` variants:\n");
printf("QID - inverter's serial\nQVFW - firmware version\nQMCHGCR - max charging currents available\n");
printf("QMUCHGCR - max utility charging currents available\n");
printf("\n\n");
}
int main(int argc, char **argv){
sl_init();
sl_parseargs(&argc, &argv, opts);
if(G.help) sl_showhelp(-1, opts);
if(!G.path || G.baudrate < 1) ERRX("Need device path and baudrate");
dev = sl_tty_new(G.path, G.baudrate, 128);
if(!dev) ERR("Can't init serial device");
dev = sl_tty_open(dev, 1);
if(!dev) ERR("Can't open %s", G.path);
if(sl_tty_tmout(100000)) WARNX("Can't set timeout");
DBG("bufsz: %zd", dev->bufsz);
if(G.getstatus){
if(!sl_get_suboption(G.getstatus, sopts) || S.help){
gettershelp();
return 1;
}
showstatus();
}
if(G.customcmd){
green("Try to send '%s'\n", G.customcmd);
if(sendcmd(G.customcmd)){
char *got = rd();
if(got) printf("Get data: '%s'\n", got);
}
}
sl_tty_close(&dev);
if(G.settershelp) showsettershelp();
return 0;
}

View File

@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.0) cmake_minimum_required(VERSION 3.30)
set(PROJ chkweather) set(PROJ chkweather)
set(MINOR_VERSION "1") set(MINOR_VERSION "1")
set(MID_VERSION "0") set(MID_VERSION "0")

View File

@@ -40,7 +40,7 @@ glob_pars const Gdefault = {
* Define command line options by filling structure: * Define command line options by filling structure:
* name has_arg flag val type argptr help * name has_arg flag val type argptr help
*/ */
static myoption cmdlnopts[] = { static sl_option_t cmdlnopts[] = {
// set 1 to param despite of its repeating number: // set 1 to param despite of its repeating number:
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")}, {"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")},
{"speed", NEED_ARG, NULL, 's', arg_int, APTR(&G.speed), _("baudrate (default: 9600)")}, {"speed", NEED_ARG, NULL, 's', arg_int, APTR(&G.speed), _("baudrate (default: 9600)")},
@@ -59,10 +59,10 @@ static myoption cmdlnopts[] = {
glob_pars *parse_args(int argc, char **argv){ glob_pars *parse_args(int argc, char **argv){
void *ptr = memcpy(&G, &Gdefault, sizeof(G)); assert(ptr); void *ptr = memcpy(&G, &Gdefault, sizeof(G)); assert(ptr);
// format of help: "Usage: progname [args]\n" // format of help: "Usage: progname [args]\n"
change_helpstring(_("Usage: %s [args]\n\n\tWhere args are:\n")); sl_helpstring(_("Usage: %s [args]\n\n\tWhere args are:\n"));
// parse arguments // parse arguments
parseargs(&argc, &argv, cmdlnopts); sl_parseargs(&argc, &argv, cmdlnopts);
if(help) showhelp(-1, cmdlnopts); if(help) sl_showhelp(-1, cmdlnopts);
if(argc > 0){ if(argc > 0){
WARNX("Wrong arguments:\n"); WARNX("Wrong arguments:\n");
for(int i = 0; i < argc; i++) for(int i = 0; i < argc; i++)

View File

@@ -51,28 +51,28 @@ static int getpar(char *string, double *Val, char *Name){
int main(int argc, char **argv){ int main(int argc, char **argv){
glob_pars *G = NULL; // default parameters see in cmdlnopts.c glob_pars *G = NULL; // default parameters see in cmdlnopts.c
initial_setup(); sl_init();
G = parse_args(argc, argv); G = parse_args(argc, argv);
TTY_descr *dev = new_tty(G->ttyname, G->speed, 64); sl_tty_t *dev = sl_tty_new(G->ttyname, G->speed, 64);
if(!dev) return 1; if(!dev) return 1;
size_t got, L = 0; size_t got, L = 0;
char buff[BUFLEN], *ptr = buff; char buff[BUFLEN], *ptr = buff;
int errctr = 0; int errctr = 0;
for(; errctr < ERRCTR_MAX; ++errctr){ for(; errctr < ERRCTR_MAX; ++errctr){
if(!tty_open(dev, 1)){ if(!sl_tty_open(dev, 1)){
sleep(1); sleep(1);
continue; continue;
} }
while(read_tty(dev)); // clear buffer while(sl_tty_read(dev)); // clear buffer
if(write_tty(dev->comfd, "?U\r\n", 3)){ if(sl_tty_write(dev->comfd, "?U\r\n", 3)){
WARNX("write_tty()"); WARNX("write_tty()");
continue; continue;
} }
double t0 = dtime(); double t0 = sl_dtime();
while(dtime() - t0 < 10.){ // timeout - 10s while(sl_dtime() - t0 < 10.){ // timeout - 10s
got = read_tty(dev); got = sl_tty_read(dev);
if(got == 0) continue; if(got == 0) continue;
t0 = dtime(); t0 = sl_dtime();
if(L + got > BUFLEN - 1) break; if(L + got > BUFLEN - 1) break;
L += got; L += got;
buff[L] = 0; buff[L] = 0;
@@ -92,8 +92,8 @@ int main(int argc, char **argv){
continue; continue;
}else break; }else break;
} }
while(read_tty(dev)); while(sl_tty_read(dev));
close_tty(&dev); sl_tty_close(&dev);
if(errctr == ERRCTR_MAX){ if(errctr == ERRCTR_MAX){
ERRX("No connection to meteostation"); ERRX("No connection to meteostation");
} }

View File

@@ -4,7 +4,7 @@ A="90:00:00"
H="45:00:00" H="45:00:00"
function sendcmd(){ function sendcmd(){
echo $1 | nc 192.168.70.33 10001 -q10 echo $1 | nc localhost 10001 -q10
} }
sendcmd ":Sz${A}#" sendcmd ":Sz${A}#"

View File

@@ -0,0 +1,20 @@
#!/bin/bash
#
# $1 - scaling factor (in percents) of the image
#
scale=50
if [ $# -gt 0 ]; then
scale=$1
fi
unset http_proxy
clear
while [[ 1 ]]; do
tput cup 0 0
curl -s http://zarch.sao.ru/webcam/mirat_allsky.cgi | magick - -colors 256 +dither -normalize -resize $scale% sixel:-
# sleep 30s
sleep 5s
done

View File

@@ -0,0 +1,114 @@
#!/bin/bash
#
# $1 - scaling factor (in percents) of the image
#
function get_val {
echo $(echo $1 | cut -d "=" -f 2 | cut -d "." -f 1)
}
white_col="\e[97m"
red_col="\e[1m\e[31m"
end_col="\e[0m"
last_row=0
scale=50
if [ $# -gt 0 ]; then
scale=$1
fi
unset http_proxy
im_sleep=20 # in secs
info_sleep=180 # in secs
n_info=$((info_sleep/im_sleep))
clear
while [[ 1 ]]; do
# weather info
m_old=($(curl 192.168.70.33:12345 2>/dev/null)// / )
rain=${m_old[0]}
clouds=${m_old[1]}
temp=${m_old[2]}
m_new=($(curl localhost:3333/stat3600 2>/dev/null | sed 's/[\x01-\x1F\x7F]//g')// / )
windmax=${m_new[0]}
m_new=($(curl localhost:3333 2>/dev/null | sed 's/[\x01-\x1F\x7F]//g')// / )
wind=${m_new[0]}
humi=${m_new[4]}
rain_col=$white_col
clouds_col=$white_col
humi_col=$white_col
wind_col=$white_col
wind_max_col=$white_col
let rain_flag=$(get_val $rain)
if [[ $rain_flag -eq 1 ]]; then
rain_col=$red_col
fi
let clouds_val=$(get_val $clouds)
if [[ $clouds_val -le 1500 ]]; then
clouds_col=$red_col
fi
let humi_val=$(get_val $humi)
if [[ $humi_val -ge 90 ]]; then
humi_col=$red_col
fi
let wind_val=$(get_val $wind)
if [[ $wind_val -ge 10 ]]; then
wind_col=$red_col
fi
let wind_max_val=$(get_val $windmax)
if [[ $wind_max_val -ge 10 ]]; then
wind_max_col=$red_col
fi
ncols=`tput cols`
start_col=$((ncols-25))
tput cup $last_row $start_col
# echo -e "\e[4m`date`:\e[0m"
echo -e "\e[4m`date +'%F %T'`:\e[0m"
((++last_row))
tput cup $last_row $start_col
echo -e "$clouds_col$clouds $rain_col($rain)$end_col"
((++last_row))
tput cup $last_row $start_col
# echo -e "$temp $humi_col($humi)$end_col"
temp_val=`printf "%.1f" ${temp#*=}`
echo -e "Temp=$temp_val, ${humi_col}Hum=$humi_val%$end_col"
((++last_row))
tput cup $last_row $start_col
# echo -e "$wind_col$wind $wind_max_col($windmax @hour)$end_col\n"
wind_max_val=`printf "%.1f" ${windmax#*=}`
echo -e "$wind_col$wind $wind_max_col(Max=$wind_max_val/hour)$end_col\n"
IFS='[;' read -p $'\e[6n' -d R -rs _ last_row col _
# allsky image
for i in `seq $n_info`; do
tput cup 0 0
curl -s http://zarch.sao.ru/webcam/omea_allsky.cgi | magick - -colors 256 -normalize +dither -resize $scale% sixel:-
# curl -s http://zarch.sao.ru/webcam/mirat_allsky.cgi | magick - -colors 256 -resize $scale% sixel:-
sleep ${im_sleep}s
done
done

View File

@@ -0,0 +1,18 @@
#!/bin/bash
#
# $1 - directory to be copied
#
RDIR="/home/obs/robotel1_2025"
# copy non-FITS files
tar c --exclude='*.fit' --exclude='*shit*' $1 | ssh obs@roboserv "tar x -C $RDIR"
#tar c --exclude='*.fit' --exclude='*shit*' $1 | ssh obs@roboserv "tar x -C /home/obs/robotel1_2023"
# copy FITS files and XZ-ing it on remote server
CMD='sh -c "xz -6e -T0 - > $TAR_FILENAME.xz"'
tar c $1/*.fit | ssh obs@roboserv "cd $RDIR; tar x --to-command='$CMD'"
#tar c $1/*.fit | ssh obs@roboserv "cd /home/obs/robotel1_2023; tar x --to-command='$CMD'"
ssh obs@roboserv "cd $RDIR; tar c $1 | ssh data@robostorage 'tar x -C /mnt/ARCHIVE/ROBOTEL1/'"

View File

@@ -0,0 +1,33 @@
#!/bin/bash
A="01:48:38"
H="01:13:29"
function sendcmd(){
echo $1 | nc localhost 10001 -q10 || (echo "Can't connect" >&2; exit 1)
}
#lower limit is 0
sendcmd ":So0#"
sendcmd ":Sz${A}#"
sendcmd ":Sa${H}#"
sendcmd ":MA#" # || exit 1
errctr=0
while true; do
sleep 2
ANS=$(sendcmd ":Gstat#")
if [ "x$ANS" == "x" ]; then
[[ $((++errctr)) < 5 ]] && continue
echo "No connection to server" >&2
exit 1
fi
echo $ANS
[ $ANS == "0#" -o $ANS == "7#" ] && break
done
# stop tracking
sendcmd ":AL#"
echo -e "\n\nTelescope parked\n"

View File

@@ -0,0 +1,33 @@
#!/bin/bash
A="00:00:00"
H="2:00:00"
function sendcmd(){
echo $1 | nc localhost 10001 -q10 || (echo "Can't connect" >&2; exit 1)
}
#lower limit is 0
sendcmd ":So0#"
sendcmd ":Sz${A}#"
sendcmd ":Sa${H}#"
sendcmd ":MA#" # || exit 1
errctr=0
while true; do
sleep 2
ANS=$(sendcmd ":Gstat#")
if [ "x$ANS" == "x" ]; then
[[ $((++errctr)) < 5 ]] && continue
echo "No connection to server" >&2
exit 1
fi
echo $ANS
[ $ANS == "0#" -o $ANS == "7#" ] && break
done
# stop tracking
sendcmd ":AL#"
echo -e "\n\nTelescope parked\n"

View File

@@ -0,0 +1,165 @@
#!/bin/bash
RA="17:17:08.86"
DEC="+67:57:11.4"
OBJ="GALEX171708.5"
EXPTIME=31000
FLATTIME=40000
OBS="Fatkhullin T.A."
BADWEATHER=1300
DATEEND=$(sunrise 14)
# focus each N seconds
FOCUST=7200
FNO=1
FDATE=0
#
# NOTE: THIS IS A NEW VERSION OF THE OBSERVATION SCRIPT!
# CHAGLELOG:
# Oct 2024: replace focussing algorithm (T. Fatkhullin)
# At the night start the first focussing run
# uses of two-step algorithm:
# 1) rough focus astimation along full season-to-season
# focus range (as it was implemented in the old obs. script)
# 2) precise focussing along narrow range computed from
# previous rough estimation
# Next focussing runs compute range from the current focus value.
# (new function 'focustel_new')
#
# May 2025: rewrite detection of running this script process (T. Fatkhullin)
# (use of '-c' commandline option for 'pgrep' command)
function focustel_new(){
rm focus*.fit 2>/dev/null
echo "Focussing..."
let fno=$1
if [[ $fno -gt 1 ]]; then
let curr_foc=`fli_control | tail -n 5 | head -n 1 | cut -d "=" -f 2`
let lowf=$curr_foc-1500
let highf=$curr_foc+1500
focus_seq_FLI.py -v -c focus$(printf "%02d" $1).jpg $lowf $highf 500
if [[ $? -ne 0 ]]; then
echo -e "\nFOCUSSING SCRIPT RETURNED: $?"
echo -e "SOMETHING WAS WRONG IN FOCUSSING SEQUENCE!!! SET FOCUS TO PREVIOUS VALUE!!\n"
fli_control -g $curr_foc
fi
else
focus_seq_FLI.py --guess -v -N 7 -c focus$(printf "%02d" $1).jpg 47000 60000 500
fi
FDATE=$(date +%s)
}
function sendcmd(){
echo $1 | nc 192.168.70.33 10001 -q10
}
function point_tel(){
touch lastpointing
send_coords -r $1 -d $2
}
#c=$(pgrep run_full | wc -l)
# $ will run another run_full, so c=2 for single run
#if [[ $c -gt 1 ]]; then
# echo "Another process is running; exiting"
# exit 1
#fi
if [[ $(pgrep -c run_full) -gt 1 ]]; then
echo "Another process is running! Exit!"
exit 1
fi
export http_proxy=""
# set lower limit to 5degr
send_command2mount ":So5#"
echo "Time diff: $(($DATEEND-$(date +%s)))"
if [ $(($DATEEND-$(date +%s))) -lt 3600 ]; then
echo "There's less an hour for observation!"
exit 2
fi
if [ $(($DATEEND-$(date +%s))) -gt 53200 ]; then
echo "There's more than 12 hours till closing, check script data!"
exit 3
fi
#STARTobs
#send_coords
#echo "Wait a little"
#sleep 10
echo "GoTo object: ${RA} ${DEC}"
send_coords -r${RA} -d${DEC}
echo "Start taking object"
badweather=0
while true; do
now=$(date +%s)
ANS=$(curl localhost:55555/status 2>/dev/null)
echo "Dome status: $ANS"
if [ $ANS != "opened" ]; then
echo "Closed"
curl localhost:55555/weather 2>/dev/null > DomeClosed
break;
fi
chkweather ${BADWEATHER} > lastweather && badweather=0 || badweather=$((badweather+1))
[ $badweather -gt 5 ] && break
[ -f stopobs ] && break
[ -f exitjob ] && exit 0
if [ "$now" -lt "$DATEEND" ]; then
est=$(sendcmd ":Gmte#"|sed -e 's/^0*//' -e 's/#//')
echo -e "\n\n\n\n\nEstimated time to flip: $est minutes"
if [[ ("x$est" == "x") || ($est -lt 3) ]]; then
point_tel "${RA}" "${DEC}"
continue
fi
ST=$(send_coords | awk '{print $4}')
[ "x$ST" == "x" ] && break
if [ $ST -ne "0" ]; then
point_tel "${RA}" "${DEC}"
continue
else
[ $(($(date +%s) - $FDATE)) -gt $FOCUST ] && focustel_new $((FNO++))
# [ $(($(date +%s) - $FDATE)) -gt $FOCUST ] && focustel $((FNO++))
preflash
fli_control -r /tmp/10micron.fitsheader -x $EXPTIME -N "${OBS}" -O "${OBJ}" "$OBJ"
fi
else
break
fi
done
echo "Dome closed @ $(date)" >> closed
curl localhost:55555/close
relay_manage -s1
park_telescope
for x in $(seq 1 10); do
preflash
fli_control -r /tmp/10micron.fitsheader -x1 -N "${OBS}" -O "bias" -d bias
preflash
fli_control -r /tmp/10micron.fitsheader -x $EXPTIME -N "${OBS}" -O "dark" -d dark
preflash
fli_control -r /tmp/10micron.fitsheader -n3 -x $FLATTIME -N "${OBS}" -O "flat" flat
done
relay_manage -r1
echo "Closed @ $(date)" >> closed
STOPobs || true
DIR=$(basename $PWD)
echo "TAR: $DIR"
cd ..
./copy_and_xz.sh $DIR
echo "Archived, end"
echo "$DIR archived @ $(date)" >> archived

View File

@@ -0,0 +1,44 @@
#!/bin/bash
#
# The script creates working directory,
# copies 'run' script into it and
# edits observer name according to
# the its argument
#
# Working directory name is formed from
# date of the script running and is computed
# as follows:
# now - 12hours
# i.e. the day starts from 12h not from 0h!
#
# $1 - observer name
#
if [[ $# -eq 0 ]]; then
obs_name="Fatkhullin T.A."
else
obs_name=$1
fi
# now - 12h
let now12=`date +%s`-12*3600
# working directory
wdir=/DATA/FITS/`date -d @$now12 +%y.%m.%d`
echo -n "Creating working directory: $wdir ..."
if [[ -d $wdir ]]; then
echo -e "\tFAILED! The directory already exists! Exit!"
exit 1
else
echo -e "\tOK!"
mkdir $wdir
cd $wdir
fi
cp ../run_full.new_foc .
# replace observer name
sed -i "0,/^OBS=\".*\"/ s//OBS=\"${obs_name}\"/" run_full.new_foc
#sed -i "0,/^OBS=\"[a-zA-Z \.]*\"/ s//OBS=\"${obs_name}\"/" run_full.new_foc

View File

@@ -0,0 +1,3 @@
#!/bin/bash
mpv -vo sixel --really-quiet=yes "rtsp://viewer:view25@192.168.70.25:554/axis-media/media.amp?videocodec=h264&resolution=640x480"

View File

@@ -41,7 +41,7 @@ static glob_pars G = {
* Define command line options by filling structure: * Define command line options by filling structure:
* name has_arg flag val type argptr help * name has_arg flag val type argptr help
*/ */
static myoption cmdlnopts[] = { static sl_option_t cmdlnopts[] = {
// common options // common options
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), "show this help"}, {"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), "show this help"},
{"delimeter",NEED_ARG, NULL, 'd', arg_string, APTR(&G.delimeter), "coordinates delimeter string (default: ':')"}, {"delimeter",NEED_ARG, NULL, 'd', arg_string, APTR(&G.delimeter), "coordinates delimeter string (default: ':')"},
@@ -71,10 +71,10 @@ glob_pars *parse_args(int argc, char **argv){
char helpstring[1024], *hptr = helpstring; char helpstring[1024], *hptr = helpstring;
snprintf(hptr, hlen, "Usage: %%s [args]\n\n\tWhere args are:\n"); snprintf(hptr, hlen, "Usage: %%s [args]\n\n\tWhere args are:\n");
// format of help: "Usage: progname [args]\n" // format of help: "Usage: progname [args]\n"
change_helpstring(helpstring); sl_helpstring(helpstring);
// parse arguments // parse arguments
parseargs(&argc, &argv, cmdlnopts); sl_parseargs(&argc, &argv, cmdlnopts);
if(help) showhelp(-1, cmdlnopts); if(help) sl_showhelp(-1, cmdlnopts);
if(argc > 0){ if(argc > 0){
G.rest_pars_num = argc; G.rest_pars_num = argc;
G.rest_pars = MALLOC(char *, argc); G.rest_pars = MALLOC(char *, argc);

View File

@@ -100,7 +100,7 @@ static void savepoints(FILE *f, point *pts, int N, char *delim, int mask){
} }
int main(int argc, char **argv){ int main(int argc, char **argv){
initial_setup(); sl_init();
glob_pars *G = parse_args(argc, argv); glob_pars *G = parse_args(argc, argv);
FILE *f = NULL; FILE *f = NULL;
if(G->outfile){ if(G->outfile){

View File

@@ -32,7 +32,7 @@ typedef struct{
static glob_pars G = {.tolerance = 10.}; static glob_pars G = {.tolerance = 10.};
static myoption cmdlnopts[] = { static sl_option_t cmdlnopts[] = {
// common options // common options
{"help", NO_ARGS, NULL, 'h', arg_none, APTR(&G.help), _("show this help")}, {"help", NO_ARGS, NULL, 'h', arg_none, APTR(&G.help), _("show this help")},
{"infile", NEED_ARG, NULL, 'i', arg_string, APTR(&G.input), _("input file name")}, {"infile", NEED_ARG, NULL, 'i', arg_string, APTR(&G.input), _("input file name")},
@@ -158,11 +158,11 @@ static double calcfocus(double coeffs[3]){
int main(int argc, char **argv){ int main(int argc, char **argv){
char helpstring[256]; char helpstring[256];
initial_setup(); sl_init();
snprintf(helpstring, 255, "Usage: `cat file | %%s` or with args; file format \"x y\\n..\"\n\tArgs:\n"); snprintf(helpstring, 255, "Usage: `cat file | %%s` or with args; file format \"x y\\n..\"\n\tArgs:\n");
change_helpstring(helpstring); sl_helpstring(helpstring);
parseargs(&argc, &argv, cmdlnopts); sl_parseargs(&argc, &argv, cmdlnopts);
if(G.help) showhelp(-1, cmdlnopts); if(G.help) sl_showhelp(-1, cmdlnopts);
if(G.tolerance <= 0.) ERRX("Tolerance should be > 0"); if(G.tolerance <= 0.) ERRX("Tolerance should be > 0");
FILE *f = stdin; FILE *f = stdin;
if(G.input){ if(G.input){

View File

@@ -36,7 +36,7 @@ static const char *radtodeg(double r){
int main(){ int main(){
initial_setup(); sl_init();
at_MJD_t mjd; at_MJD_t mjd;
if(!at_get_MJDu(time(NULL), &mjd)) ERRX("at_get_MJDu"); if(!at_get_MJDu(time(NULL), &mjd)) ERRX("at_get_MJDu");
printf("MJD=%g; TAI=%g/%g, TT=%g/%g, UTC=%g/%g\n", mjd.MJD, mjd.tai1, mjd.tai2, mjd.tt1, mjd.tt2, mjd.utc1, mjd.utc2); printf("MJD=%g; TAI=%g/%g, TT=%g/%g, UTC=%g/%g\n", mjd.MJD, mjd.tai1, mjd.tai2, mjd.tt1, mjd.tt2, mjd.utc1, mjd.utc2);

View File

@@ -56,7 +56,7 @@ static parameters G = {
.py = -10000. .py = -10000.
}; };
static myoption cmdlnopts[] = { static sl_option_t cmdlnopts[] = {
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&G.help), "show this help"}, {"help", NO_ARGS, NULL, 'h', arg_int, APTR(&G.help), "show this help"},
{"obsplace", NO_ARGS, NULL, 'O', arg_int, APTR(&G.obsplace), "input RA/Dec is observed place"}, {"obsplace", NO_ARGS, NULL, 'O', arg_int, APTR(&G.obsplace), "input RA/Dec is observed place"},
{"JD", NEED_ARG, NULL, 'J', arg_double, APTR(&G.JD), "Julian date"}, {"JD", NEED_ARG, NULL, 'J', arg_double, APTR(&G.JD), "Julian date"},
@@ -77,9 +77,9 @@ static myoption cmdlnopts[] = {
int main(int argc, char **argv){ int main(int argc, char **argv){
initial_setup(); sl_init();
parseargs(&argc, &argv, cmdlnopts); sl_parseargs(&argc, &argv, cmdlnopts);
if(G.help) showhelp(-1, cmdlnopts); if(G.help) sl_showhelp(-1, cmdlnopts);
at_MJD_t MJD; at_MJD_t MJD;
G.ra *= ERFA_DD2R; G.ra *= ERFA_DD2R;
G.dec *= ERFA_DD2R; G.dec *= ERFA_DD2R;

View File

@@ -8,3 +8,5 @@ Different daemons & tools
- *netsocket* - scripts for management of network 220V-socket - *netsocket* - scripts for management of network 220V-socket
- *send_coordinates* - get/send coordinates to 10-micron mount through stellarium daemon - *send_coordinates* - get/send coordinates to 10-micron mount through stellarium daemon
- *teldaemon* - open/close Astrosib-500 scope covers by network query - *teldaemon* - open/close Astrosib-500 scope covers by network query
- *weatherdaemon* - weather daemon for old meteostation
- *weatherdaemon_newmeteo* - daemon for new (chinese) meteostation

View File

@@ -180,9 +180,10 @@ static void toomuch(int fd){
LOGWARN("Client fd=%d tried to connect after MAX reached", fd); LOGWARN("Client fd=%d tried to connect after MAX reached", fd);
} }
// new connections handler // new connections handler
static void connected(sl_sock_t *c){ static int connected(sl_sock_t *c){
if(c->type == SOCKT_UNIX) LOGMSG("New client fd=%d connected", c->fd); if(c->type == SOCKT_UNIX) LOGMSG("New client fd=%d connected", c->fd);
else LOGMSG("New client fd=%d, IP=%s connected", c->fd, c->IP); else LOGMSG("New client fd=%d, IP=%s connected", c->fd, c->IP);
return TRUE;
} }
// disconnected handler // disconnected handler
static void disconnected(sl_sock_t *c){ static void disconnected(sl_sock_t *c){
@@ -196,12 +197,12 @@ void server_run(sl_socktype_e type, const char *node, sl_tty_t *serial){
ERRX("server_run(): wrong parameters"); ERRX("server_run(): wrong parameters");
} }
dome_serialdev(serial); dome_serialdev(serial);
sl_sock_changemaxclients(5);
sl_sock_maxclhandler(toomuch);
sl_sock_connhandler(connected);
sl_sock_dischandler(disconnected);
s = sl_sock_run_server(type, node, -1, handlers); s = sl_sock_run_server(type, node, -1, handlers);
if(!s) ERRX("Can't create socket and/or run threads"); if(!s) ERRX("Can't create socket and/or run threads");
sl_sock_changemaxclients(s, 5);
sl_sock_maxclhandler(s, toomuch);
sl_sock_connhandler(s, connected);
sl_sock_dischandler(s, disconnected);
while(s && s->connected){ while(s && s->connected){
if(!s->rthread){ if(!s->rthread){
LOGERR("Server handlers thread is dead"); LOGERR("Server handlers thread is dead");

View File

@@ -54,7 +54,7 @@ glob_pars const Gdefault = {
* Define command line options by filling structure: * Define command line options by filling structure:
* name has_arg flag val type argptr help * name has_arg flag val type argptr help
*/ */
myoption cmdlnopts[] = { sl_option_t cmdlnopts[] = {
// common options // common options
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")}, {"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")},
{"device", NEED_ARG, NULL, 'i', arg_string, APTR(&G.device), _("serial device name (default: none)")}, {"device", NEED_ARG, NULL, 'i', arg_string, APTR(&G.device), _("serial device name (default: none)")},
@@ -79,10 +79,10 @@ glob_pars *parse_args(int argc, char **argv){
void *ptr; void *ptr;
ptr = memcpy(&G, &Gdefault, sizeof(G)); assert(ptr); ptr = memcpy(&G, &Gdefault, sizeof(G)); assert(ptr);
// format of help: "Usage: progname [args]\n" // format of help: "Usage: progname [args]\n"
change_helpstring("Usage: %s [args]\n\n\tWhere args are:\n"); sl_helpstring("Usage: %s [args]\n\n\tWhere args are:\n");
// parse arguments // parse arguments
parseargs(&argc, &argv, cmdlnopts); sl_parseargs(&argc, &argv, cmdlnopts);
if(help) showhelp(-1, cmdlnopts); if(help) sl_showhelp(-1, cmdlnopts);
if(argc > 0){ if(argc > 0){
G.rest_pars_num = argc; G.rest_pars_num = argc;
G.rest_pars = calloc(argc, sizeof(char*)); G.rest_pars = calloc(argc, sizeof(char*));

View File

@@ -30,14 +30,14 @@
glob_pars *GP; glob_pars *GP;
void signals(int signo){ void signals(int signo){
restore_console(); sl_restore_con();
if(ttydescr) close_tty(&ttydescr); if(ttydescr) sl_tty_close(&ttydescr);
LOGERR("exit with status %d", signo); LOGERR("exit with status %d", signo);
exit(signo); exit(signo);
} }
int main(int argc, char **argv){ int main(int argc, char **argv){
initial_setup(); sl_init();
signal(SIGTERM, signals); // kill (-15) - quit signal(SIGTERM, signals); // kill (-15) - quit
signal(SIGHUP, SIG_IGN); // hup - ignore signal(SIGHUP, SIG_IGN); // hup - ignore
signal(SIGINT, signals); // ctrl+C - quit signal(SIGINT, signals); // ctrl+C - quit
@@ -52,7 +52,7 @@ int main(int argc, char **argv){
signals(0); // never reached! signals(0); // never reached!
} }
if(GP->logfile){ if(GP->logfile){
sl_loglevel lvl = LOGLEVEL_ERR; sl_loglevel_e lvl = LOGLEVEL_ERR;
for(; GP->verb && lvl < LOGLEVEL_ANY; --GP->verb) ++lvl; for(; GP->verb && lvl < LOGLEVEL_ANY; --GP->verb) ++lvl;
DBG("Loglevel: %d", lvl); DBG("Loglevel: %d", lvl);
if(!OPENLOG(GP->logfile, lvl, 1)) ERRX("Can't open log file"); if(!OPENLOG(GP->logfile, lvl, 1)) ERRX("Can't open log file");

View File

@@ -28,7 +28,7 @@
#define BUFLEN 1024 #define BUFLEN 1024
TTY_descr *ttydescr = NULL; sl_tty_t *ttydescr = NULL;
static char buf[BUFLEN]; static char buf[BUFLEN];
@@ -50,14 +50,14 @@ static char *read_string(){
return ptr; return ptr;
} }
ptr = buf; ptr = buf;
double d0 = dtime(); double d0 = sl_dtime();
do{ do{
if((l = read_tty(ttydescr))){ if((l = sl_tty_read(ttydescr))){
r += l; LL -= l; ptr += l; r += l; LL -= l; ptr += l;
if(ptr[-1] == '\n') break; if(ptr[-1] == '\n') break;
d0 = dtime(); d0 = sl_dtime();
} }
}while(dtime() - d0 < WAIT_TMOUT && LL); }while(sl_dtime() - d0 < WAIT_TMOUT && LL);
if(r){ if(r){
buf[r] = 0; buf[r] = 0;
//DBG("r=%zd, got string: %s", r, buf); //DBG("r=%zd, got string: %s", r, buf);
@@ -75,10 +75,10 @@ static char *read_string(){
int try_connect(char *device, int baudrate){ int try_connect(char *device, int baudrate){
if(!device) return 0; if(!device) return 0;
fflush(stdout); fflush(stdout);
ttydescr = new_tty(device, baudrate, 1024); ttydescr = sl_tty_new(device, baudrate, 1024);
if(ttydescr) ttydescr = tty_open(ttydescr, 1); // exclusive open if(ttydescr) ttydescr = sl_tty_open(ttydescr, 1); // exclusive open
if(!ttydescr) return 0; if(!ttydescr) return 0;
while(read_tty(ttydescr)); // clear rbuf while(sl_tty_read(ttydescr)); // clear rbuf
LOGMSG("Connected to %s", device); LOGMSG("Connected to %s", device);
return 1; return 1;
} }
@@ -91,14 +91,14 @@ void run_terminal(){
green(_("Work in terminal mode without echo\n")); green(_("Work in terminal mode without echo\n"));
int rb; int rb;
size_t l; size_t l;
setup_con(); sl_setup_con();
while(1){ while(1){
if((l = read_tty(ttydescr))){ if((l = sl_tty_read(ttydescr))){
printf("%s", ttydescr->buf); printf("%s", ttydescr->buf);
} }
if((rb = read_console())){ if((rb = sl_read_con())){
char c = (char) rb; char c = (char) rb;
write_tty(ttydescr->comfd, &c, 1); sl_tty_write(ttydescr->comfd, &c, 1);
} }
} }
} }
@@ -109,8 +109,8 @@ void run_terminal(){
*/ */
char *poll_device(){ char *poll_device(){
char *ans; char *ans;
double t0 = dtime(); double t0 = sl_dtime();
while(dtime() - t0 < T_POLLING_TMOUT){ while(sl_dtime() - t0 < T_POLLING_TMOUT){
if((ans = read_string())){ // parse new data if((ans = read_string())){ // parse new data
DBG("got %s", ans); DBG("got %s", ans);
/* /*

View File

@@ -31,7 +31,7 @@
// Terminal polling timeout - 1 second // Terminal polling timeout - 1 second
#define T_POLLING_TMOUT (1.0) #define T_POLLING_TMOUT (1.0)
extern TTY_descr *ttydescr; extern sl_tty_t *ttydescr;
void run_terminal(); void run_terminal();
int try_connect(char *device, int baudrate); int try_connect(char *device, int baudrate);
char *poll_device(); char *poll_device();

View File

@@ -46,7 +46,7 @@ static glob_pars const Gdefault = {
* Define command line options by filling structure: * Define command line options by filling structure:
* name has_arg flag val type argptr help * name has_arg flag val type argptr help
*/ */
static myoption cmdlnopts[] = { static sl_option_t cmdlnopts[] = {
// common options // common options
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")}, {"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), _("show this help")},
{"port", NEED_ARG, NULL, 'P', arg_string, APTR(&G.port), _("port to connect (default: " DEFAULT_PORT ")")}, {"port", NEED_ARG, NULL, 'P', arg_string, APTR(&G.port), _("port to connect (default: " DEFAULT_PORT ")")},
@@ -73,13 +73,13 @@ glob_pars *parse_args(int argc, char **argv){
char helpstring[1024], *hptr = helpstring; char helpstring[1024], *hptr = helpstring;
snprintf(hptr, hlen, "Usage: %%s [args]\n\n\tWhere args are:\n"); snprintf(hptr, hlen, "Usage: %%s [args]\n\n\tWhere args are:\n");
// format of help: "Usage: progname [args]\n" // format of help: "Usage: progname [args]\n"
change_helpstring(helpstring); sl_helpstring(helpstring);
// parse arguments // parse arguments
parseargs(&argc, &argv, cmdlnopts); sl_parseargs(&argc, &argv, cmdlnopts);
if(help) showhelp(-1, cmdlnopts); if(help) sl_showhelp(-1, cmdlnopts);
if(argc > 0){ if(argc > 0){
fprintf(stderr, "Undefined extra parameters!\n"); fprintf(stderr, "Undefined extra parameters!\n");
showhelp(-1, cmdlnopts); sl_showhelp(-1, cmdlnopts);
G.rest_pars_num = argc; G.rest_pars_num = argc;
G.rest_pars = MALLOC(char *, argc); G.rest_pars = MALLOC(char *, argc);
for (i = 0; i < argc; i++) for (i = 0; i < argc; i++)

View File

@@ -36,7 +36,7 @@ void signals(int sig){
signal(sig, SIG_IGN); signal(sig, SIG_IGN);
DBG("Get signal %d, quit.\n", sig); DBG("Get signal %d, quit.\n", sig);
} }
restore_console(); sl_restore_con();
exit(sig); exit(sig);
} }
@@ -45,7 +45,7 @@ void iffound_default(pid_t pid){
} }
int main(int argc, char *argv[]){ int main(int argc, char *argv[]){
initial_setup(); sl_init();
char *self = strdup(argv[0]); char *self = strdup(argv[0]);
GP = parse_args(argc, argv); GP = parse_args(argc, argv);
DBG("here"); DBG("here");
@@ -66,7 +66,7 @@ int main(int argc, char *argv[]){
signal(SIGQUIT, signals); // ctrl+\ - quit signal(SIGQUIT, signals); // ctrl+\ - quit
signal(SIGTSTP, SIG_IGN); // ignore ctrl+Z signal(SIGTSTP, SIG_IGN); // ignore ctrl+Z
DBG("here"); DBG("here");
setup_con(); sl_setup_con();
/* /*
if(GP->rest_pars_num){ if(GP->rest_pars_num){
for(int i = 0; i < GP->rest_pars_num; ++i) for(int i = 0; i < GP->rest_pars_num; ++i)

View File

@@ -56,7 +56,7 @@ void signals(int signo){
exit(signo); exit(signo);
} }
static myoption cmdlnopts[] = { static sl_option_t cmdlnopts[] = {
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&G.help), "show this help"}, {"help", NO_ARGS, NULL, 'h', arg_int, APTR(&G.help), "show this help"},
{"address", NEED_ARG, NULL, 'a', arg_string, APTR(&G.server), "server name or IP"}, {"address", NEED_ARG, NULL, 'a', arg_string, APTR(&G.server), "server name or IP"},
{"port", NEED_ARG, NULL, 'p', arg_string, APTR(&G.port), "server port"}, {"port", NEED_ARG, NULL, 'p', arg_string, APTR(&G.port), "server port"},
@@ -68,19 +68,19 @@ static myoption cmdlnopts[] = {
int main(int argc, char **argv){ int main(int argc, char **argv){
char *self = strdup(argv[0]); char *self = strdup(argv[0]);
initial_setup(); sl_init();
parseargs(&argc, &argv, cmdlnopts); sl_parseargs(&argc, &argv, cmdlnopts);
if(G.help) showhelp(-1, cmdlnopts); if(G.help) sl_showhelp(-1, cmdlnopts);
if(argc > 0) WARNX("Got %d unused keys", argc); if(argc > 0) WARNX("Got %d unused keys", argc);
if(!G.dbname) ERRX("Point database file name"); if(!G.dbname) ERRX("Point database file name");
if(!G.server) ERRX("Point server IP or name"); if(!G.server) ERRX("Point server IP or name");
if(!G.port) ERRX("Point server port"); if(!G.port) ERRX("Point server port");
sl_loglevel lvl = LOGLEVEL_ERR + G.v; sl_loglevel_e lvl = LOGLEVEL_ERR + G.v;
if(lvl > LOGLEVEL_ANY) lvl = LOGLEVEL_ANY; if(lvl > LOGLEVEL_ANY) lvl = LOGLEVEL_ANY;
if(G.logfile) OPENLOG(G.logfile, lvl, 1); if(G.logfile) OPENLOG(G.logfile, lvl, 1);
LOGMSG("hello, start"); LOGMSG("hello, start");
LOGDBG("SQLite version: %s", sqlite3_libversion()); LOGDBG("SQLite version: %s", sqlite3_libversion());
check4running(self, G.pidfile); sl_check4running(self, G.pidfile);
// signal reactions: // signal reactions:
signal(SIGTERM, signals); // kill (-15) - quit signal(SIGTERM, signals); // kill (-15) - quit
signal(SIGHUP, SIG_IGN); // hup - ignore signal(SIGHUP, SIG_IGN); // hup - ignore
@@ -93,11 +93,11 @@ int main(int argc, char **argv){
while(1){ while(1){
childpid = fork(); childpid = fork();
if(childpid){ // master if(childpid){ // master
double t0 = dtime(); double t0 = sl_dtime();
LOGMSG("Created child with pid %d", childpid); LOGMSG("Created child with pid %d", childpid);
wait(NULL); wait(NULL);
LOGWARN("Child %d died", childpid); LOGWARN("Child %d died", childpid);
if(dtime() - t0 < 1.) pause += 5; if(sl_dtime() - t0 < 1.) pause += 5;
else pause = 1; else pause = 1;
if(pause > 900) pause = 900; if(pause > 900) pause = 900;
sleep(pause); // wait a little before respawn sleep(pause); // wait a little before respawn

View File

@@ -78,7 +78,7 @@ static void sendmessage(int fd, const char *msg, int l){
LOGWARN("write()"); LOGWARN("write()");
WARN("write()"); WARN("write()");
}else{ }else{
if(globlog){ // logging turned ON if(sl_globlog){ // logging turned ON
tmpbuf[l-1] = 0; // remove trailing '\n' for logging tmpbuf[l-1] = 0; // remove trailing '\n' for logging
LOGMSG("SEND to fd %d: %s", fd, tmpbuf); LOGMSG("SEND to fd %d: %s", fd, tmpbuf);
} }
@@ -125,10 +125,10 @@ static int canberead(int fd){
// collect data and write into database // collect data and write into database
// @return FALSE if can't get full data string // @return FALSE if can't get full data string
static int getdata(int fd){ static int getdata(int fd){
double t0 = dtime(); double t0 = sl_dtime();
char buf[BUFSIZ]; char buf[BUFSIZ];
int len = 0, leave = BUFSIZ, got = 0; int len = 0, leave = BUFSIZ, got = 0;
while(dtime() - t0 < ANS_TIMEOUT){ while(sl_dtime() - t0 < ANS_TIMEOUT){
int r = canberead(fd); int r = canberead(fd);
if(r == 0) continue; if(r == 0) continue;
r = read(fd, buf + len, leave); r = read(fd, buf + len, leave);
@@ -169,7 +169,7 @@ static int getdata(int fd){
void run_socket(int fd){ void run_socket(int fd){
double t0 = 0.; double t0 = 0.;
while(1){ while(1){
double tlast = dtime(); double tlast = sl_dtime();
if(tlast - t0 >= POLLING_INTERVAL){ if(tlast - t0 >= POLLING_INTERVAL){
sendstrmessage(fd, SERVER_COMMAND); sendstrmessage(fd, SERVER_COMMAND);
if(getdata(fd)) t0 = tlast; if(getdata(fd)) t0 = tlast;

View File

@@ -0,0 +1,69 @@
cmake_minimum_required(VERSION 4.0)
set(PROJ weatherdaemon)
set(PROJLIB senslib)
set(MAJOR_VERSION "0")
set(MID_VERSION "0")
set(MINOR_VERSION "1")
aux_source_directory(${CMAKE_CURRENT_SOURCE_DIR} SOURCES)
set(VERSION "${MAJOR_VERSION}.${MID_VERSION}.${MINOR_VERSION}")
project(${PROJ} VERSION ${VERSION} LANGUAGES C)
message("VER: ${VERSION}")
# list of options
option(DEBUG "Compile in debug mode" OFF)
option(DUMMY "Dummy device plugin" ON)
option(FDEXAMPLE "Example of file descriptor plugin" ON)
# default flags
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -W -Wextra -pedantic-errors -fPIC")
message("Install dir prefix: ${CMAKE_INSTALL_PREFIX}")
add_definitions(-D_XOPEN_SOURCE=1234 -D_DEFAULT_SOURCE -D_GNU_SOURCE
-DPACKAGE_VERSION=\"${VERSION}\" -DMINOR_VERSION=\"${MINOR_VERSION}\" -DMID_VERSION=\"${MID_VERSION}\"
-DMAJOR_VERSION=\"${MAJOR_VESION}\")
set(CMAKE_COLOR_MAKEFILE ON)
# cmake -DDEBUG=on -> debugging
if(DEBUG)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Og -g3 -ggdb -Werror")
add_definitions(-DEBUG)
set(CMAKE_BUILD_TYPE DEBUG)
set(CMAKE_VERBOSE_MAKEFILE "ON")
else()
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -O3 -march=native -fdata-sections -ffunction-sections -flto=auto")
SET(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,--gc-sections -flto=auto")
set(CMAKE_BUILD_TYPE RELEASE)
endif()
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}")
find_package(PkgConfig REQUIRED)
pkg_check_modules(${PROJ} REQUIRED usefull_macros>=0.3.5)
#include(FindOpenMP)
#if(OPENMP_FOUND)
# set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
# set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}")
# add_definitions(-DOMP_FOUND)
#endif()
# static lib for sensors
set(LIBSRC "weathlib.c")
set(LIBHEADER "weathlib.h")
add_library(${PROJLIB} STATIC ${LIBSRC})
set_target_properties(${PROJLIB} PROPERTIES VERSION ${VERSION})
# exe & deps files
add_executable(${PROJ} ${SOURCES})
target_link_libraries(${PROJ} ${${PROJ}_LIBRARIES} ${PROJLIB} -lm ${CMAKE_DL_LIBS})
target_include_directories(${PROJ} PUBLIC ${${PROJ}_INCLUDE_DIRS} .)
target_link_directories(${PROJ} PUBLIC ${${PROJ}_LIBRARY_DIRS} )
include(GNUInstallDirs)
# Installation of the program
install(TARGETS ${PROJ} DESTINATION "bin")
add_subdirectory("plugins")

View File

@@ -0,0 +1,22 @@
Weather daemon for several different weather stations
=====================================================
## Usage:
```
Usage: weatherdaemon [args]
Be careful: command line options have priority over config
Where args are:
-P, --pidfile=arg pidfile name (default: /tmp/weatherdaemon.pid)
-c, --conffile=arg configuration file name (consists all or a part of long-named parameters and their values (e.g. plugin=liboldweather.so)
-h, --help show this help
-l, --logfile=arg save logs to file (default: none)
-p, --plugin=arg add this weather plugin (may be a lot of) (can occur multiple times)
-v, --verb logfile verbocity level (each -v increased)
--port=arg network port to connect (default: 12345); hint: use "localhost:port" to make local net socket
--sockpath=arg UNIX socket path (starting from '\0' for anonimous) of command socket
```
TODO: brief documentation will be here

View File

@@ -0,0 +1,164 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <assert.h>
#include <stdio.h>
#include <string.h>
#include <strings.h>
#include <usefull_macros.h>
#include "cmdlnopts.h"
/*
* here are global parameters initialisation
*/
int help;
// default values for Gdefault & help
#define DEFAULT_PORT "12345"
#define DEFAULT_PID "/tmp/weatherdaemon.pid"
// DEFAULTS
// default global parameters
static glob_pars defpars = {
.port = DEFAULT_PORT,
.logfile = NULL,
.verb = 0,
.pidfile = DEFAULT_PID
};
// default config: all values should be wrong or empty to understand than user change them
static glob_pars defconf = {
.verb = -1,
};
static glob_pars G;
/*
* Define command line options by filling structure:
* name has_arg flag val type argptr help
*/
#define COMMON_OPTS \
{"port", NEED_ARG, NULL, 0, arg_string, APTR(&G.port), "network port to connect (default: " DEFAULT_PORT "); hint: use \"localhost:port\" to make local net socket"}, \
{"logfile", NEED_ARG, NULL, 'l', arg_string, APTR(&G.logfile), "save logs to file (default: none)"}, \
{"pidfile", NEED_ARG, NULL, 'P', arg_string, APTR(&G.pidfile), "pidfile name (default: " DEFAULT_PID ")"}, \
{"sockpath",NEED_ARG, NULL, 0, arg_string, APTR(&G.sockname), "UNIX socket path (starting from '\\0' for anonimous) of command socket"}, \
{"plugin", MULT_PAR, NULL, 'p', arg_string, APTR(&G.plugins), "add this weather plugin (may be a lot of); FORMAT: \"dlpath:l:dev\", where `dlpath` - path of plugin library; `l` - 'D' for device, 'U' for UNIX-socket or 'N' for INET socket; dev - path to device and speed (like /dev/ttyS0:9600), UNIX socket name or host:port for INET"}, \
{"pollt", NEED_ARG, NULL, 'T', arg_int, APTR(&G.pollt), "set maximal polling interval (seconds, integer)"},
sl_option_t cmdlnopts[] = {
{"help", NO_ARGS, NULL, 'h', arg_int, APTR(&help), "show this help"},
{"conffile",NEED_ARG, NULL, 'c', arg_string, APTR(&G.conffile), "configuration file name (consists all or a part of long-named parameters and their values (e.g. plugin=liboldweather.so:D:/dev/ttyS0:115200)"},
{"verb", NO_ARGS, NULL, 'v', arg_none, APTR(&G.verb), "logfile verbocity level (each -v increased)"}, \
COMMON_OPTS
end_option
};
sl_option_t confopts[] = {
{"verbose", NEED_ARG, NULL, 'v', arg_int, APTR(&G.verb), "logfile verbocity level"}, \
COMMON_OPTS
end_option
};
static int sortstrings(const void *v1, const void *v2){
const char **s1 = (const char **)v1, **s2 = (const char **)v2;
return strcmp(*s1, *s2);
}
// compare plugins from configuration and command line; add to command line plugins all new
static void compplugins(glob_pars *cmdline, glob_pars *conf){
if(!cmdline) return;
char **p;
int nconf = 0;
if(conf){
p = conf->plugins;
if(p && *p) while(*p++) ++nconf;
}
int ncmd = 0;
p = cmdline->plugins;
if(p && *p) while(*p++) ++ncmd;
DBG("Got %d plugins in conf and %d in cmdline", nconf, ncmd);
// compare plugins and rebuild new list
int newsize = ncmd + nconf;
if(newsize == 0) return; // no plugins in both
char **newarray = MALLOC(char*, newsize + 1); // +1 for ending NULL
for(int i = 0; i < ncmd; ++i){ newarray[i] = cmdline->plugins[i]; }
FREE(cmdline->plugins);
if(conf){
for(int i = 0; i < nconf; ++i){ newarray[i+ncmd] = conf->plugins[i]; }
FREE(conf->plugins);
}
qsort(newarray, newsize, sizeof(char*), sortstrings);
DBG("NOW together:"); p = newarray; while(*p) printf("\t%s\n", *p++);
p = newarray;
int nondobuleidx = 0;
for(int i = 0; i < newsize;){
int j = i + 1;
for(; j < newsize; ++j){
if(strcmp(newarray[i], newarray[j])) break;
FREE(newarray[j]);
}
if(nondobuleidx != i){
newarray[nondobuleidx] = newarray[i];
newarray[i] = NULL;
}
++nondobuleidx;
i = j;
}
DBG("Result:"); p = newarray; while(*p) printf("\t%s\n", *p++);
cmdline->plugins = newarray;
cmdline->nplugins = nondobuleidx;
}
/**
* Parse command line options and return dynamically allocated structure
* to global parameters
* @param argc - copy of argc from main
* @param argv - copy of argv from main
* @return allocated structure with global parameters
*/
glob_pars *parse_args(int argc, char **argv){
G = defpars; // copy defaults
// format of help: "Usage: progname [args]\n"
sl_helpstring("Usage: %s [args]\n\t" COLOR_RED "Be careful: command line options have priority over config" COLOR_OLD "\n\tWhere args are:\n");
// parse arguments
sl_parseargs(&argc, &argv, cmdlnopts);
DBG("verb: %d", G.verb);
if(help) sl_showhelp(-1, cmdlnopts);
if(argc > 0){
WARNX("You give %d unused parameters:", argc);
while(argc) printf("\t%s\n", argv[--argc]);
}
DBG("PARS: \n-------------\n%s-------------\n\n", sl_print_opts(cmdlnopts, 1));
if(G.conffile){ // read conffile and fix parameters (cmdline args are in advantage)
glob_pars oldpars = G; // save cmdline opts
G = defconf;
if(!sl_conf_readopts(oldpars.conffile, confopts)) ERRX("Can't get options from %s", G.conffile);
DBG("CONF: \n-------------\n%s-------------\n\n", sl_print_opts(confopts, 1));
if((0 == strcmp(oldpars.port, DEFAULT_PORT)) && G.port) oldpars.port = G.port;
if(!oldpars.logfile && G.logfile) oldpars.logfile = G.logfile;
if(!oldpars.verb && G.verb > -1) oldpars.verb = G.verb;
if((0 == strcmp(oldpars.pidfile, DEFAULT_PID)) && G.pidfile) oldpars.pidfile = G.pidfile;
if(!oldpars.sockname && G.sockname) oldpars.sockname = G.sockname;
// now check plugins
compplugins(&oldpars, &G);
G = oldpars;
}else compplugins(&G, NULL);
DBG("RESULT: \n-------------\n%s-------------\n\n", sl_print_opts(cmdlnopts, 1));
DBG("Nplugins = %d", G.nplugins);
return &G;
}

View File

@@ -0,0 +1,37 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
/*
* here are some typedef's for global data
*/
typedef struct{
char *sockname; // UNIX socket name for internal connections (commands etc)
char *port; // port for external clients
char *logfile; // logfile name
int verb; // verbocity level
char *pidfile; // pidfile name
char **plugins; // all plugins connected
int nplugins; // amount of plugins
char *conffile; // configuration file used instead of long command line
int pollt; // sensors maximal polling interval
} glob_pars;
glob_pars *parse_args(int argc, char **argv);

View File

@@ -0,0 +1,152 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2026 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
// try to open device or socket that user pointed for plugin
// WARNING!!! The `getFD` function intended for single use for each plugin!
// WARNING!!! If you will try to close some plugins in running mode and open others, it
// WARNING!!! would cause to a memory leak!
#include <arpa/inet.h>
#include <netdb.h>
#include <string.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <sys/un.h> // unix socket
#include <usefull_macros.h>
#include "fd.h"
/**
* @brief openserial - try to open serial device
* @param path - path to device and speed, colon-separated (without given speed assume 9600)
* @return -1 if failed or opened FD
* WARNING!!! Memory leakage danger. Don't call this function too much times!
*/
static int openserial(char *path){
FNAME();
int speed = 9600; // default speed
char *colon = strchr(path, ':');
if(colon){
*colon++ = 0;
if(!sl_str2i(&speed, colon)){
WARNX("Wrong speed settings: '%s'", colon);
return -1;
}
}
sl_tty_t *serial = sl_tty_new(path, speed, BUFSIZ);
if(!serial || !sl_tty_open(serial, TRUE)){
WARN("Can't open %s @ speed %d", path, speed);
return -1;
}
return serial->comfd;
}
static char *convunsname(const char *path){
char *apath = MALLOC(char, 106);
if(*path == 0 || *path == '@'){
DBG("convert name starting from 0 or @");
apath[0] = 0;
strncpy(apath+1, path+1, 104);
}else if(strncmp("\\0", path, 2) == 0){
DBG("convert name starting from \\0");
apath[0] = 0;
strncpy(apath+1, path+2, 104);
}else strncpy(apath, path, 105);
return apath;
}
/**
* @brief opensocket - try to open socket
* @param sock - UNIX socket path or hostname:port for INET socket
* @param type - UNIX or INET
* @return -1 if failed or opened FD
*/
static int opensocket(char *path, sl_socktype_e type){
FNAME();
DBG("path: '%s'", path);
int sock = -1;
struct addrinfo ai = {0}, *res = &ai;
struct sockaddr_un unaddr = {0};
char *node = path, *service = NULL;
ai.ai_socktype = 0; // try to get socket type from `getaddrinfo`
switch(type){
case SOCKT_UNIX:
{
char *str = convunsname(path);
if(!str) return -1;
unaddr.sun_family = AF_UNIX;
ai.ai_addr = (struct sockaddr*) &unaddr;
ai.ai_addrlen = sizeof(unaddr);
memcpy(unaddr.sun_path, str, 106);
FREE(str);
ai.ai_family = AF_UNIX;
}
break;
case SOCKT_NET:
case SOCKT_NETLOCAL:
ai.ai_family = AF_INET;
char *delim = strchr(path, ':');
if(delim){
*delim = 0;
service = delim+1;
if(delim == path) node = NULL; // only port
}
DBG("node: '%s', service: '%s'", node, service);
int e = getaddrinfo(node, service, &ai, &res);
if(e){
WARNX("getaddrinfo(): %s", gai_strerror(e));
return -1;
}
for(struct addrinfo *p = res; p; p = p->ai_next){
if((sock = socket(p->ai_family, p->ai_socktype, p->ai_protocol)) < 0) continue;
DBG("Try proto %d, type %d", p->ai_protocol, p->ai_socktype);
if(connect(sock, p->ai_addr, p->ai_addrlen) == -1){
WARN("connect()");
close(sock); sock = -1;
} else break;
}
break;
default: // never reached
WARNX("Unsupported socket type %d", type);
return -1;
}
DBG("FD: %d", sock);
return sock;
}
/**
* @brief getFD - try to open given device/socket
* @param path - rest of string for --plugin= (e.g. "N:host.com:12345")
* WARNING!!! Contents of `path` would be modified in this function!
* @return opened file descriptor or -1 in case of error
*/
int getFD(char *path){
if(!path || !*path) return -1;
char type = *path;
path += 2;
switch(type){
case 'D': // serial device
return openserial(path);
case 'N': // INET socket
return opensocket(path, SOCKT_NET);
case 'U': // UNIX socket
return opensocket(path, SOCKT_UNIX);
}
WARNX("Wrong plugin format: '%c', should be 'D', 'N' or 'U'", type);
return -1;
}

View File

@@ -0,0 +1,21 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2026 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
int getFD(char *path);

View File

@@ -0,0 +1,102 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <signal.h>
#include <stdio.h>
#include <string.h>
#include <sys/wait.h> // wait
#include <sys/prctl.h> //prctl
#include <usefull_macros.h>
#include "cmdlnopts.h"
#include "sensors.h"
#include "server.h"
static pid_t childpid = 0;
void signals(int signo){
if(childpid){
LOGERR("Killed with status %d", signo);
closeplugins();
kill_servers();
usleep(1000); // let child close everything before dead
}else{
LOGERR("Main process exits with status %d", signo);
}
exit(signo);
}
static void getpipe(int _U_ signo){
WARNX("Get sigpipe!");
// TODO: check all sensors for disconnected one
signal(SIGPIPE, getpipe);
}
extern const char *__progname;
int main(int argc, char **argv){
glob_pars *GP = NULL;
sl_init();
signal(SIGTERM, signals); // kill (-15) - quit
signal(SIGHUP, SIG_IGN); // hup - ignore
signal(SIGINT, signals); // ctrl+C - quit
signal(SIGQUIT, signals); // ctrl+\ - quit
signal(SIGTSTP, SIG_IGN); // ignore ctrl+Z
signal(SIGPIPE, getpipe); // socket disconnected
GP = parse_args(argc, argv);
if(!GP) ERRX("Error parsing args");
if(!GP->sockname) ERRX("Point command socket name");
if(GP->logfile){
sl_loglevel_e lvl = LOGLEVEL_ERR + GP->verb;
if(lvl >= LOGLEVEL_AMOUNT) lvl = LOGLEVEL_AMOUNT - 1;
DBG("Loglevel: %d", lvl);
if(!OPENLOG(GP->logfile, lvl, 1)) ERRX("Can't open log file");
LOGMSG("Started");
}
if(GP->pollt > 0){
if(!set_pollT((time_t)GP->pollt)) ERRX("Can't set polling time to %d seconds", GP->pollt);
}
int nopened = openplugins(GP->plugins, GP->nplugins);
if(nopened < 1){
LOGERR("No plugins found; exit!");
ERRX("Can't find any sensor plugin");
}
if(GP->nplugins && GP->nplugins != nopened) LOGWARN("Work without some plugins");
#ifndef EBUG
sl_check4running((char*)__progname, GP->pidfile);
while(1){ // guard for dead processes
childpid = fork();
if(childpid){
LOGDBG("create child with PID %d\n", childpid);
DBG("Created child with PID %d\n", childpid);
wait(NULL);
WARNX("Child %d died\n", childpid);
LOGWARN("Child %d died\n", childpid);
sleep(1);
}else{
prctl(PR_SET_PDEATHSIG, SIGTERM); // send SIGTERM to child when parent dies
break; // go out to normal functional
}
}
#endif
if(!start_servers(GP->port, GP->sockname)) ERRX("Can't run server's threads");
while(1);
//WARNX("TEST ends");
//signals(0);
return 0; // never reached
}

View File

@@ -0,0 +1,24 @@
cmake_minimum_required(VERSION 3.20)
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR})
find_package(PkgConfig REQUIRED)
pkg_check_modules(PLUGINS REQUIRED usefull_macros)
include_directories(${PLUGINS_INCLUDE_DIRS} ..)
link_directories(${PLUGINS_LIBRARY_DIRS} ..)
link_libraries(${$PLUGINS_LIBRARIES} ${PROJLIB} -fPIC)
set(LIBS "")
if(DUMMY)
add_library(wsdummy SHARED dummy.c)
list(APPEND LIBS wsdummy)
endif()
if(FDEXAMPLE)
add_library(fdex SHARED fdexample.c)
list(APPEND LIBS fdex)
endif()
install(TARGETS ${LIBS} LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR})

View File

@@ -0,0 +1,95 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
// dummy meteostation sending data each `tpoll` seconds
#include "weathlib.h"
#define NS (6)
extern sensordata_t sensor;
static const val_t values[NS] = { // fields `name` and `comment` have no sense until value meaning is `IS_OTHER`
{.sense = VAL_OBLIGATORY, .type = VALT_FLOAT, .meaning = IS_WIND},
{.sense = VAL_RECOMMENDED, .type = VALT_FLOAT, .meaning = IS_WINDDIR},
{.sense = VAL_OBLIGATORY, .type = VALT_FLOAT, .meaning = IS_AMB_TEMP},
{.sense = VAL_RECOMMENDED, .type = VALT_FLOAT, .meaning = IS_PRESSURE},
{.sense = VAL_RECOMMENDED, .type = VALT_FLOAT, .meaning = IS_HUMIDITY},
{.sense = VAL_OBLIGATORY, .type = VALT_UINT, .meaning = IS_PRECIP},
};
static void *mainthread(void _U_ *U){
FNAME();
double t0 = sl_dtime();
while(1){
float f = sensor.values[0].value.f + (drand48() - 0.5) / 2.;
if(f >= 0.) sensor.values[0].value.f = f;
f = sensor.values[1].value.f + (drand48() - 0.5) * 4.;
if(f > 160. && f < 200.) sensor.values[1].value.f = f;
f = sensor.values[2].value.f + (drand48() - 0.5) / 20.;
if(f > 13. && f < 21.) sensor.values[2].value.f = f;
f = sensor.values[3].value.f + (drand48() - 0.5) / 100.;
if(f > 585. && f < 615.) sensor.values[3].value.f = f;
f = sensor.values[4].value.f + (drand48() - 0.5) / 10.;
if(f > 60. && f <= 100.) sensor.values[4].value.f = f;
sensor.values[5].value.u = (f > 98.) ? 1 : 0;
time_t cur = time(NULL);
for(int i = 0; i < NS; ++i) sensor.values[i].time = cur;
if(sensor.freshdatahandler) sensor.freshdatahandler(&sensor);
while(sl_dtime() - t0 < sensor.tpoll) usleep(500);
t0 = sl_dtime();
}
return NULL;
}
static int init(struct sensordata_t* s, int N, time_t pollt, int _U_ fd){
FNAME();
if(pthread_create(&s->thread, NULL, mainthread, NULL)) return 0;
if(pollt) s->tpoll = pollt;
s->values = MALLOC(val_t, NS);
for(int i = 0; i < NS; ++i) s->values[i] = values[i];
sensor.values[0].value.f = 1.;
sensor.values[1].value.f = 180.;
sensor.values[2].value.f = 17.;
sensor.values[3].value.f = 600.;
sensor.values[4].value.f = 80.;
sensor.values[5].value.u = 0;
sensor.PluginNo = N;
return NS;
}
/**
* @brief getval - value's getter
* @param o (o) - value
* @param N - it's index
* @return FALSE if failed
*/
static int getval(struct sensordata_t* s, val_t *o, int N){
if(N < 0 || N >= NS) return FALSE;
if(o) *o = s->values[N];
return TRUE;
}
sensordata_t sensor = {
.name = "Dummy weatherstation",
.Nvalues = NS,
.init = init,
.onrefresh = common_onrefresh,
.get_value = getval,
.kill = common_kill,
};

View File

@@ -0,0 +1,151 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2026 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <string.h>
#include <time.h>
#include "weathlib.h"
// dummy example of file descriptors usage
#define NS (4)
extern sensordata_t sensor;
static const val_t values[NS] = { // fields `name` and `comment` have no sense until value meaning is `IS_OTHER`
{.sense = VAL_OBLIGATORY, .type = VALT_FLOAT, .meaning = IS_WIND},
{.sense = VAL_OBLIGATORY, .type = VALT_FLOAT, .meaning = IS_AMB_TEMP},
{.sense = VAL_RECOMMENDED, .type = VALT_FLOAT, .meaning = IS_PRESSURE},
{.sense = VAL_RECOMMENDED, .type = VALT_FLOAT, .meaning = IS_HUMIDITY},
};
static int format_values(char *buf){
int gotvals = 0;
char *token = strtok(buf, ",");
time_t tnow = time(NULL);
while(token && gotvals < NS){
double v;
DBG("TOKEN: %s", token);
if(sl_str2d(&v, token)){
DBG("next value: %g", v);
sensor.values[gotvals].value.f = (float) v;
sensor.values[gotvals].time = tnow;
++gotvals;
}
token = strtok(NULL, ",");
}
DBG("GOT: %d", gotvals);
return gotvals;
}
static ssize_t writedata(int fd, const char *str, size_t size){
ssize_t sent = 0;
do{
DBG("try to write %zd bytes", size);
int canwrite = sl_canwrite(fd);
if(canwrite < 0){
WARNX("Disconnected?!");
return -1;
}else if(canwrite){
ssize_t r = write(fd, str+sent, size);
if(r < 0){
sent = -1;
WARNX("Disconnected??");
break;
}else{
sent += r;
size -= r;
}
DBG("sent %zd bytes; total send %zd, leave %zd", r, sent, size);
}
}while(size);
return sent;
}
static void *mainthread(void _U_ *U){
FNAME();
time_t task = 0;
const char begging[] = "Enter comma-separated data: wind, exttemp, pressure, humidity\n";
char buf[128];
while(sensor.fdes > -1){
time_t tnow = time(NULL);
int canread = sl_canread(sensor.fdes);
if(canread < 0){
WARNX("Disconnected fd %d", sensor.fdes);
break;
}else if(canread == 1){
ssize_t got = read(sensor.fdes, buf, 128);
if(got > 0){
sl_RB_write(sensor.ringbuffer, (uint8_t*)buf, got);
}else if(got < 0){
DBG("Disconnected?");
break;
}
}
if(sl_RB_readline(sensor.ringbuffer, buf, 127) > 0){
if(NS == format_values(buf) && sensor.freshdatahandler)
sensor.freshdatahandler(&sensor);
}
if(sensor.tpoll){
if(tnow >= task){
DBG("write %s", begging);
ssize_t got = writedata(sensor.fdes, begging, sizeof(begging)-1);
if(got > 0) task = tnow + sensor.tpoll;
else if(got < 0){
close(sensor.fdes);
sensor.fdes = -1;
}
}
}
}
DBG("OOOOps!");
return NULL;
}
static int init(struct sensordata_t *s, int N, time_t pollt, int fd){
FNAME();
if(!s) return -1;
s->fdes = fd;
if(s->fdes < 0) return -1;
sensor.PluginNo = N;
if(pollt) s->tpoll = pollt;
if(pthread_create(&s->thread, NULL, mainthread, NULL)) return -1;
s->values = MALLOC(val_t, NS);
// don't use memcpy, as `values` could be aligned
for(int i = 0; i < NS; ++i) s->values[i] = values[i];
if(!(s->ringbuffer = sl_RB_new(BUFSIZ))){
WARNX("Can't init ringbuffer!");
return -1;
}
return NS;
}
static int getval(struct sensordata_t *s, val_t *o, int N){
if(!s || N < 0 || N >= NS) return FALSE;
if(o) *o = s->values[N];
return TRUE;
}
sensordata_t sensor = {
.name = "Dummy socket or serial device weatherstation",
.Nvalues = NS,
.init = init,
.onrefresh = common_onrefresh,
.get_value = getval,
.kill = common_kill,
};

View File

@@ -0,0 +1,226 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <dlfcn.h>
#include <string.h>
#include <usefull_macros.h>
#include "fd.h"
#include "sensors.h"
#define WARNXL(...) do{ LOGWARN(__VA_ARGS__); WARNX(__VA_ARGS__); } while(0)
#define WARNL(...) do{ LOGWARN(__VA_ARGS__); WARN(__VA_ARGS__); } while(0)
#define ERRXL(...) do{ LOGERR(__VA_ARGS__); ERRX(__VA_ARGS__); } while(0)
#define ERRL(...) do{ LOGERR(__VA_ARGS__); ERR(__VA_ARGS__); } while(0)
// poll each `poll_interval` seconds
static time_t poll_interval = 15;
static int nplugins = 0;
static sensordata_t **allplugins = NULL;
int get_nplugins(){
return nplugins;
}
// set polling interval
int set_pollT(time_t t){
if(t == 0 || t > MAX_POLLT) return FALSE;
poll_interval = t;
return TRUE;
}
/**
* @brief get_plugin - get link to opened plugin
* @param o (o) - plugin with given index
* @param N - index in `allplugins`
* @return NULL if failed or pointer
*/
sensordata_t *get_plugin(int N){
if(N < 0 || N >= nplugins) return NULL;
return allplugins[N];
}
void *open_plugin(const char *name){
DBG("try to open lib %s", name);
void* dlh = dlopen(name, RTLD_NOLOAD); // library may be already opened
if(!dlh){
DBG("Not loaded - load");
dlh = dlopen(name, RTLD_NOW);
}
if(!dlh){
char *e = dlerror();
WARNXL("Can't find plugin! %s", (e) ? e : "");
return NULL;
}
return dlh;
}
#ifdef EBUG
// in release this function can be used for meteo logging
static void dumpsensors(struct sensordata_t* station){
FNAME();
if(!station || !station->get_value || station->Nvalues < 1) return;
char buf[FULL_LEN+1];
uint64_t Tsum = 0; int nsum = 0;
int N = (nplugins > 1) ? station->PluginNo : -1;
for(int i = 0; i < station->Nvalues; ++i){
val_t v;
if(!station->get_value(station, &v, i)) continue;
if(0 < format_sensval(&v, buf, FULL_LEN+1, N)){
printf("%s\n", buf);
++nsum; Tsum += v.time;
}
}
time_t last = (time_t)(Tsum / nsum);
if(0 < format_msrmttm(last, buf, FULL_LEN+1)){
printf("%s\n\n", buf);
}
}
#endif
/**
* @brief openplugins - open sensors' plugin and init it
* @param paths - paths to plugins
* @param N - amount of plugins
* @return amount of opened and inited plugins
* This function should be runned only once at start
*/
int openplugins(char **paths, int N){
char buf[PATH_MAX+1];
if(!paths || !*paths || N < 1) return 0;
if(allplugins || nplugins){
WARNXL("Plugins already opened"); return 0;
}
allplugins = MALLOC(sensordata_t*, N);
green("Try to open plugins:\n");
for(int i = 0; i < N; ++i){
printf("\tplugin[%d]=%s\n", i, paths[i]);
snprintf(buf, PATH_MAX, "%s", paths[i]);
char *colon = strchr(buf, ':');
if(colon) *colon++ = 0;
void* dlh = open_plugin(buf);
if(!dlh) continue;
DBG("OPENED");
void *s = dlsym(dlh, "sensor");
if(s){
sensordata_t *S = (sensordata_t*) s;
if(!S->get_value) WARNXL("Sensor library %s have no values' getter!", paths[i]);
if(!S->init){
WARNXL("Sensor library %s have no init funtion");
continue;
}
int fd = -1;
if(colon) fd = getFD(colon);
int ns = S->init(S, nplugins, poll_interval, fd); // here nplugins is index in array
if(ns < 1) WARNXL("Can't init plugin %s", paths[i]);
else{
#ifdef EBUG
if(!S->onrefresh(S, dumpsensors)) WARNXL("Can't init refresh funtion");
#endif
LOGMSG("Plugin %s nave %d sensors", paths[i], ns);
allplugins[nplugins++] = S;
}
}else WARNXL("Can't find field `sensor` in plugin %s: %s", paths[i], dlerror());
}
return nplugins;
}
/**
* @brief closeplugins - call `die` function for all sensors
* This function should be runned at exit
*/
void closeplugins(){
if(!allplugins || nplugins < 1) return;
for(int i = 0; i < nplugins; ++i){
if(allplugins[i]->kill) allplugins[i]->kill(allplugins[i]);
}
FREE(allplugins);
nplugins = 0;
}
/**
* @brief format_sensval - snprintf sensor's value into buffer
* @param v - value to get
* @param buf - buffer
* @param buflen - full length of `buf`
* @param Np - if Np>-1, show it as plugin number (added to field name in square brackets, like WIND[1]);
* @return amount of symbols printed or -1 if error
*/
int format_sensval(const val_t *v, char *buf, int buflen, int Np){
--buflen; // for trailing zero
if(!v || !buf || buflen < FULL_LEN) return -1;
char strval[VAL_LEN+1];
switch(v->type){
case VALT_UINT: snprintf(strval, VAL_LEN, "%u", v->value.u); break;
case VALT_INT: snprintf(strval, VAL_LEN, "%d", v->value.i); break;
case VALT_FLOAT: snprintf(strval, VAL_LEN, "%g", v->value.f); break;
default: sprintf(strval, "'ERROR'");
}
const char* const NM[] = { // names of standard fields
[IS_WIND] = "WIND",
[IS_WINDDIR] = "WINDDIR",
[IS_HUMIDITY] = "HUMIDITY",
[IS_AMB_TEMP] = "EXTTEMP",
[IS_INNER_TEMP] = "INTTEMP",
[IS_HW_TEMP] = "HWTEMP", // mirror?
[IS_PRESSURE] = "PRESSURE",
[IS_PRECIP] = "PRECIP",
[IS_PRECIP_LEVEL]="PRECIPLV",
[IS_MIST] = "MIST",
[IS_CLOUDS] = "CLOUDS",
[IS_SKYTEMP] = "SKYTEMP"
};
const char* const CMT[] = { // comments for standard fields
[IS_WIND] = "Wind, m/s",
[IS_WINDDIR] = "Wind direction, degr (CW from north to FROM)",
[IS_HUMIDITY] = "Humidity, percent",
[IS_AMB_TEMP] = "Ambient temperature, degC",
[IS_INNER_TEMP] = "In-dome temperature, degC",
[IS_HW_TEMP] = "Hardware (mirror?) termperature, degC",
[IS_PRESSURE] = "Atmospheric pressure, mmHg",
[IS_PRECIP] = "Precipitation (1 - yes, 0 - no)",
[IS_PRECIP_LEVEL]="Precipitation level (mm)",
[IS_MIST] = "Mist (1 - yes, 0 - no)",
[IS_CLOUDS] = "Integral clouds value (bigger - better)",
[IS_SKYTEMP] = "Mean sky temperatyre"
};
const char *name = NULL, *comment = NULL;
int idx = v->meaning;
if(idx < IS_OTHER){
name = NM[idx];
comment = CMT[idx];
}else{
name = v->name;
comment = v->comment;
}
int got;
if(Np > -1) got = snprintf(buf, buflen, "%s[%d]=%s / %s", name, Np, strval, comment);
else got = snprintf(buf, buflen, "%s=%s / %s", name, strval, comment);
return got;
}
// the same for measurement time formatting
int format_msrmttm(time_t t, char *buf, int buflen){
--buflen; // for trailing zero
if(!buf || buflen < FULL_LEN) return -1;
char cmt[COMMENT_LEN+1];
struct tm *T = localtime(&t);
strftime(cmt, COMMENT_LEN, "%F %T", T);
return snprintf(buf, buflen, "TMEAS=%zd / Last measurement time: %s", t, cmt);
}

View File

@@ -0,0 +1,32 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "weathlib.h"
// don't allow to set polling time more than 10 minutes
#define MAX_POLLT (600)
int openplugins(char **paths, int N);
void closeplugins();
sensordata_t *get_plugin(int N);
int get_nplugins();
int format_sensval(const val_t *v, char *buf, int buflen, int Np);
int format_msrmttm(time_t t, char *buf, int buflen);
int set_pollT(time_t t);

View File

@@ -0,0 +1,229 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <signal.h>
#include <string.h>
#include <usefull_macros.h>
#include "sensors.h"
#include "server.h"
// if measurement time oldest than now minus `oldest_interval`, we think measurement are too old
static time_t oldest_interval = 60;
// server's sockets: net and local (UNIX)
static sl_sock_t *netsocket = NULL, *localsocket;
//static pthread_t netthread, locthread;
// show user current time
static sl_sock_hresult_e timehandler(sl_sock_t *client, _U_ sl_sock_hitem_t *item, _U_ const char *req){
if(!client) return RESULT_FAIL;
char buf[32];
snprintf(buf, 31, "UNIXT=%.3f\n", sl_dtime());
sl_sock_sendstrmessage(client, buf);
return RESULT_SILENCE;
}
// show all connected libraries
static sl_sock_hresult_e listhandler(sl_sock_t *client, _U_ sl_sock_hitem_t *item, _U_ const char *req){
if(!client) return RESULT_FAIL;
char buf[256];
int N = get_nplugins();
if(N < 1) return RESULT_FAIL;
sensordata_t *d = NULL;
for(int i = 0; i < N; ++i){
if(!(d = get_plugin(i))) continue;
snprintf(buf, 255, "PLUGIN[%d]=%s\nNVALUES[%d]=%d\n", i, d->name, i, d->Nvalues);
sl_sock_sendstrmessage(client, buf);
}
return RESULT_SILENCE;
}
/**
* @brief showdata - send to user meteodata
* @param client - client data
* @param N - index of station
* @param showidx - == TRUE to show index in square brackets
*/
static void showdata(sl_sock_t *client, int N, int showidx){
char buf[FULL_LEN+1];
val_t v;
sensordata_t *s = NULL;
if(!(s = get_plugin(N)) || (s->Nvalues < 1)){
snprintf(buf, FULL_LEN, "Can't get plugin[%d]\n", N);
sl_sock_sendstrmessage(client, buf);
return;
}
if(!showidx || get_nplugins() == 1) N = -1; // only one -> don't show indexes
time_t oldest = time(NULL) - oldest_interval;
uint64_t Tsum = 0; int nsum = 0;
for(int i = 0; i < s->Nvalues; ++i){
if(!s->get_value(s, &v, i)) continue;
if(v.time < oldest) continue;
if(1 > format_sensval(&v, buf, FULL_LEN+1, N)) continue;
DBG("formatted: '%s'", buf);
sl_sock_sendstrmessage(client, buf);
sl_sock_sendbyte(client, '\n');
++nsum; Tsum += v.time;
}
oldest = (time_t)(Tsum / nsum);
if(0 < format_msrmttm(oldest, buf, FULL_LEN+1)){ // send mean measuring time
DBG("Formatted time: '%s'", buf);
sl_sock_sendstrmessage(client, buf);
sl_sock_sendbyte(client, '\n');
}
}
// get meteo data
static sl_sock_hresult_e gethandler(sl_sock_t *client, _U_ sl_sock_hitem_t *item, const char *req){
if(!client) return RESULT_FAIL;
int N = get_nplugins();
if(N < 1) return RESULT_FAIL;
if(!req) for(int i = 0; i < N; ++i) showdata(client, i, TRUE);
else{
int n;
if(!sl_str2i(&n, req) || n < 0 || n >= N) return RESULT_BADVAL;
showdata(client, n, FALSE);
}
return RESULT_SILENCE;
}
// graceful closing socket: let client know that he's told to fuck off
static void toomuch(int fd){
const char *m = "Try later: too much clients connected\n";
send(fd, m, sizeof(m)-1, MSG_NOSIGNAL);
shutdown(fd, SHUT_WR);
DBG("shutdown, wait");
double t0 = sl_dtime();
uint8_t buf[8];
while(sl_dtime() - t0 < 90.){ // change this value to smaller for real work
if(sl_canread(fd)){
ssize_t got = read(fd, buf, 8);
DBG("Got=%zd", got);
if(got < 1) break;
}
}
DBG("Disc after %gs", sl_dtime() - t0);
LOGWARN("Client fd=%d tried to connect after MAX reached", fd);
}
// new connections handler (return FALSE to reject client)
static int connected(sl_sock_t *c){
if(c->type == SOCKT_UNIX) LOGMSG("New local client fd=%d connected", c->fd);
else LOGMSG("New client fd=%d, IP=%s connected", c->fd, c->IP);
return TRUE;
}
// disconnected handler
static void disconnected(sl_sock_t *c){
if(c->type == SOCKT_UNIX) LOGMSG("Disconnected local client fd=%d", c->fd);
else LOGMSG("Disconnected client fd=%d, IP=%s", c->fd, c->IP);
}
static sl_sock_hresult_e defhandler(struct sl_sock *s, const char *str){
if(!s || !str) return RESULT_FAIL;
sl_sock_sendstrmessage(s, "You entered wrong command:\n```\n");
sl_sock_sendstrmessage(s, str);
sl_sock_sendstrmessage(s, "\n```\nTry \"help\"\n");
return RESULT_SILENCE;
}
// handlers for network and local (UNIX) sockets
static sl_sock_hitem_t nethandlers[] = { // net - only getters and client-only setters
{gethandler, "get", "get all meteo or only for given plugin number", NULL},
{listhandler, "list", "show all opened plugins", NULL},
{timehandler, "time", "get server's UNIX time", NULL},
{NULL, NULL, NULL, NULL}
};
static sl_sock_hitem_t localhandlers[] = { // local - full amount of setters/getters
{gethandler, "get", "get all meteo or only for given plugin number", NULL},
{listhandler, "list", "show all opened plugins", NULL},
{timehandler, "time", "get server's UNIX time", NULL},
{NULL, NULL, NULL, NULL}
};
#if 0
// common parsers for both net and local sockets
static void *cmdparser(void *U){
if(!U) return NULL;
sl_sock_t *s = (sl_sock_t*) U;
while(s && s->connected){
if(!s->rthread){
LOGERR("Server's handlers' thread is dead");
break;
}
}
LOGDBG("cmdparser(): exit");
return NULL;
}
#endif
int start_servers(const char *netnode, const char *sockpath){
if(!netnode || !sockpath){
LOGERR("start_servers(): need arguments");
return FALSE;
}
netsocket = sl_sock_run_server(SOCKT_NET, netnode, BUFSIZ, nethandlers);
if(!netsocket){
LOGERR("start_servers(): can't run network socket");
return FALSE;
}
localsocket = sl_sock_run_server(SOCKT_UNIX, sockpath, BUFSIZ, localhandlers);
if(!localsocket){
LOGERR("start_servers(): can't run local socket");
return FALSE;
}
sl_sock_changemaxclients(netsocket, MAX_CLIENTS);
sl_sock_changemaxclients(localsocket, 1);
sl_sock_maxclhandler(netsocket, toomuch);
sl_sock_maxclhandler(localsocket, toomuch);
sl_sock_connhandler(netsocket, connected);
sl_sock_connhandler(localsocket, connected);
sl_sock_dischandler(netsocket, disconnected);
sl_sock_dischandler(localsocket, disconnected);
sl_sock_defmsghandler(netsocket, defhandler);
sl_sock_defmsghandler(localsocket, defhandler);
#if 0
if(pthread_create(&netthread, NULL, cmdparser, (void*)netsocket)){
LOGERR("Can't run server's net thread");
goto errs;
}
if(pthread_create(&locthread, NULL, cmdparser, (void*)localsocket)){
LOGERR("Can't run server's local thread");
goto errs;
}
#endif
return TRUE;
#if 0
errs:
sl_sock_delete(&localsocket);
sl_sock_delete(&netsocket);
return FALSE;
#endif
}
void kill_servers(){
//pthread_cancel(locthread);
//pthread_cancel(netthread);
//LOGMSG("Server threads canceled");
//usleep(500);
sl_sock_delete(&localsocket);
sl_sock_delete(&netsocket);
LOGMSG("Server sockets destroyed");
//usleep(500);
//pthread_kill(locthread, 9);
//pthread_kill(netthread, 9);
//LOGMSG("Server threads killed");
}

View File

@@ -0,0 +1,25 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
// maximal amount of simultaneous clients connected
#define MAX_CLIENTS (30)
int start_servers(const char *netnode, const char *sockpath);
void kill_servers();

View File

@@ -0,0 +1 @@
-std=c17

View File

@@ -0,0 +1,4 @@
#define EBUG 1
#define _GNU_SOURCE
#define _XOPEN_SOURCE 1111
#define _POSIX_C_SOURCE 200000

View File

@@ -0,0 +1 @@
[General]

View File

@@ -0,0 +1 @@
-std=c++17

View File

@@ -0,0 +1,14 @@
CMakeLists.txt
cmdlnopts.c
cmdlnopts.h
fd.c
fd.h
main.c
plugins/dummy.c
plugins/fdexample.c
sensors.c
sensors.h
server.c
server.h
weathlib.c
weathlib.h

View File

@@ -0,0 +1 @@
.

View File

@@ -0,0 +1,66 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2026 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
// Some common functions and handlers for sensors
#include "weathlib.h"
/**
* @brief sensor_alive - test if sensor's thread isn't dead
* @param s - sensor
* @return FALSE if thread is dead
*/
int sensor_alive(sensordata_t *s){
if(!s) return FALSE;
if(pthread_kill(s->thread, 0)) return FALSE;
return TRUE;
}
/**
* @brief common_onrefresh - common `change onrefresh handler`
* @param s - sensor
* @return FALSE if failed
*/
int common_onrefresh(sensordata_t *s, void (*handler)(sensordata_t *)){
FNAME();
if(!s || !handler) return FALSE;
s->freshdatahandler = handler;
return TRUE;
}
/**
* @brief common_kill - common `die` function
* @param s - sensor
*/
void common_kill(sensordata_t *s){
FNAME();
if(!s) return;
if(0 == pthread_kill(s->thread, -9)){
DBG("%s main thread killed, join", s->name);
pthread_join(s->thread, NULL);
DBG("Done");
}
DBG("Delete RB");
sl_RB_delete(&s->ringbuffer);
if(s->fdes > -1){
close(s->fdes);
DBG("FD closed");
}
FREE(s->values);
DBG("Sensor %s killed", s->name);
}

View File

@@ -0,0 +1,108 @@
/*
* This file is part of the weatherdaemon project.
* Copyright 2025 Edward V. Emelianov <edward.emelianoff@gmail.com>.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <pthread.h>
#include <signal.h> // pthread_kill
#include <stdint.h>
#include <time.h>
#include <usefull_macros.h>
// length (in symbols) of key, value and comment
#define KEY_LEN (8)
#define VAL_LEN (31)
#define COMMENT_LEN (63)
// maximal full length of "KEY=val / comment" (as for sfitsio)
#define FULL_LEN (81)
// name of meteo-plugin
#define NAME_LEN (127)
// importance of values
typedef enum{
VAL_OBLIGATORY, // can't be omitted
VAL_RECOMMENDED, // recommended to show
VAL_UNNECESSARY, // may be shown by user request
VAL_BROKEN // sensor is broken, omit it
} valsense_t;
// meaning of values
typedef enum{
IS_WIND, // wind, m/s
IS_WINDDIR, // wind direction, degr
IS_HUMIDITY, // humidity, percent
IS_AMB_TEMP, // ambient temperature, degC
IS_INNER_TEMP, // in-dome temperature, degC
IS_HW_TEMP, // hardware (?) termperature, degC
IS_PRESSURE, // atmospheric pressure, mmHg
IS_PRECIP, // precipitation (1 - yes, 0 - no)
IS_PRECIP_LEVEL, // precipitation level (mm)
IS_MIST, // mist (1 - yes, 0 - no)
IS_CLOUDS, // integral clouds value (bigger - better)
IS_SKYTEMP, // mean sky temperatyre
IS_OTHER // something other - read "name" and "comment"
} valmeaning_t;
typedef union{
uint32_t u;
int32_t i;
float f;
} num_t;
// type of value
typedef enum{
VALT_UINT,
VALT_INT,
VALT_FLOAT,
//VALT_STRING,
} valtype_t;
// value
typedef struct{
char name[KEY_LEN+1]; // max VAL_LEN symbols FITS header keyword name
char comment[COMMENT_LEN+1];// max COMMENT_LEN symbols of comment to FITS header
valsense_t sense; // importance
valtype_t type; // type of given value
valmeaning_t meaning; // what type of sensor is it
num_t value; // value itself
time_t time; // last changing time
} val_t;
// all sensor's data
// all functions have `this` as first arg
typedef struct sensordata_t{
char name[NAME_LEN+1]; // max 31 symbol of sensor's name (e.g. "rain sensor")
int Nvalues; // amount of values
int PluginNo; // plugin number in array (if several)
int (*init)(struct sensordata_t*, int, time_t, int); // init meteostation with given PluginNo, poll_interval and fd; return amount of parameters found or -1 if error
int (*onrefresh)(struct sensordata_t*, void (*handler)(struct sensordata_t*)); // handler of new data; return TRUE if OK
int (*get_value)(struct sensordata_t*, val_t*, int); // getter of Nth value
void (*kill)(struct sensordata_t*); // close everything and remove sensor
// private members:
val_t *values; // array of values
pthread_t thread; // main thread
void (*freshdatahandler)(struct sensordata_t*); // handler of fresh data
int fdes; // file descriptor of device/socket
sl_ringbuffer_t *ringbuffer; // ringbuffer for device reading
time_t tpoll; // forced polling time for sensor
} sensordata_t;
// library functions and other
int common_onrefresh(sensordata_t*, void (*handler)(sensordata_t*));
void common_kill(sensordata_t *s);
int sensor_alive(sensordata_t *s);