Skip to content
Snippets Groups Projects
TerminalControl.cpp 4.85 KiB
Newer Older
//
// Created by philipp on 26.04.18.
//

#include "../include/VeloxProtocolLib/Connection.h"
#include <iostream>
#include <boost/algorithm/string.hpp>
Hoop77's avatar
-  
Hoop77 committed
#include <fstream>
Hoop77's avatar
-  
Hoop77 committed
#include "ultrasonic/UltrasonicSensor.h"
#include "tools/StreamMeanFilter.h"
Hoop77's avatar
-  
Hoop77 committed
constexpr float MAX_SPEED = 0.1f;
Hoop77's avatar
-  
Hoop77 committed
constexpr float BRAKE_SPEED = -0.06f * 4;
Hoop77's avatar
Hoop77 committed

Hoop77's avatar
-  
Hoop77 committed
int readDevId()
{
    // open config file
    std::string userHome = getenv("HOME");
    std::ifstream configFile;
    configFile.open(userHome + "/CarConfig/sensor.config", std::ifstream::in);
    if (!configFile.is_open())
    { throw std::runtime_error{"File '/CarConfig/sensor.config' not found!\n"}; }

    // desired parameters
    int devId;
    bool devIdFound{false};
    std::string contentLine;
    while (!configFile.eof())
    {
        std::getline(configFile, contentLine);

        // split this line
        std::istringstream iss(contentLine);
        std::vector<std::string> words{std::istream_iterator<std::string>{iss}, {}};

        if (words.size() > 1)
        { // this line contains parameter[at(0)] and value[at(1)]
            if (words.at(0) == "devId:")
            {
                std::stringstream ss;
                ss << std::hex << words.at(1);
                ss >> devId;
                devIdFound = true;
            }
        }
    }

    if (!devIdFound)
    { throw std::runtime_error{"No attribute devId found!\n"}; }

    configFile.close();

    return devId;
}

int main(int argc, char ** argv)
{
    using namespace veloxProtocol;
    networking::Networking net;
Hoop77's avatar
-  
Hoop77 committed
    std::atomic<bool> monitorSTM{false};
    std::atomic<bool> monitorUSS{false};
Hoop77's avatar
-  
Hoop77 committed
    std::atomic<float> speed{0.0f};
Hoop77's avatar
-  
Hoop77 committed
    std::atomic<float> stopDistance{0};
Hoop77's avatar
-  
Hoop77 committed
    std::mutex outputMutex;
Hoop77's avatar
-  
Hoop77 committed
    UltrasonicSensor sensor{readDevId()};
Hoop77's avatar
-  
Hoop77 committed
    car::StreamMeanFilter streamMeanFilter{5};
Hoop77's avatar
-  
Hoop77 committed
    auto timer = networking::time::Timer::create(net);
    auto conn = Connection::create(net);
    conn->open(
        "/dev/ttySAC0",
        [&]
        {
Hoop77's avatar
-  
Hoop77 committed
            if (!monitorSTM)
Hoop77's avatar
-  
Hoop77 committed
            std::lock_guard<std::mutex> lock{outputMutex};
            std::cout << "[STM Update]\nSpeed=" << conn->getMeasuredSpeed().get()
                      << "\nSteering Angle: " << conn->getMeasuredSteeringAngle().get() << "\n\n";
Hoop77's avatar
-  
Hoop77 committed
        }, [] {});
Hoop77's avatar
-  
Hoop77 committed
    sensor.init();
    timer = networking::time::Timer::create(net);
    timer->startPeriodicTimeout(
        std::chrono::milliseconds(UltrasonicSensor::DELAY),
Hoop77's avatar
-  
Hoop77 committed
        [&]
        {
Hoop77's avatar
-  
Hoop77 committed
            auto originalDistance = sensor.getDistance();
            auto filteredDistance = streamMeanFilter.moveWindow(originalDistance);
Hoop77's avatar
-  
Hoop77 committed
            if (filteredDistance <= stopDistance)
Hoop77's avatar
-  
Hoop77 committed
                conn->setSpeed(BRAKE_SPEED);
Hoop77's avatar
-  
Hoop77 committed
            else
                conn->setSpeed(speed);
Hoop77's avatar
-  
Hoop77 committed

Hoop77's avatar
-  
Hoop77 committed
            if (!monitorUSS)
                return;
Hoop77's avatar
-  
Hoop77 committed

Hoop77's avatar
-  
Hoop77 committed
            std::lock_guard<std::mutex> lock{outputMutex};
Hoop77's avatar
-  
Hoop77 committed
            std::cout << "[USS Update]\n"
                      << "Original Distance=" << originalDistance << "\n"
                      << "Filtered Distance=" << filteredDistance << "\n\n";
Hoop77's avatar
-  
Hoop77 committed
        });
Hoop77's avatar
-  
Hoop77 committed

    std::cout << "\n\nMANUAL\n"
              << "------\n"
              << "Enter 'stm' to enable/disable monitoring for STM data.\n"
              << "Enter 'uss' to enable/disable monitoring for USS data.\n"
              << "Enter 'q' to quit.\n"
              << "Enter 's <float> t' to set speed\n"
              << "Enter 'a <float>' to set angle\n"
              << "\n\n";

    for (std::string in; in != "q"; std::getline(std::cin, in))
    {
Hoop77's avatar
-  
Hoop77 committed
        try
Hoop77's avatar
-  
Hoop77 committed
        {
Hoop77's avatar
-  
Hoop77 committed
            if (in == "stm")
                monitorSTM = !monitorSTM;
            else if (in == "uss")
                monitorUSS = !monitorUSS;
            else
Hoop77's avatar
Hoop77 committed
            {
Hoop77's avatar
-  
Hoop77 committed
                std::vector<std::string> split;
                boost::split(split, in, [](char c) { return c == ' '; });

                std::string cmd = split.at(0);
                float value = std::stof(split.at(1));

                if (cmd == "a")
                {
                    std::cout << "Setting steering angle to: " << value << "\n";
                    conn->setSteeringAngle(value);
                }
                else if (cmd == "s")
                {
                    value /= 100.0f;
                    if (std::abs(value) > MAX_SPEED)
                    {
                        value = value >= 0 ? MAX_SPEED : -MAX_SPEED;
                        std::cout << "WARNING: Speed set to 1.0 due to risk of collision!\n";
                    }
                    speed = value;
Hoop77's avatar
-  
Hoop77 committed
                    stopDistance = speed.load() * 100 * 15;
Hoop77's avatar
-  
Hoop77 committed
                    std::cout << "Setting speed to: " << value << "\n";
                }
Hoop77's avatar
Hoop77 committed
            }
Hoop77's avatar
-  
Hoop77 committed
        catch (...)
Hoop77's avatar
-  
Hoop77 committed
        {
Hoop77's avatar
-  
Hoop77 committed
            std::cout << "Invalid input! The car brakes now!\n";
Hoop77's avatar
-  
Hoop77 committed
            speed = BRAKE_SPEED;
Hoop77's avatar
-  
Hoop77 committed
        }
Hoop77's avatar
-  
Hoop77 committed
    timer->stop();
Hoop77's avatar
-  
Hoop77 committed
    conn->setSpeed(BRAKE_SPEED);
Hoop77's avatar
-  
Hoop77 committed
    conn->close();