Now you can change the default /tmp directory with the flag --log_dir

$ ./gnss-sdr --log_dir=./log

Added some documentation and comments

git-svn-id: https://svn.code.sf.net/p/gnss-sdr/code/trunk@101 64b25241-fba3-4117-9849-534c7e92360d
This commit is contained in:
Carles Fernandez 2011-12-27 21:21:12 +00:00
parent 27b5074152
commit 0cee2be18f
11 changed files with 246 additions and 127 deletions

View File

@ -76,7 +76,7 @@ gps_l1_ca_pvt_cc::gps_l1_ca_pvt_cc(unsigned int nchannels, gr_msg_queue_sptr que
d_averaging_depth=averaging_depth;
d_flag_averaging=flag_averaging;
/*!
* \todo Enable RINEX printer: The actual RINEX printer need a complete refactoring and some bug fixing work
* \todo Enable RINEX printer: The current RINEX printer need a complete refactoring and some bug fixing work
*/
//d_rinex_printer.set_headers("GNSS-SDR");
d_ls_pvt=new gps_l1_ca_ls_pvt(nchannels,d_dump_filename,d_dump);

View File

@ -136,7 +136,7 @@ void gps_l1_ca_pcps_acquisition_cc::set_satellite(unsigned int satellite)
code_gen_complex_sampled(d_fft_if->get_inbuf(), satellite, d_fs_in, 0);
d_fft_if->execute(); // We need the FFT of GPS C/A code
//Conjugate the local code
//TODO Optimize it !
//TODO Optimize it ! try conj()
for (unsigned int i = 0; i < d_fft_size; i++)
{
d_fft_codes[i] = std::complex<float>(
@ -172,12 +172,12 @@ int gps_l1_ca_pcps_acquisition_cc::general_work(int noutput_items,
/*!
* By J.Arribas
* Acquisition A strategy (Kay Borre book + CFAR threshold):
* 1º- Compute the input signal power estimation
* 2º- Doppler serial search loop
* 3º- Perform the FFT-based circular convolution (parallel time search)
* 4º- record the maximum peak and the associated synchronization parameters
* 5º- Compute the test statistics and compare to the threshold
* 6º- Declare positive or negative acquisition using a message queue
* 1. Compute the input signal power estimation
* 2. Doppler serial search loop
* 3. Perform the FFT-based circular convolution (parallel time search)
* 4. Record the maximum peak and the associated synchronization parameters
* 5. Compute the test statistics and compare to the threshold
* 6. Declare positive or negative acquisition using a message queue
*/
if (!d_active)
@ -217,7 +217,8 @@ int gps_l1_ca_pcps_acquisition_cc::general_work(int noutput_items,
<< d_threshold << ", doppler_max: " << d_doppler_max
<< ", doppler_step: " << d_doppler_step;
// 1º Compute the input signal power estimation
// 1- Compute the input signal power estimation
//! \TODO try norm()
for (i = 0; i < d_fft_size; i++)
{
d_input_power += std::abs(in[i]) * std::abs(in[i]);
@ -225,7 +226,7 @@ int gps_l1_ca_pcps_acquisition_cc::general_work(int noutput_items,
d_input_power = d_input_power / (float)d_fft_size;
// 2º- Doppler frequency search loop
// 2- Doppler frequency search loop
for (doppler = (int)(-d_doppler_max); doppler < (int)d_doppler_max; doppler
+= d_doppler_step)
{ // doppler search steps
@ -236,8 +237,10 @@ int gps_l1_ca_pcps_acquisition_cc::general_work(int noutput_items,
d_fft_if->get_inbuf()[i] = in[i] * d_sine_if[i];
}
//3º- Perform the FFT-based circular convolution (parallel time search)
d_fft_if->execute(); //TODO Optimize me
//3- Perform the FFT-based circular convolution (parallel time search)
d_fft_if->execute();
//TODO Optimize me
for (i = 0; i < d_fft_size; i++)
{
d_ifft->get_inbuf()[i] = (d_fft_if->get_outbuf()[i]
@ -245,7 +248,7 @@ int gps_l1_ca_pcps_acquisition_cc::general_work(int noutput_items,
}
d_ifft->execute();
// ASM accelerated version
// old version
//x86_gr_complex_mag(d_ifft->get_outbuf(), d_fft_size); // d_ifft->get_outbuf()=|abs(·)|^2 and the array is converted from CPX->Float
//x86_float_max((float*)d_ifft->get_outbuf(), &indext, &magt,
// d_fft_size); // find max of |abs(·)|^2 -> index and magt
@ -274,7 +277,7 @@ int gps_l1_ca_pcps_acquisition_cc::general_work(int noutput_items,
d_dump_file.write((char*)d_ifft->get_outbuf(), n); //write directly |abs(·)|^2 in this Doppler bin
d_dump_file.close();
}
// 4º- record the maximum peak and the associated synchronization parameters
// 4- record the maximum peak and the associated synchronization parameters
if (d_mag < magt)
{
d_mag = magt;
@ -283,9 +286,9 @@ int gps_l1_ca_pcps_acquisition_cc::general_work(int noutput_items,
}
}
// 5º- Compute the test statistics and compare to the threshold
// 5- Compute the test statistics and compare to the threshold
d_test_statistics = 2*d_fft_size*d_mag / d_input_power;
// 6º- Declare positive or negative acquisition using a message queue
// 6- Declare positive or negative acquisition using a message queue
if (d_test_statistics > d_threshold)
{ //0.004

View File

@ -147,11 +147,12 @@ void gps_l1_ca_tong_pcps_acquisition_cc::set_satellite(unsigned int satellite)
d_noise_power = 0.0;
// The GPS codes are generated on the fly using a custom version of the GPS code generator
//! \TODO In-memory codes instead of generated on the fly
code_gen_complex_sampled(d_fft_if->get_inbuf(), satellite, d_fs_in, 0);
d_fft_if->execute(); // We need the FFT of GPS C/A code
//Conjugate the local code
//TODO Optimize it !
//! \TODO Optimize it ! Try conj() or Armadillo
for (unsigned int i = 0; i < d_samples; i++)
{
d_fft_codes[i] = std::complex<float>(
@ -210,22 +211,24 @@ int gps_l1_ca_tong_pcps_acquisition_cc::general_work(int noutput_items,
// vt = noise_envelope * sqrt( -2 * log( d_pfa ) );
// 1º Compute the input signal power estimation
// 1- Compute the input signal power estimation
for (unsigned int i = 0; i < d_samples; i++)
{
d_noise_power += std::abs(in[i]);
}
d_noise_power = sqrt(d_noise_power / (float)d_samples);
//Perform the carrier wipe-off
//2. Perform the carrier wipe-off
sine_gen_complex(d_if_sin, d_freq + d_doppler, d_fs_in, d_samples);
for (unsigned int i = 0; i < d_samples; i++)
{
d_fft_if->get_inbuf()[i] = in[i] * d_if_sin[i];
}
//3º- Perform the FFT-based circular convolution (parallel time search)
d_fft_if->execute(); //TODO Optimize me
//3- Perform the FFT-based circular convolution (parallel time search)
d_fft_if->execute();
//TODO Optimize me: use Armadillo!
for (unsigned int i = 0; i < d_samples; i++)
{
d_ifft->get_inbuf()[i] = d_fft_if->get_outbuf()[i]
@ -233,6 +236,7 @@ int gps_l1_ca_tong_pcps_acquisition_cc::general_work(int noutput_items,
}
d_ifft->execute();
x86_gr_complex_mag(d_ifft->get_outbuf(), d_samples); // d_ifft->get_outbuf()=|abs(·)|^2 and the array is converted from CPX->Float
x86_float_max((float*)d_ifft->get_outbuf(), &d_indext, &magt,
d_samples); // find max of |abs(·)|^2 -> index and magt

View File

@ -1,25 +1,37 @@
/*! \file SSE.cpp
SIMD functionality, mainly for 32 bit interleaved complex integer type (CPX)
*/
/*!
* \file gps_sdr_simd.cc
* \brief SIMD functionality, mainly for 32 bit interleaved complex integer type (CPX)
* \author Copyright 2008 Gregory W Heckler
*
* This class implements operations in assembler (SSE technology in Intel processors)
* It has been copied from Gregory W Heckler's GPS-SDR Project
* Please see http://github.com/gps-sdr/gps-sdr
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2011 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR 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.
*
* GNSS-SDR 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 GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
/************************************************************************************************
Copyright 2008 Gregory W Heckler
This file is part of the GPS Software Defined Radio (GPS-SDR)
The GPS-SDR 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 2 of the
License, or (at your option) any later version.
The GPS-SDR 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 GPS-SDR; if not,
write to the:
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
************************************************************************************************/
#ifdef USE_SIMD
#include "gps_sdr_simd.h"

View File

@ -1,50 +1,54 @@
/*! \file SIMD.h
Contains prototpyes for all the SIMD functions
*/
/************************************************************************************************
Copyright 2008 Gregory W Heckler
This file is part of the GPS Software Defined Radio (GPS-SDR)
The GPS-SDR 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 2 of the
License, or (at your option) any later version.
The GPS-SDR 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 GPS-SDR; if not,
write to the:
Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
************************************************************************************************/
/*!
* \file gps_sdr_simd.cc
* \brief Contains prototypes for SIMD instructions
* \author Copyright 2008 Gregory W Heckler
*
* This class implements operations in assembler (SSE technology in Intel processors)
* It has been copied from Gregory W Heckler's GPS-SDR Project
* Please see http://github.com/gps-sdr/gps-sdr
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2011 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR 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.
*
* GNSS-SDR 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 GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef SIMD_H_
#define SIMD_H_
//#ifdef GLOBALS_HERE
// #define EXTERN
//#else
// #define EXTERN extern
//#endif
#include "gps_sdr_defines.h"
#include "gps_sdr_signal_processing.h"
/* Found in CPUID.cpp */
/*----------------------------------------------------------------------------------------------*/
bool CPU_MMX(); //!< Does the CPU support MMX?
bool CPU_SSE(); //!< Does the CPU support SSE?
bool CPU_SSE2(); //!< Does the CPU support SSE2?
bool CPU_SSE3(); //!< Does the CPU support SSE3?
bool CPU_SSSE3(); //!< Does the CPU support SSSE3? No thats not a typo!
bool CPU_SSE41(); //!< Does the CPU support SSE4.1?
bool CPU_SSE42(); //!< Does the CPU support SSE4.2?
void Init_SIMD(); //!< Initialize the global function pointers
//bool CPU_MMX(); //!< Does the CPU support MMX?
//bool CPU_SSE(); //!< Does the CPU support SSE?
//bool CPU_SSE2(); //!< Does the CPU support SSE2?
//bool CPU_SSE3(); //!< Does the CPU support SSE3?
//bool CPU_SSSE3(); //!< Does the CPU support SSSE3? No thats not a typo!
//bool CPU_SSE41(); //!< Does the CPU support SSE4.1?
//bool CPU_SSE42(); //!< Does the CPU support SSE4.2?
//void Init_SIMD(); //!< Initialize the global function pointers
/*----------------------------------------------------------------------------------------------*/
/* Found in SSE.cpp */

View File

@ -1,9 +1,11 @@
/*!
* \file control_thread.cc
* \brief Brief description of the file here
* \brief This class implements the receiver control plane
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
*
* Detailed description of the file here if needed.
* GNSS Receiver Control Plane: connects the flowgraph, starts running it,
* and while it does not stop, reads the control messages generated by the blocks,
* process them, and apply the corresponding actions.
*
* -------------------------------------------------------------------------
*
@ -71,16 +73,18 @@ ControlThread::~ControlThread()
delete control_message_factory_;
}
/*! Main loop to read and process the control messages
*
* 1- Connect the GNSS receiver flowgraph
* 2- Start the GNSS receiver flowgraph
* while (flowgraph_->running() && !stop)_{
* 3- Read control messages and process them }
*/
void ControlThread::run()
{
/* Runs the control thread
*
* This is the main loop that reads and process the control messages
*
* 1- Connect the GNSS receiver flowgraph
* 2- Start the GNSS receiver flowgraph
* while (flowgraph_->running() && !stop)_{
* 3- Read control messages and process them }
*/
flowgraph_->connect();
if (flowgraph_->connected())
{
@ -128,12 +132,10 @@ void ControlThread::set_control_queue(gr_msg_queue_sptr control_queue)
control_queue_ = control_queue;
}
/*! Creates a control_queue_, a flowgraph_ and a control_message_factory,
* sets stop_ to false and initializes processed_control_messages_ and
* applied_actions_ to zero
*/
void ControlThread::init()
{
// Instantiates a control queue, a GNSS flowgraph, and a control message factory
control_queue_ = gr_make_msg_queue(0);
flowgraph_ = new GNSSFlowgraph(configuration_, control_queue_);
control_message_factory_ = new ControlMessageFactory();

View File

@ -1,8 +1,12 @@
/*!
* \file control_thread.h
* \brief This class represents the main thread of the application, aka control thread.
* \brief Interface of the receiver control plane
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
*
* GNSS Receiver Control Plane: connects the flowgraph, starts running it,
* and while it does not stop, reads the control messages generated by the blocks,
* process them, and apply the corresponding actions.
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2011 (see AUTHORS file for a list of contributors)
@ -45,10 +49,12 @@ class ControlThread
{
public:
//! Default constructor
/*!
* \brief Default constructor
*/
ControlThread();
/*!
* \brief Constructor that initializes the class with parameters
*
@ -56,12 +62,18 @@ public:
*/
ControlThread(ConfigurationInterface *configuration);
//! Virtual destructor. Derived classes must implement the destructor
//! \brief Virtual destructor. Derived classes must implement the destructor
virtual ~ControlThread();
/*!
* \brief Runs the ControlThread
*/
/*! \brief Runs the control thread
*
* This is the main loop that reads and process the control messages
* 1- Connect the GNSS receiver flowgraph
* 2- Start the GNSS receiver flowgraph
* while (flowgraph_->running() && !stop)_{
* 3- Read control messages and process them }
*/
void run();
/*!
@ -71,6 +83,7 @@ public:
*/
void set_control_queue(gr_msg_queue_sptr control_queue);
unsigned int processed_control_messages()
{
return processed_control_messages_;
@ -88,6 +101,7 @@ public:
*/
GNSSFlowgraph* flowgraph()
{
return flowgraph_;
}

View File

@ -215,38 +215,46 @@ GNSSBlockInterface* GNSSBlockFactory::GetBlock(
std::string implementation, unsigned int in_streams,
unsigned int out_streams, gr_msg_queue_sptr queue)
{
/*!
* \brief Returns the block with the required configuration and implementation
*
* PLEASE ADD YOUR NEW BLOCK HERE!!
*/
GNSSBlockInterface* block = NULL;
GNSSBlockInterface* block = NULL; //Change to nullptr when available in compilers (C++11)
// SIGNAL SOURCES
if (implementation.compare("File_Signal_Source") == 0)
{
block = new FileSignalSource(configuration, role, in_streams,
out_streams, queue);
}
else if (implementation.compare("Pass_Through") == 0)
{
block = new PassThrough(configuration, role, in_streams, out_streams);
}
else if (implementation.compare("Null_Sink_Output_Filter") == 0)
{
block = new NullSinkOutputFilter(configuration, role, in_streams,
out_streams);
}
else if (implementation.compare("File_Output_Filter") == 0)
{
block = new FileOutputFilter(configuration, role, in_streams,
out_streams);
}
// else if (implementation.compare("USRP1_Signal_Source") == 0)
// {
// block = new Usrp1SignalSource(configuration, role, in_streams,
// out_streams, queue);
// }
//! \todo Create a UHD block
// SIGNAL CONDITIONERS
else if (implementation.compare("Pass_Through") == 0)
{
block = new PassThrough(configuration, role, in_streams, out_streams);
}
else if (implementation.compare("Direct_Resampler") == 0)
{
block = new DirectResamplerConditioner(configuration, role,
in_streams, out_streams);
}
// ACQUISITION BLOCKS
else if (implementation.compare("GPS_L1_CA_GPS_SDR_Acquisition") == 0)
{
block = new GpsL1CaGpsSdrAcquisition(configuration, role, in_streams,
@ -262,6 +270,9 @@ GNSSBlockInterface* GNSSBlockFactory::GetBlock(
block = new GpsL1CaTongPcpsAcquisition(configuration, role,
in_streams, out_streams, queue);
}
// TRACKING BLOCKS
else if (implementation.compare("GPS_L1_CA_DLL_PLL_Tracking") == 0)
{
block = new GpsL1CaDllPllTracking(configuration, role, in_streams,
@ -272,21 +283,42 @@ GNSSBlockInterface* GNSSBlockFactory::GetBlock(
block = new GpsL1CaDllFllPllTracking(configuration, role, in_streams,
out_streams, queue);
}
// TELEMETRY DECODERS
else if (implementation.compare("GPS_L1_CA_Telemetry_Decoder") == 0)
{
block = new GpsL1CaTelemetryDecoder(configuration, role, in_streams,
out_streams, queue);
}
// OBSERVABLES
else if (implementation.compare("GPS_L1_CA_Observables") == 0)
{
block = new GpsL1CaObservables(configuration, role, in_streams,
out_streams, queue);
}
// PVT
else if (implementation.compare("GPS_L1_CA_PVT") == 0)
{
block = new GpsL1CaPvt(configuration, role, in_streams,
out_streams, queue);
}
// OUTPUT FILTERS
else if (implementation.compare("Null_Sink_Output_Filter") == 0)
{
block = new NullSinkOutputFilter(configuration, role, in_streams,
out_streams);
}
else if (implementation.compare("File_Output_Filter") == 0)
{
block = new FileOutputFilter(configuration, role, in_streams,
out_streams);
}
else
{
// Log fatal. This causes execution to stop.

View File

@ -51,7 +51,6 @@ using google::LogMessage;
GNSSFlowgraph::GNSSFlowgraph(ConfigurationInterface *configuration,
gr_msg_queue_sptr queue)
{
connected_ = false;
running_ = false;
configuration_ = configuration;
@ -111,7 +110,11 @@ void GNSSFlowgraph::stop()
void GNSSFlowgraph::connect()
{
DLOG(INFO) << "Connecting flowgraph";
/* Connects the blocks in the flowgraph
*
* Signal Source > Signal conditioner > Channels >> Observables >> PVT > Output filter
*/
DLOG(INFO) << "Connecting flowgraph";
if (connected_)
{
LOG_AT_LEVEL(WARNING) << "flowgraph already connected";
@ -255,8 +258,8 @@ void GNSSFlowgraph::connect()
DLOG(INFO) << "Channel " << i
<< " connected to observables and ready for acquisition";
}
/*!
* Enabled the observables multichannel output connection to PVT
/*
* Connect the observables output of each channel to the PVT block
*/
try
{
@ -309,7 +312,12 @@ void GNSSFlowgraph::wait()
void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
{
/*!
* \brief Applies an action to the flowgraph
*
* \param[in] who Who generated the action
* \param[in] what What is the action 0: acquisition failed
*/
DLOG(INFO) << "received " << what << " from " << who;
switch (what)
@ -385,7 +393,9 @@ GNSSBlockInterface* GNSSFlowgraph::output_filter()
void GNSSFlowgraph::init()
{
/*!
* \brief Instantiates the receiver blocks
*/
blocks_->push_back(
block_factory_->GetSignalSource(configuration_, queue_));
blocks_->push_back(block_factory_->GetSignalConditioner(configuration_,
@ -422,7 +432,15 @@ void GNSSFlowgraph::init()
void GNSSFlowgraph::set_satellites_list()
{
for (unsigned int id = 1; id < 33; id++)
/*
* Sets a sequential list of satellites (1...33)
*/
/*!
* \TODO Describe GNSS satellites more nicely, with RINEX notation
* See http://igscb.jpl.nasa.gov/igscb/data/format/rinex301.pdf (page 5)
*/
for (unsigned int id = 1; id < 33; id++)
{
available_GPS_satellites_IDs_->push_back(id);
}
@ -445,7 +463,7 @@ void GNSSFlowgraph::set_satellites_list()
}
}
// std::cout << "Cola de satélites: ";
// std::cout << "Satellite queue: ";
// for (std::list<unsigned int>::iterator it =
// available_GPS_satellites_IDs_->begin(); it
// != available_GPS_satellites_IDs_->end(); it++)

View File

@ -56,11 +56,15 @@ class GNSSFlowgraph
{
public:
/*!
* \brief Constructor that initializes the receiver flowgraph
*/
GNSSFlowgraph(ConfigurationInterface* configuration,
gr_msg_queue_sptr queue);
//! Virtual destructor
/*!
* \brief Virtual destructor
*/
virtual ~GNSSFlowgraph();
//! Start the flowgraph
@ -69,7 +73,11 @@ public:
//! Stop the flowgraph
void stop();
//! Connect the defined flowgraph
/*!
* \brief Connects the defined blocks in the flowgraph
*
* Signal Source > Signal conditioner > Channels >> Observables >> PVT > Output filter
*/
void connect();
void wait();

View File

@ -30,6 +30,8 @@
*
* -------------------------------------------------------------------------
*/
#include <boost/filesystem.hpp>
#include <gflags/gflags.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
@ -43,6 +45,8 @@
using google::LogMessage;
DECLARE_string(log_dir);
/*!
* \todo make this queue generic for all the GNSS systems (javi)
*/
@ -68,10 +72,28 @@ int main(int argc, char** argv)
google::SetUsageMessage(intro_help);
google::SetVersionString("0.1");
google::ParseCommandLineFlags(&argc, &argv, true);
google::InitGoogleLogging(argv[0]);
std::cout<<"Initializing GNSS-SDR... Please wait"<<std::endl;
google::InitGoogleLogging(argv[0]);
if (FLAGS_log_dir.empty())
{
std::cout << "Logging will be done at " << boost::filesystem::temp_directory_path() << std::endl
<< "Use gnss-sdr --log_dir=/path/to/log to change that."<< std::endl;
}
else
{
const boost::filesystem::path p (FLAGS_log_dir);
if (!boost::filesystem::exists(p))
{
std::cout << "The path " << FLAGS_log_dir << " does not exist, attepting to create it" << std::endl;
boost::filesystem::create_directory(p);
}
std::cout << "Logging with be done at " << FLAGS_log_dir << std::endl;
}
ControlThread *control_thread = new ControlThread();
control_thread->run();