goodrobots / vision_landing

Precision landing using visual targets
GNU General Public License v3.0
202 stars 71 forks source link

Deactivate when FC not in precland/precloiter mode #36

Closed fnoop closed 7 years ago

fnoop commented 7 years ago

Only activate opencv/aruco vision processing when in landing/precloiter mode, to save (a lot of) CPU cycles. Will need to alter comms between python/c++ processes to allow c++ code to receive instructions as it's not directly connected to mavlink.

fnoop commented 7 years ago

Need to communicate two ways with track_targets - currently vision_landing wrapper just listens but doesn't write. Tried writing to track_targets.stdin but it conflicts with the signal handling:

// Setup stdin listener
    string incommand;
    pollfd cinfd[1];
    cinfd[0].fd = fileno(stdin);
    cinfd[0].events = POLLIN;
while (true) {
// Listen for commands on stdin
        if (poll(cinfd, 1, 1000))
        {
            cerr << "INCOMING MESSAGE!:" << endl;
            getline(cin, incommand);
            cerr << "MESSAGE RECEIVED!:" << incommand << endl;
        }
}
fnoop commented 7 years ago

For now, just use signals - eg. sigusr1/sigusr2 to handle stop/start communications.

fnoop commented 7 years ago

Looks like Craft.process doesn't allow to send stdin or signals, might be because it's bound to threaded reader?

fnoop commented 7 years ago

Implemented crude mechanism in track_targets: SIGUSR1 turns vision processing on SIGUSR2 turns vision processing off