diff options
Diffstat (limited to 'host/lib/usrp/e300')
-rw-r--r-- | host/lib/usrp/e300/CMakeLists.txt | 12 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_async_serial.cpp | 245 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_async_serial.hpp | 113 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_common.cpp | 35 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_defaults.hpp | 9 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_fpga_defs.hpp | 2 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_impl.cpp | 363 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_impl.hpp | 27 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_io_impl.cpp | 12 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_network.cpp | 34 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_remote_codec_ctrl.cpp | 110 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_remote_codec_ctrl.hpp | 14 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_sensor_manager.cpp | 141 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_sensor_manager.hpp | 9 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_ublox_control.hpp | 50 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_ublox_control_impl.cpp | 505 | ||||
-rw-r--r-- | host/lib/usrp/e300/e300_ublox_control_impl.hpp | 457 |
17 files changed, 405 insertions, 1733 deletions
diff --git a/host/lib/usrp/e300/CMakeLists.txt b/host/lib/usrp/e300/CMakeLists.txt index 9ee9b5521..26e34294a 100644 --- a/host/lib/usrp/e300/CMakeLists.txt +++ b/host/lib/usrp/e300/CMakeLists.txt @@ -1,5 +1,5 @@ # -# Copyright 2013-2014 Ettus Research LLC +# Copyright 2013-2015 Ettus Research LLC # # 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 @@ -39,8 +39,6 @@ IF(ENABLE_E300) ${CMAKE_CURRENT_SOURCE_DIR}/e300_i2c.cpp ${CMAKE_CURRENT_SOURCE_DIR}/e300_eeprom_manager.cpp ${CMAKE_CURRENT_SOURCE_DIR}/e300_common.cpp - ${CMAKE_CURRENT_SOURCE_DIR}/e300_async_serial.cpp - ${CMAKE_CURRENT_SOURCE_DIR}/e300_ublox_control_impl.cpp ${CMAKE_CURRENT_SOURCE_DIR}/e300_remote_codec_ctrl.cpp ) LIBUHD_APPEND_SOURCES(${E300_SOURCES}) @@ -52,4 +50,12 @@ IF(ENABLE_E300) PROPERTIES COMPILE_DEFINITIONS "E300_NATIVE=1" ) ENDIF(UDEV_FOUND) + + IF(ENABLE_GPSD) + SET_SOURCE_FILES_PROPERTIES( + ${CMAKE_CURRENT_SOURCE_DIR}/e300_impl.cpp + ${CMAKE_CURRENT_SOURCE_DIR}/e300_impl.hpp + PROPERTIES COMPILE_DEFINITIONS "E300_GPSD=1" + ) + ENDIF(ENABLE_GPSD) ENDIF(ENABLE_E300) diff --git a/host/lib/usrp/e300/e300_async_serial.cpp b/host/lib/usrp/e300/e300_async_serial.cpp deleted file mode 100644 index cdf18f7f7..000000000 --- a/host/lib/usrp/e300/e300_async_serial.cpp +++ /dev/null @@ -1,245 +0,0 @@ -// -// Copyright 2014 Ettus Research LLC -// -// 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 "e300_async_serial.hpp" - -namespace uhd { namespace usrp { namespace gps { - -async_serial::async_serial() - : _io(), - _port(_io), - _background_thread(), - _open(false), - _error(false) -{ -} - -async_serial::async_serial( - const std::string &node, - const size_t baud_rate, - boost::asio::serial_port_base::parity opt_parity, - boost::asio::serial_port_base::character_size opt_csize, - boost::asio::serial_port_base::flow_control opt_flow, - boost::asio::serial_port_base::stop_bits opt_stop) - : _io(), - _port(_io), - _background_thread(), - _open(false), - _error(false) -{ - open(node, baud_rate, opt_parity, opt_csize, opt_flow, opt_stop); -} - -void async_serial::open( - const std::string &node, - const size_t baud_rate, - boost::asio::serial_port_base::parity opt_parity, - boost::asio::serial_port_base::character_size opt_csize, - boost::asio::serial_port_base::flow_control opt_flow, - boost::asio::serial_port_base::stop_bits opt_stop) -{ - if(is_open()) - close(); - - _set_error_status(true); - _port.open(node); - _port.set_option( - boost::asio::serial_port_base::baud_rate(baud_rate)); - _port.set_option(opt_parity); - _port.set_option(opt_csize); - _port.set_option(opt_flow); - _port.set_option(opt_stop); - - _io.post(boost::bind(&async_serial::_do_read, this)); - - boost::thread t(boost::bind(&boost::asio::io_service::run, &_io)); - _background_thread.swap(t); - _set_error_status(false); - _open=true; -} - -bool async_serial::is_open() const -{ - return _open; -} - -bool async_serial::error_status() const -{ - boost::lock_guard<boost::mutex> l(_error_mutex); - return _error; -} - -void async_serial::close() -{ - if(!is_open()) - return; - - _open=false; - _io.post(boost::bind(&async_serial::_do_close, this)); - _background_thread.join(); - _io.reset(); - if(error_status()) - throw(boost::system::system_error(boost::system::error_code(), - "Error while closing the device")); -} - -void async_serial::write(const char *data, size_t size) -{ - { - boost::lock_guard<boost::mutex> l(_write_queue_mutex); - _write_queue.insert(_write_queue.end(), data, data+size); - } - _io.post(boost::bind(&async_serial::_do_write, this)); -} - -void async_serial::write(const std::vector<char> &data) -{ - { - boost::lock_guard<boost::mutex> l(_write_queue_mutex); - _write_queue.insert( - _write_queue.end(), - data.begin(), - data.end()); - } - _io.post(boost::bind(&async_serial::_do_write, this)); -} - -void async_serial::write_string(const std::string &s) -{ - { - boost::lock_guard<boost::mutex> l(_write_queue_mutex); - _write_queue.insert( - _write_queue.end(), - s.begin(), - s.end()); - } - _io.post(boost::bind(&async_serial::_do_write, this)); -} - -async_serial::~async_serial() -{ - if(is_open()) { - try { - close(); - } catch(...) { - //Don't throw from a destructor - } - } -} - -void async_serial::_do_read() -{ - _port.async_read_some(boost::asio::buffer( - _read_buffer,READ_BUFFER_SIZE), - boost::bind(&async_serial::_read_end, - this, - boost::asio::placeholders::error, - boost::asio::placeholders::bytes_transferred)); -} - -void async_serial::_read_end( - const boost::system::error_code& error, - size_t bytes_transferred) -{ - if(error) { - if(is_open()) { - _do_close(); - _set_error_status(true); - } - } else { - if(_callback) - _callback( - _read_buffer, - bytes_transferred); - _do_read(); - } -} - -void async_serial::_do_write() -{ - // if a write operation is already in progress, do nothing - if(_write_buffer == 0) { - boost::lock_guard<boost::mutex> l(_write_queue_mutex); - _write_buffer_size=_write_queue.size(); - _write_buffer.reset(new char[_write_queue.size()]); - std::copy(_write_queue.begin(),_write_queue.end(), - _write_buffer.get()); - _write_queue.clear(); - async_write( - _port, boost::asio::buffer(_write_buffer.get(), - _write_buffer_size), - boost::bind( - &async_serial::_write_end, - this, - boost::asio::placeholders::error)); - } -} - -void async_serial::_write_end(const boost::system::error_code& error) -{ - if(!error) { - boost::lock_guard<boost::mutex> l(_write_queue_mutex); - if(_write_queue.empty()) { - _write_buffer.reset(); - _write_buffer_size=0; - return; - } - _write_buffer_size = _write_queue.size(); - _write_buffer.reset(new char[_write_queue.size()]); - std::copy(_write_queue.begin(),_write_queue.end(), - _write_buffer.get()); - _write_queue.clear(); - async_write( - _port, - boost::asio::buffer(_write_buffer.get(), - _write_buffer_size), - boost::bind( - &async_serial::_write_end, - this, - boost::asio::placeholders::error)); - } else { - _set_error_status(true); - _do_close(); - } -} - -void async_serial::_do_close() -{ - boost::system::error_code ec; - _port.cancel(ec); - if(ec) - _set_error_status(true); - _port.close(ec); - if(ec) - _set_error_status(true); -} - -void async_serial::_set_error_status(const bool e) -{ - boost::lock_guard<boost::mutex> l(_error_mutex); - _error = e; -} - - -void async_serial::set_read_callback( - const boost::function<void (const char*, size_t)> &callback) -{ - _callback = callback; -} - - -}}} // namespace diff --git a/host/lib/usrp/e300/e300_async_serial.hpp b/host/lib/usrp/e300/e300_async_serial.hpp deleted file mode 100644 index fafc7de3d..000000000 --- a/host/lib/usrp/e300/e300_async_serial.hpp +++ /dev/null @@ -1,113 +0,0 @@ -// -// Copyright 2013-2014 Ettus Research LLC -// -// 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/>. -// - -#ifndef INCLUDED_ASYNC_SERIAL_HPP -#define INCLUDED_ASYNC_SERIAL_HPP - -#include <boost/asio.hpp> -#include <boost/bind.hpp> -#include <boost/thread.hpp> -#include <boost/utility.hpp> -#include <boost/function.hpp> -#include <boost/shared_array.hpp> - -namespace uhd { namespace usrp { namespace gps { - -class async_serial : private boost::noncopyable -{ -public: - async_serial(); - ~async_serial(); - - async_serial(const std::string &node, const size_t baud_rate, - boost::asio::serial_port_base::parity opt_parity= - boost::asio::serial_port_base::parity( - boost::asio::serial_port_base::parity::none), - boost::asio::serial_port_base::character_size opt_csize= - boost::asio::serial_port_base::character_size(8), - boost::asio::serial_port_base::flow_control opt_flow= - boost::asio::serial_port_base::flow_control( - boost::asio::serial_port_base::flow_control::none), - boost::asio::serial_port_base::stop_bits opt_stop= - boost::asio::serial_port_base::stop_bits( - boost::asio::serial_port_base::stop_bits::one)); - - void open(const std::string& node, const size_t baud_rate, - boost::asio::serial_port_base::parity opt_parity= - boost::asio::serial_port_base::parity( - boost::asio::serial_port_base::parity::none), - boost::asio::serial_port_base::character_size opt_csize= - boost::asio::serial_port_base::character_size(8), - boost::asio::serial_port_base::flow_control opt_flow= - boost::asio::serial_port_base::flow_control( - boost::asio::serial_port_base::flow_control::none), - boost::asio::serial_port_base::stop_bits opt_stop= - boost::asio::serial_port_base::stop_bits( - boost::asio::serial_port_base::stop_bits::one)); - - bool is_open(void) const; - - bool error_status(void) const; - - void close(void); - - void write(const char *data, const size_t size); - void write(const std::vector<char> &data); - - void write_string(const std::string &s); - - static const size_t READ_BUFFER_SIZE=512; - - void set_read_callback( - const boost::function<void (const char*, size_t)>& callback); - - void clear_callback(); - -private: // methods - void _do_read(); - - void _read_end( - const boost::system::error_code &error, - size_t bytes_transferred); - - void _do_write(); - - void _write_end(const boost::system::error_code &error); - - void _do_close(); - - void _set_error_status(const bool e); -private: // members - boost::asio::io_service _io; - boost::asio::serial_port _port; - boost::thread _background_thread; - bool _open; - bool _error; - mutable boost::mutex _error_mutex; - - std::vector<char> _write_queue; - boost::shared_array<char> _write_buffer; - size_t _write_buffer_size; - boost::mutex _write_queue_mutex; - char _read_buffer[READ_BUFFER_SIZE]; - - boost::function<void (const char*, size_t)> _callback; -}; - -}}} // namespace - -#endif //INCLUDED_ASYNC_SERIAL_HPP diff --git a/host/lib/usrp/e300/e300_common.cpp b/host/lib/usrp/e300/e300_common.cpp index db5b37055..29117e21f 100644 --- a/host/lib/usrp/e300/e300_common.cpp +++ b/host/lib/usrp/e300/e300_common.cpp @@ -1,5 +1,5 @@ // -// Copyright 2014 Ettus Research LLC +// Copyright 2014-2015 Ettus Research LLC // // 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 @@ -14,8 +14,12 @@ // 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 <uhd/image_loader.hpp> #include <uhd/utils/msg.hpp> +#include <uhd/utils/paths.hpp> +#include <uhd/utils/static.hpp> +#include "e300_impl.hpp" #include "e300_fifo_config.hpp" #include "e300_fifo_config.hpp" @@ -23,6 +27,7 @@ #include <boost/filesystem.hpp> #include <fstream> +#include <string> namespace uhd { namespace usrp { namespace e300 { @@ -54,6 +59,34 @@ void load_fpga_image(const std::string &path) UHD_MSG(status) << " done" << std::endl; } +static bool e300_image_loader(const image_loader::image_loader_args_t &image_loader_args) { + // Make sure this is an E3x0 and we don't want to use anything connected + uhd::device_addrs_t devs = e300_find(image_loader_args.args); + if(devs.size() == 0 or !image_loader_args.load_fpga) return false; + + std::string fpga_filename, idle_image; // idle_image never used, just needed for function + if(image_loader_args.fpga_path == "") { + get_e3x0_fpga_images(devs[0], fpga_filename, idle_image); + } + else { + if(not boost::filesystem::exists(image_loader_args.fpga_path)) { + throw uhd::runtime_error(str(boost::format("The path \"%s\" does not exist.") + % image_loader_args.fpga_path)); + } + else fpga_filename = image_loader_args.fpga_path; + } + + load_fpga_image(fpga_filename); + return true; +} + +UHD_STATIC_BLOCK(register_e300_image_loader) { + std::string recovery_instructions = "The default FPGA image will be loaded the next " + "time UHD uses this device."; + + image_loader::register_image_loader("e3x0", e300_image_loader, recovery_instructions); +} + } }}} diff --git a/host/lib/usrp/e300/e300_defaults.hpp b/host/lib/usrp/e300/e300_defaults.hpp index d409062c5..267897e03 100644 --- a/host/lib/usrp/e300/e300_defaults.hpp +++ b/host/lib/usrp/e300/e300_defaults.hpp @@ -23,18 +23,13 @@ namespace uhd { namespace usrp { namespace e300 { static const double DEFAULT_TICK_RATE = 32e6; -static const double MAX_TICK_RATE = 50e6; -static const double MIN_TICK_RATE = 1e6; +static const double MIN_TICK_RATE = 10e6; static const double DEFAULT_TX_SAMP_RATE = 1.0e6; static const double DEFAULT_RX_SAMP_RATE = 1.0e6; static const double DEFAULT_DDC_FREQ = 0.0; static const double DEFAULT_DUC_FREQ = 0.0; -static const double DEFAULT_FE_GAIN = 0.0; -static const double DEFAULT_FE_FREQ = 1.0e9; -static const double DEFAULT_FE_BW = 56e6; - static const std::string DEFAULT_TIME_SRC = "internal"; static const std::string DEFAULT_CLOCK_SRC = "internal"; @@ -73,7 +68,7 @@ public: digital_interface_delays_t get_digital_interface_timing() { digital_interface_delays_t delays; delays.rx_clk_delay = 0; - delays.rx_data_delay = 0xF; + delays.rx_data_delay = 0x8; delays.tx_clk_delay = 0; delays.tx_data_delay = 0xF; return delays; diff --git a/host/lib/usrp/e300/e300_fpga_defs.hpp b/host/lib/usrp/e300/e300_fpga_defs.hpp index eea4d7f63..fbbca329a 100644 --- a/host/lib/usrp/e300/e300_fpga_defs.hpp +++ b/host/lib/usrp/e300/e300_fpga_defs.hpp @@ -21,7 +21,7 @@ namespace uhd { namespace usrp { namespace e300 { namespace fpga { static const size_t NUM_RADIOS = 2; -static const boost::uint32_t COMPAT_MAJOR = 8; +static const boost::uint32_t COMPAT_MAJOR = 9; static const boost::uint32_t COMPAT_MINOR = 0; }}}} // namespace diff --git a/host/lib/usrp/e300/e300_impl.cpp b/host/lib/usrp/e300/e300_impl.cpp index a08168eab..6eb63c786 100644 --- a/host/lib/usrp/e300/e300_impl.cpp +++ b/host/lib/usrp/e300/e300_impl.cpp @@ -1,5 +1,5 @@ // -// Copyright 2013-2014 Ettus Research LLC +// Copyright 2013-2015 Ettus Research LLC // // 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 @@ -121,7 +121,7 @@ static bool is_loopback(const if_addrs_t &if_addrs) return if_addrs.inet == asio::ip::address_v4::loopback().to_string(); } -static device_addrs_t e300_find(const device_addr_t &multi_dev_hint) +device_addrs_t e300_find(const device_addr_t &multi_dev_hint) { // handle multi device discovery device_addrs_t hints = separate_device_addr(multi_dev_hint); @@ -268,6 +268,36 @@ static device::sptr e300_make(const device_addr_t &device_addr) return device::sptr(new e300_impl(device_addr)); } +// Common code used by e300_impl and e300_image_loader +void get_e3x0_fpga_images(const uhd::device_addr_t &device_addr, + std::string &fpga_image, + std::string &idle_image){ + const boost::uint16_t pid = boost::lexical_cast<boost::uint16_t>( + device_addr["product"]); + + //extract the FPGA path for the e300 + switch(e300_eeprom_manager::get_mb_type(pid)) { + case e300_eeprom_manager::USRP_E310_MB: + fpga_image = device_addr.cast<std::string>("fpga", + find_image_path(E310_FPGA_FILE_NAME)); + idle_image = find_image_path(E310_FPGA_IDLE_FILE_NAME); + break; + case e300_eeprom_manager::USRP_E300_MB: + fpga_image = device_addr.cast<std::string>("fpga", + find_image_path(E300_FPGA_FILE_NAME)); + idle_image = find_image_path(E300_FPGA_IDLE_FILE_NAME); + break; + case e300_eeprom_manager::UNKNOWN: + default: + UHD_MSG(warning) << "Unknown motherboard type, loading e300 image." + << std::endl; + fpga_image = device_addr.cast<std::string>("fpga", + find_image_path(E300_FPGA_FILE_NAME)); + idle_image = find_image_path(E300_FPGA_IDLE_FILE_NAME); + break; + } +} + /*********************************************************************** * Structors **********************************************************************/ @@ -286,33 +316,10 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr) if (_xport_path == AXI) { _do_not_reload = device_addr.has_key("no_reload_fpga"); if (not _do_not_reload) { - // Load FPGA image if provided via args - const boost::uint16_t pid = boost::lexical_cast<boost::uint16_t>( - device_addr["product"]); - std::string fpga_image; - - //extract the FPGA path for the e300 - switch(e300_eeprom_manager::get_mb_type(pid)) { - case e300_eeprom_manager::USRP_E310_MB: - fpga_image = device_addr.cast<std::string>("fpga", - find_image_path(E310_FPGA_FILE_NAME)); - _idle_image = find_image_path(E310_FPGA_IDLE_FILE_NAME); - break; - case e300_eeprom_manager::USRP_E300_MB: - fpga_image = device_addr.cast<std::string>("fpga", - find_image_path(E300_FPGA_FILE_NAME)); - _idle_image = find_image_path(E300_FPGA_IDLE_FILE_NAME); - break; - case e300_eeprom_manager::UNKNOWN: - default: - UHD_MSG(warning) << "Unknown motherboard type, loading e300 image." - << std::endl; - fpga_image = device_addr.cast<std::string>("fpga", - find_image_path(E300_FPGA_FILE_NAME)); - _idle_image = find_image_path(E300_FPGA_IDLE_FILE_NAME); - break; - } + get_e3x0_fpga_images(device_addr, + fpga_image, + _idle_image); common::load_fpga_image(fpga_image); } } @@ -387,18 +394,35 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr) // This is horrible ... why do I have to sleep here? boost::this_thread::sleep(boost::posix_time::milliseconds(100)); _eeprom_manager = boost::make_shared<e300_eeprom_manager>(i2c::make_i2cdev(E300_I2CDEV_DEVICE)); + _sensor_manager = e300_sensor_manager::make_local(_global_regs); } + _codec_mgr = ad936x_manager::make(_codec_ctrl, fpga::NUM_RADIOS); - UHD_MSG(status) << "Detecting internal GPSDO.... " << std::flush; - if (_xport_path == AXI) { - try { - _gps = gps::ublox::ubx::control::make("/dev/ttyPS1", 9600); - } catch (std::exception &e) { - UHD_MSG(error) << "An error occured making GPSDO control: " << e.what() << std::endl; +#ifdef E300_GPSD + UHD_MSG(status) << "Detecting internal GPSDO " << std::flush; + try { + if (_xport_path == AXI) + _gps = gpsd_iface::make("localhost", 2947); + else + _gps = gpsd_iface::make(device_addr["addr"], 2947); + } catch (std::exception &e) { + UHD_MSG(error) << "An error occured making GPSDd interface: " << e.what() << std::endl; + } + + if (_gps) { + for (size_t i = 0; i < _GPS_TIMEOUT; i++) + { + boost::this_thread::sleep(boost::posix_time::seconds(1)); + if (!_gps->gps_detected()) + std::cout << "." << std::flush; + else { + std::cout << ".... " << std::flush; + break; + } } - _sensor_manager = e300_sensor_manager::make_local(_gps, _global_regs); + UHD_MSG(status) << (_gps->gps_detected() ? "found" : "not found") << std::endl; } - UHD_MSG(status) << (_sensor_manager->get_gps_found() ? "found" : "not found") << std::endl; +#endif // Verify we can talk to the e300 core control registers ... UHD_MSG(status) << "Initializing core control..." << std::endl; @@ -443,6 +467,15 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr) _tree->create<sensor_value_t>(mb_path / "sensors" / name) .publish(boost::bind(&e300_sensor_manager::get_sensor, _sensor_manager, name)); } +#ifdef E300_GPSD + if (_gps) { + BOOST_FOREACH(const std::string &name, _gps->get_sensors()) + { + _tree->create<sensor_value_t>(mb_path / "sensors" / name) + .publish(boost::bind(&gpsd_iface::get_sensor, _gps, name)); + } + } +#endif //////////////////////////////////////////////////////////////////// // setup the mboard eeprom @@ -471,28 +504,23 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr) for(size_t instance = 0; instance < fpga::NUM_RADIOS; instance++) this->_setup_radio(instance); - _codec_ctrl->data_port_loopback(true); - // Radio 0 loopback through AD9361 - this->_codec_loopback_self_test(_radio_perifs[0].ctrl); + _codec_mgr->loopback_self_test(_radio_perifs[0].ctrl, TOREG(SR_CODEC_IDLE), RB64_CODEC_READBACK); // Radio 1 loopback through AD9361 - this->_codec_loopback_self_test(_radio_perifs[1].ctrl); - - _codec_ctrl->data_port_loopback(false); + _codec_mgr->loopback_self_test(_radio_perifs[1].ctrl, TOREG(SR_CODEC_IDLE), RB64_CODEC_READBACK); //////////////////////////////////////////////////////////////////// // internal gpios //////////////////////////////////////////////////////////////////// gpio_core_200::sptr fp_gpio = gpio_core_200::make(_radio_perifs[0].ctrl, TOREG(SR_FP_GPIO), RB32_FP_GPIO); - const std::vector<std::string> gpio_attrs = boost::assign::list_of("CTRL")("DDR")("OUT")("ATR_0X")("ATR_RX")("ATR_TX")("ATR_XX"); - BOOST_FOREACH(const std::string &attr, gpio_attrs) + BOOST_FOREACH(const gpio_attr_map_t::value_type attr, gpio_attr_map) { - _tree->create<boost::uint32_t>(mb_path / "gpio" / "INT0" / attr) - .subscribe(boost::bind(&e300_impl::_set_internal_gpio, this, fp_gpio, attr, _1)) + _tree->create<boost::uint32_t>(mb_path / "gpio" / "INT0" / attr.second) + .subscribe(boost::bind(&e300_impl::_set_internal_gpio, this, fp_gpio, attr.first, _1)) .set(0); } _tree->create<boost::uint8_t>(mb_path / "gpio" / "INT0" / "READBACK") - .publish(boost::bind(&e300_impl::_get_internal_gpio, this, fp_gpio, "READBACK")); + .publish(boost::bind(&e300_impl::_get_internal_gpio, this, fp_gpio)); //////////////////////////////////////////////////////////////////// @@ -510,7 +538,11 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr) _tree->create<std::string>(mb_path / "time_source" / "value") .subscribe(boost::bind(&e300_impl::_update_time_source, this, _1)) .set(e300::DEFAULT_TIME_SRC); +#ifdef E300_GPSD static const std::vector<std::string> time_sources = boost::assign::list_of("none")("internal")("external")("gpsdo"); +#else + static const std::vector<std::string> time_sources = boost::assign::list_of("none")("internal")("external"); +#endif _tree->create<std::vector<std::string> >(mb_path / "time_source" / "options").set(time_sources); //setup reference source props _tree->create<std::string>(mb_path / "clock_source" / "value") @@ -575,7 +607,7 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr) // init the clock rate to something reasonable _tree->access<double>(mb_path / "tick_rate").set( - device_addr.cast<double>("master_clock_rate", e300::DEFAULT_TICK_RATE)); + device_addr.cast<double>("master_clock_rate", ad936x_manager::DEFAULT_TICK_RATE)); // subdev spec contains full width of selections subdev_spec_t rx_spec, tx_spec; @@ -590,40 +622,56 @@ e300_impl::e300_impl(const uhd::device_addr_t &device_addr) _tree->access<subdev_spec_t>(mb_path / "rx_subdev_spec").set(rx_spec); _tree->access<subdev_spec_t>(mb_path / "tx_subdev_spec").set(tx_spec); - UHD_MSG(status) << "Initializing time to the internal GPSDO" << std::endl; - const time_t tp = time_t(_sensor_manager->get_sensor("gps_time").to_int()+1); - _tree->access<time_spec_t>(mb_path / "time" / "pps").set(time_spec_t(tp)); +#ifdef E300_GPSD + //GPS installed: use external ref, time, and init time spec + if (_gps and _gps->gps_detected()) { + UHD_MSG(status) << "Setting references to the internal GPSDO" + << std::endl; + _tree->access<std::string>(mb_path / "time_source" / "value").set("gpsdo"); + UHD_MSG(status) << "Initializing time to the internal GPSDO" + << std::endl; + const time_t tp = time_t(_gps->get_sensor("gps_time").to_int()+1); + _tree->access<time_spec_t>(mb_path / "time" / "pps").set(time_spec_t(tp)); + + // wait for time to be actually set + boost::this_thread::sleep(boost::posix_time::seconds(1)); + } +#else + //init to internal clock and time source + _tree->access<std::string>(mb_path / "time_source/value").set("internal"); +#endif// E300_GPSD - // wait for time to be actually set - boost::this_thread::sleep(boost::posix_time::seconds(1)); } -boost::uint8_t e300_impl::_get_internal_gpio( - gpio_core_200::sptr gpio, - const std::string &) +boost::uint8_t e300_impl::_get_internal_gpio(gpio_core_200::sptr gpio) { return boost::uint32_t(gpio->read_gpio(dboard_iface::UNIT_RX)); } void e300_impl::_set_internal_gpio( gpio_core_200::sptr gpio, - const std::string &attr, + const gpio_attr_t attr, const boost::uint32_t value) { - if (attr == "CTRL") + switch (attr) + { + case GPIO_CTRL: return gpio->set_pin_ctrl(dboard_iface::UNIT_RX, value); - else if (attr == "DDR") + case GPIO_DDR: return gpio->set_gpio_ddr(dboard_iface::UNIT_RX, value); - else if (attr == "OUT") + case GPIO_OUT: return gpio->set_gpio_out(dboard_iface::UNIT_RX, value); - else if (attr == "ATR_0X") + case GPIO_ATR_0X: return gpio->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_IDLE, value); - else if (attr == "ATR_RX") + case GPIO_ATR_RX: return gpio->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_RX_ONLY, value); - else if (attr == "ATR_TX") + case GPIO_ATR_TX: return gpio->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_TX_ONLY, value); - else if (attr == "ATR_XX") + case GPIO_ATR_XX: return gpio->set_atr_reg(dboard_iface::UNIT_RX, dboard_iface::ATR_REG_FULL_DUPLEX, value); + default: + UHD_THROW_INVALID_CODE_PATH(); + } } uhd::sensor_value_t e300_impl::_get_fe_pll_lock(const bool is_tx) @@ -665,6 +713,17 @@ void e300_impl::_enforce_tick_rate_limits( % direction )); } + // Minimum rate restriction due to MMCM used in capture interface to AD9361. + // Xilinx Artix-7 FPGA MMCM minimum input frequency is 10 MHz. + const double min_tick_rate = uhd::usrp::e300::MIN_TICK_RATE / ((chan_count <= 1) ? 1 : 2); + if (tick_rate - min_tick_rate < 0.0) + { + throw uhd::value_error(boost::str( + boost::format("current master clock rate (%.6f MHz) set below minimum possible master clock rate (%.6f MHz)") + % (tick_rate/1e6) + % (min_tick_rate/1e6) + )); + } } } @@ -721,30 +780,6 @@ std::string e300_impl::_get_version_hash(void) % ((git_hash & 0xF000000) ? "-dirty" : "")); } -void e300_impl::_codec_loopback_self_test(wb_iface::sptr iface) -{ - bool test_fail = false; - UHD_ASSERT_THROW(bool(iface)); - UHD_MSG(status) << "Performing CODEC loopback test... " << std::flush; - size_t hash = size_t(time(NULL)); - for (size_t i = 0; i < 100; i++) - { - boost::hash_combine(hash, i); - const boost::uint32_t word32 = boost::uint32_t(hash) & 0xfff0fff0; - iface->poke32(TOREG(SR_CODEC_IDLE), word32); - iface->peek64(RB64_CODEC_READBACK); //enough idleness for loopback to propagate - const boost::uint64_t rb_word64 = iface->peek64(RB64_CODEC_READBACK); - const boost::uint32_t rb_tx = boost::uint32_t(rb_word64 >> 32); - const boost::uint32_t rb_rx = boost::uint32_t(rb_word64 & 0xffffffff); - test_fail = word32 != rb_tx or word32 != rb_rx; - if (test_fail) break; //exit loop on any failure - } - UHD_MSG(status) << ((test_fail)? " fail" : "pass") << std::endl; - - /* Zero out the idle data. */ - iface->poke32(TOREG(SR_CODEC_IDLE), 0); -} - boost::uint32_t e300_impl::_allocate_sid(const sid_config_t &config) { const boost::uint32_t stream = (config.dst_prefix | (config.router_dst_there << 2)) & 0xff; @@ -799,8 +834,10 @@ void e300_impl::_update_time_source(const std::string &source) UHD_MSG(status) << boost::format("Setting time source to %s") % source << std::endl; if (source == "none" or source == "internal") { _misc.pps_sel = global_regs::PPS_INT; +#ifdef E300_GPSD } else if (source == "gpsdo") { _misc.pps_sel = global_regs::PPS_GPS; +#endif } else if (source == "external") { _misc.pps_sel = global_regs::PPS_EXT; } else { @@ -928,6 +965,7 @@ void e300_impl::_setup_radio(const size_t dspno) { radio_perifs_t &perif = _radio_perifs[dspno]; const fs_path mb_path = "/mboards/0"; + std::string slot_name = (dspno == 0) ? "A" : "B"; //////////////////////////////////////////////////////////////////// // crossbar config for ctrl xports @@ -956,137 +994,102 @@ void e300_impl::_setup_radio(const size_t dspno) ctrl_sid, dspno ? "1" : "0"); this->_register_loopback_self_test(perif.ctrl); - perif.atr = gpio_core_200_32wo::make(perif.ctrl, TOREG(SR_GPIO)); //////////////////////////////////////////////////////////////////// - // front end corrections + // Set up peripherals //////////////////////////////////////////////////////////////////// - std::string slot_name = (dspno == 0) ? "A" : "B"; + perif.atr = gpio_core_200_32wo::make(perif.ctrl, TOREG(SR_GPIO)); perif.rx_fe = rx_frontend_core_200::make(perif.ctrl, TOREG(SR_RX_FRONT)); - const fs_path rx_fe_path = mb_path / "rx_frontends" / slot_name; - _tree->create<std::complex<double> >(rx_fe_path / "dc_offset" / "value") - .coerce(boost::bind(&rx_frontend_core_200::set_dc_offset, perif.rx_fe, _1)) - .set(std::complex<double>(0.0, 0.0)); - _tree->create<bool>(rx_fe_path / "dc_offset" / "enable") - .subscribe(boost::bind(&rx_frontend_core_200::set_dc_offset_auto, perif.rx_fe, _1)) - .set(true); - _tree->create<std::complex<double> >(rx_fe_path / "iq_balance" / "value") - .subscribe(boost::bind(&rx_frontend_core_200::set_iq_balance, perif.rx_fe, _1)) - .set(std::complex<double>(0.0, 0.0)); - + perif.rx_fe->set_dc_offset(rx_frontend_core_200::DEFAULT_DC_OFFSET_VALUE); + perif.rx_fe->set_dc_offset_auto(rx_frontend_core_200::DEFAULT_DC_OFFSET_ENABLE); + perif.rx_fe->set_iq_balance(rx_frontend_core_200::DEFAULT_IQ_BALANCE_VALUE); perif.tx_fe = tx_frontend_core_200::make(perif.ctrl, TOREG(SR_TX_FRONT)); - const fs_path tx_fe_path = mb_path / "tx_frontends" / slot_name; - _tree->create<std::complex<double> >(tx_fe_path / "dc_offset" / "value") - .coerce(boost::bind(&tx_frontend_core_200::set_dc_offset, perif.tx_fe, _1)) - .set(std::complex<double>(0.0, 0.0)); - _tree->create<std::complex<double> >(tx_fe_path / "iq_balance" / "value") - .subscribe(boost::bind(&tx_frontend_core_200::set_iq_balance, perif.tx_fe, _1)) - .set(std::complex<double>(0.0, 0.0)); - - //////////////////////////////////////////////////////////////////// - // create rx dsp control objects - //////////////////////////////////////////////////////////////////// + perif.tx_fe->set_dc_offset(tx_frontend_core_200::DEFAULT_DC_OFFSET_VALUE); + perif.tx_fe->set_iq_balance(tx_frontend_core_200::DEFAULT_IQ_BALANCE_VALUE); perif.framer = rx_vita_core_3000::make(perif.ctrl, TOREG(SR_RX_CTRL)); perif.ddc = rx_dsp_core_3000::make(perif.ctrl, TOREG(SR_RX_DSP)); perif.ddc->set_link_rate(10e9/8); //whatever + perif.ddc->set_freq(e300::DEFAULT_DDC_FREQ); + perif.deframer = tx_vita_core_3000::make(perif.ctrl, TOREG(SR_TX_CTRL)); + perif.duc = tx_dsp_core_3000::make(perif.ctrl, TOREG(SR_TX_DSP)); + perif.duc->set_link_rate(10e9/8); //whatever + perif.duc->set_freq(e300::DEFAULT_DUC_FREQ); + + //////////////////////////////////////////////////////////////////// + // create time control objects + //////////////////////////////////////////////////////////////////// + time_core_3000::readback_bases_type time64_rb_bases; + time64_rb_bases.rb_now = RB64_TIME_NOW; + time64_rb_bases.rb_pps = RB64_TIME_PPS; + perif.time64 = time_core_3000::make(perif.ctrl, TOREG(SR_TIME), time64_rb_bases); + + //////////////////////////////////////////////////////////////////// + // front end corrections + //////////////////////////////////////////////////////////////////// + perif.rx_fe->populate_subtree(_tree->subtree(mb_path / "rx_frontends" / slot_name)); + perif.tx_fe->populate_subtree(_tree->subtree(mb_path / "tx_frontends" / slot_name)); + + //////////////////////////////////////////////////////////////////// + // connect rx dsp control objects + //////////////////////////////////////////////////////////////////// _tree->access<double>(mb_path / "tick_rate") .subscribe(boost::bind(&rx_vita_core_3000::set_tick_rate, perif.framer, _1)) .subscribe(boost::bind(&rx_dsp_core_3000::set_tick_rate, perif.ddc, _1)); const fs_path rx_dsp_path = mb_path / "rx_dsps" / str(boost::format("%u") % dspno); - _tree->create<meta_range_t>(rx_dsp_path / "rate" / "range") - .publish(boost::bind(&rx_dsp_core_3000::get_host_rates, perif.ddc)); - _tree->create<double>(rx_dsp_path / "rate" / "value") - .coerce(boost::bind(&rx_dsp_core_3000::set_host_rate, perif.ddc, _1)) + perif.ddc->populate_subtree(_tree->subtree(rx_dsp_path)); + _tree->access<double>(rx_dsp_path / "rate" / "value") .subscribe(boost::bind(&e300_impl::_update_rx_samp_rate, this, dspno, _1)) - .set(e300::DEFAULT_RX_SAMP_RATE); - _tree->create<double>(rx_dsp_path / "freq" / "value") - .coerce(boost::bind(&rx_dsp_core_3000::set_freq, perif.ddc, _1)) - .set(e300::DEFAULT_DDC_FREQ); - _tree->create<meta_range_t>(rx_dsp_path / "freq" / "range") - .publish(boost::bind(&rx_dsp_core_3000::get_freq_range, perif.ddc)); + ; _tree->create<stream_cmd_t>(rx_dsp_path / "stream_cmd") .subscribe(boost::bind(&rx_vita_core_3000::issue_stream_command, perif.framer, _1)); //////////////////////////////////////////////////////////////////// // create tx dsp control objects //////////////////////////////////////////////////////////////////// - perif.deframer = tx_vita_core_3000::make(perif.ctrl, TOREG(SR_TX_CTRL)); - perif.duc = tx_dsp_core_3000::make(perif.ctrl, TOREG(SR_TX_DSP)); - perif.duc->set_link_rate(10e9/8); //whatever _tree->access<double>(mb_path / "tick_rate") .subscribe(boost::bind(&tx_vita_core_3000::set_tick_rate, perif.deframer, _1)) .subscribe(boost::bind(&tx_dsp_core_3000::set_tick_rate, perif.duc, _1)); const fs_path tx_dsp_path = mb_path / "tx_dsps" / str(boost::format("%u") % dspno); - _tree->create<meta_range_t>(tx_dsp_path / "rate" / "range") - .publish(boost::bind(&tx_dsp_core_3000::get_host_rates, perif.duc)); - _tree->create<double>(tx_dsp_path / "rate" / "value") - .coerce(boost::bind(&tx_dsp_core_3000::set_host_rate, perif.duc, _1)) + perif.duc->populate_subtree(_tree->subtree(tx_dsp_path)); + _tree->access<double>(tx_dsp_path / "rate" / "value") .subscribe(boost::bind(&e300_impl::_update_tx_samp_rate, this, dspno, _1)) - .set(e300::DEFAULT_TX_SAMP_RATE); - _tree->create<double>(tx_dsp_path / "freq" / "value") - .coerce(boost::bind(&tx_dsp_core_3000::set_freq, perif.duc, _1)) - .set(e300::DEFAULT_DUC_FREQ); - _tree->create<meta_range_t>(tx_dsp_path / "freq" / "range") - .publish(boost::bind(&tx_dsp_core_3000::get_freq_range, perif.duc)); - - //////////////////////////////////////////////////////////////////// - // create time control objects - //////////////////////////////////////////////////////////////////// - time_core_3000::readback_bases_type time64_rb_bases; - time64_rb_bases.rb_now = RB64_TIME_NOW; - time64_rb_bases.rb_pps = RB64_TIME_PPS; - perif.time64 = time_core_3000::make(perif.ctrl, TOREG(SR_TIME), time64_rb_bases); + ; //////////////////////////////////////////////////////////////////// // create RF frontend interfacing //////////////////////////////////////////////////////////////////// - static const std::vector<std::string> data_directions = boost::assign::list_of("rx")("tx"); - BOOST_FOREACH(const std::string& direction, data_directions) - { - const std::string key = boost::to_upper_copy(direction) + std::string(((dspno == FE0)? "1" : "2")); + static const std::vector<direction_t> dirs = boost::assign::list_of(RX_DIRECTION)(TX_DIRECTION); + BOOST_FOREACH(direction_t dir, dirs) { + const std::string x = (dir == RX_DIRECTION) ? "rx" : "tx"; + const std::string key = boost::to_upper_copy(x) + std::string(((dspno == FE0)? "1" : "2")); const fs_path rf_fe_path - = mb_path / "dboards" / "A" / (direction + "_frontends") / ((dspno == 0) ? "A" : "B"); + = mb_path / "dboards" / "A" / (x + "_frontends") / ((dspno == 0) ? "A" : "B"); + + // This will connect all the AD936x-specific items + _codec_mgr->populate_frontend_subtree( + _tree->subtree(rf_fe_path), key, dir + ); - _tree->create<std::string>(rf_fe_path / "name").set("FE-"+key); - _tree->create<int>(rf_fe_path / "sensors"); //empty TODO + // This will connect all the e300_impl-specific items _tree->create<sensor_value_t>(rf_fe_path / "sensors" / "lo_locked") - .publish(boost::bind(&e300_impl::_get_fe_pll_lock, this, direction == "tx")); - BOOST_FOREACH(const std::string &name, ad9361_ctrl::get_gain_names(key)) - { - _tree->create<meta_range_t>(rf_fe_path / "gains" / name / "range") - .set(ad9361_ctrl::get_gain_range(key)); + .publish(boost::bind(&e300_impl::_get_fe_pll_lock, this, dir == TX_DIRECTION)) + ; - _tree->create<double>(rf_fe_path / "gains" / name / "value") - .coerce(boost::bind(&ad9361_ctrl::set_gain, _codec_ctrl, key, _1)) - .set(e300::DEFAULT_FE_GAIN); + // Network mode currently doesn't support the filter API, so + // prevent it from using it: + if (_xport_path != AXI) { + _tree->remove(rf_fe_path / "filters"); } - _tree->create<std::string>(rf_fe_path / "connection").set("IQ"); - _tree->create<bool>(rf_fe_path / "enabled").set(true); - _tree->create<bool>(rf_fe_path / "use_lo_offset").set(false); - _tree->create<double>(rf_fe_path / "bandwidth" / "value") - .coerce(boost::bind(&ad9361_ctrl::set_bw_filter, _codec_ctrl, key, _1)) - .set(e300::DEFAULT_FE_BW); - _tree->create<meta_range_t>(rf_fe_path / "bandwidth" / "range") - .publish(boost::bind(&ad9361_ctrl::get_bw_filter_range, key)); - _tree->create<double>(rf_fe_path / "freq" / "value") - .publish(boost::bind(&ad9361_ctrl::get_freq, _codec_ctrl, key)) - .coerce(boost::bind(&ad9361_ctrl::tune, _codec_ctrl, key, _1)) - .subscribe(boost::bind(&e300_impl::_update_fe_lo_freq, this, key, _1)) - .set(e300::DEFAULT_FE_FREQ); - _tree->create<meta_range_t>(rf_fe_path / "freq" / "range") - .publish(boost::bind(&ad9361_ctrl::get_rf_freq_range)); - - //setup RX related stuff - if (key[0] == 'R') { + + // Antenna Setup + if (dir == RX_DIRECTION) { static const std::vector<std::string> ants = boost::assign::list_of("TX/RX")("RX2"); _tree->create<std::vector<std::string> >(rf_fe_path / "antenna" / "options").set(ants); _tree->create<std::string>(rf_fe_path / "antenna" / "value") .subscribe(boost::bind(&e300_impl::_update_antenna_sel, this, dspno, _1)) .set("RX2"); - _tree->create<sensor_value_t>(rf_fe_path / "sensors" / "rssi") - .publish(boost::bind(&ad9361_ctrl::get_rssi, _codec_ctrl, key)); } - if (key[0] == 'T') { + else if (dir == TX_DIRECTION) { static const std::vector<std::string> ants(1, "TX/RX"); _tree->create<std::vector<std::string> >(rf_fe_path / "antenna" / "options").set(ants); _tree->create<std::string>(rf_fe_path / "antenna" / "value").set("TX/RX"); diff --git a/host/lib/usrp/e300/e300_impl.hpp b/host/lib/usrp/e300/e300_impl.hpp index 7f83c16ed..8aff51466 100644 --- a/host/lib/usrp/e300/e300_impl.hpp +++ b/host/lib/usrp/e300/e300_impl.hpp @@ -1,5 +1,5 @@ // -// Copyright 2013-2014 Ettus Research LLC +// Copyright 2013-2015 Ettus Research LLC // // 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 @@ -20,6 +20,7 @@ #include <uhd/device.hpp> #include <uhd/property_tree.hpp> +#include <uhd/types/device_addr.hpp> #include <uhd/usrp/subdev_spec.hpp> #include <uhd/usrp/mboard_eeprom.hpp> #include <uhd/usrp/dboard_eeprom.hpp> @@ -28,6 +29,7 @@ #include <uhd/types/sensors.hpp> #include <boost/weak_ptr.hpp> #include <boost/thread/mutex.hpp> +#include <string> #include "e300_fifo_config.hpp" #include "radio_ctrl_core_3000.hpp" #include "rx_frontend_core_200.hpp" @@ -38,13 +40,18 @@ #include "rx_dsp_core_3000.hpp" #include "tx_dsp_core_3000.hpp" #include "ad9361_ctrl.hpp" +#include "ad936x_manager.hpp" #include "gpio_core_200.hpp" #include "e300_global_regs.hpp" #include "e300_i2c.hpp" #include "e300_eeprom_manager.hpp" #include "e300_sensor_manager.hpp" -#include "e300_ublox_control.hpp" + +/* if we don't compile with gpsd support, don't bother */ +#ifdef E300_GPSD +#include "gpsd_iface.hpp" +#endif namespace uhd { namespace usrp { namespace e300 { @@ -98,6 +105,10 @@ static const size_t E300_R1_CTRL_STREAM = (1 << 2) | E300_RADIO_DEST_PREFIX_C static const size_t E300_R1_TX_DATA_STREAM = (1 << 2) | E300_RADIO_DEST_PREFIX_TX; static const size_t E300_R1_RX_DATA_STREAM = (1 << 2) | E300_RADIO_DEST_PREFIX_RX; +uhd::device_addrs_t e300_find(const uhd::device_addr_t &multi_dev_hint); +void get_e3x0_fpga_images(const uhd::device_addr_t &device_args, + std::string &fpga_image, + std::string &idle_image); /*! * USRP-E300 implementation guts: @@ -267,13 +278,11 @@ private: // methods uhd::sensor_value_t _get_fe_pll_lock(const bool is_tx); // internal gpios - boost::uint8_t _get_internal_gpio( - gpio_core_200::sptr, - const std::string &); + boost::uint8_t _get_internal_gpio(gpio_core_200::sptr); void _set_internal_gpio( gpio_core_200::sptr gpio, - const std::string &attr, + const gpio_attr_t attr, const boost::uint32_t value); private: // members @@ -284,6 +293,7 @@ private: // members radio_perifs_t _radio_perifs[2]; double _tick_rate; ad9361_ctrl::sptr _codec_ctrl; + ad936x_manager::sptr _codec_mgr; fe_control_settings_t _settings; global_regs::sptr _global_regs; e300_sensor_manager::sptr _sensor_manager; @@ -293,7 +303,10 @@ private: // members std::string _idle_image; bool _do_not_reload; gpio_t _misc; - gps::ublox::ubx::control::sptr _gps; +#ifdef E300_GPSD + gpsd_iface::sptr _gps; + static const size_t _GPS_TIMEOUT = 5; +#endif }; }}} // namespace diff --git a/host/lib/usrp/e300/e300_io_impl.cpp b/host/lib/usrp/e300/e300_io_impl.cpp index dadfb71e9..29d250c8f 100644 --- a/host/lib/usrp/e300/e300_io_impl.cpp +++ b/host/lib/usrp/e300/e300_io_impl.cpp @@ -91,21 +91,13 @@ void e300_impl::_update_tick_rate(const double rate) } } -#define CHECK_BANDWIDTH(dir) \ - if (rate > _codec_ctrl->get_bw_filter_range(dir).stop()) { \ - UHD_MSG(warning) \ - << "Selected " << dir << " bandwidth (" << (rate/1e6) << " MHz) exceeds\n" \ - << "analog frontend filter bandwidth (" << (_codec_ctrl->get_bw_filter_range(dir).stop()/1e6) << " MHz)." \ - << std::endl; \ - } - void e300_impl::_update_rx_samp_rate(const size_t dspno, const double rate) { boost::shared_ptr<sph::recv_packet_streamer> my_streamer = boost::dynamic_pointer_cast<sph::recv_packet_streamer>(_radio_perifs[dspno].rx_streamer.lock()); if (my_streamer) my_streamer->set_samp_rate(rate); - CHECK_BANDWIDTH("Rx"); + _codec_mgr->check_bandwidth(rate, "Rx"); } void e300_impl::_update_tx_samp_rate(const size_t dspno, const double rate) @@ -114,7 +106,7 @@ void e300_impl::_update_tx_samp_rate(const size_t dspno, const double rate) boost::dynamic_pointer_cast<sph::send_packet_streamer>(_radio_perifs[dspno].tx_streamer.lock()); if (my_streamer) my_streamer->set_samp_rate(rate); - CHECK_BANDWIDTH("Tx"); + _codec_mgr->check_bandwidth(rate, "Tx"); } /*********************************************************************** diff --git a/host/lib/usrp/e300/e300_network.cpp b/host/lib/usrp/e300/e300_network.cpp index 408f9e62d..96387d6f7 100644 --- a/host/lib/usrp/e300/e300_network.cpp +++ b/host/lib/usrp/e300/e300_network.cpp @@ -230,6 +230,27 @@ static void e300_codec_ctrl_tunnel( case codec_xact_t::ACTION_GET_RSSI: out->rssi = _codec_ctrl->get_rssi(which_str).to_real(); break; + case codec_xact_t::ACTION_GET_TEMPERATURE: + out->temp = _codec_ctrl->get_temperature().to_real(); + break; + case codec_xact_t::ACTION_SET_DC_OFFSET_AUTO: + _codec_ctrl->set_dc_offset_auto(which_str, in->use_dc_correction == 1); + break; + case codec_xact_t::ACTION_SET_IQ_BALANCE_AUTO: + _codec_ctrl->set_iq_balance_auto(which_str, in->use_iq_correction == 1); + case codec_xact_t::ACTION_SET_AGC: + _codec_ctrl->set_agc(which_str, in->use_agc == 1); + break; + case codec_xact_t::ACTION_SET_AGC_MODE: + if(in->agc_mode == 0) { + _codec_ctrl->set_agc_mode(which_str, "slow"); + } else if (in->agc_mode == 1) { + _codec_ctrl->set_agc_mode(which_str, "fast"); + } + break; + case codec_xact_t::ACTION_SET_BW: + out->bw = _codec_ctrl->set_bw_filter(which_str, in->bw); + break; default: UHD_MSG(status) << "Got unknown request?!" << std::endl; //Zero out actions to fail this request on client @@ -328,19 +349,9 @@ static void e300_sensor_tunnel( // TODO: This is ugly ... use proper serialization in->value = uhd::htonx<boost::uint32_t>( e300_sensor_manager::pack_float_in_uint32_t(temp.to_real())); - } else if (uhd::ntohx(in->which) == GPS_FOUND) { - in->value = uhd::htonx<boost::uint32_t>( - sensor_manager->get_gps_found() ? 1 : 0); - - } else if (uhd::ntohx(in->which) == GPS_LOCK) { - in->value = uhd::htonx<boost::uint32_t>( - sensor_manager->get_gps_lock().to_bool() ? 1 : 0); } else if (uhd::ntohx(in->which) == REF_LOCK) { in->value = uhd::htonx<boost::uint32_t>( sensor_manager->get_ref_lock().to_bool() ? 1 : 0); - } else if (uhd::ntohx(in->which) == GPS_TIME) { - in->value = uhd::htonx<boost::uint32_t>( - sensor_manager->get_gps_time().to_int()); } else UHD_MSG(status) << "Got unknown request?!" << std::endl; @@ -627,8 +638,7 @@ network_server_impl::network_server_impl(const uhd::device_addr_t &device_addr) _codec_ctrl = ad9361_ctrl::make_spi(client_settings, spi::make(E300_SPIDEV_DEVICE), 1); // This is horrible ... why do I have to sleep here? boost::this_thread::sleep(boost::posix_time::milliseconds(100)); - _sensor_manager = e300_sensor_manager::make_local( - gps::ublox::ubx::control::make("/dev/ttyPS1", 9600), _global_regs); + _sensor_manager = e300_sensor_manager::make_local(_global_regs); } }}} // namespace diff --git a/host/lib/usrp/e300/e300_remote_codec_ctrl.cpp b/host/lib/usrp/e300/e300_remote_codec_ctrl.cpp index 6742f5f86..9708634dd 100644 --- a/host/lib/usrp/e300/e300_remote_codec_ctrl.cpp +++ b/host/lib/usrp/e300/e300_remote_codec_ctrl.cpp @@ -130,10 +130,118 @@ public: _args.bits = uhd::htonx<boost::uint32_t>(0); _transact(); - return sensor_value_t("RSSI", _retval.rssi, "dB"); } + sensor_value_t get_temperature() + { + _clear(); + _args.action = uhd::htonx<boost::uint32_t>(transaction_t::ACTION_GET_TEMPERATURE); + _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_NONE); /*Unused*/ + _args.bits = uhd::htonx<boost::uint32_t>(0); + + _transact(); + return sensor_value_t("temp", _retval.temp, "C"); + } + + void set_dc_offset_auto(const std::string &which, const bool on) + { + _clear(); + _args.action = uhd::htonx<boost::uint32_t>(transaction_t::ACTION_SET_DC_OFFSET_AUTO); + if (which == "TX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX1); + else if (which == "TX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX2); + else if (which == "RX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX1); + else if (which == "RX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX2); + else throw std::runtime_error("e300_remote_codec_ctrl_impl incorrect chain string."); + _args.use_dc_correction = on ? 1 : 0; + + _transact(); + } + + void set_iq_balance_auto(const std::string &which, const bool on) + { + _clear(); + _args.action = uhd::htonx<boost::uint32_t>(transaction_t::ACTION_SET_IQ_BALANCE_AUTO); + if (which == "TX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX1); + else if (which == "TX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX2); + else if (which == "RX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX1); + else if (which == "RX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX2); + else throw std::runtime_error("e300_remote_codec_ctrl_impl incorrect chain string."); + _args.use_iq_correction = on ? 1 : 0; + + _transact(); + } + + void set_agc(const std::string &which, bool enable) + { + _clear(); + _args.action = uhd::htonx<boost::uint32_t>(transaction_t::ACTION_SET_AGC); + if (which == "TX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX1); + else if (which == "TX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX2); + else if (which == "RX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX1); + else if (which == "RX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX2); + else throw std::runtime_error("e300_remote_codec_ctrl_impl incorrect chain string."); + _args.use_agc = enable ? 1 : 0; + + _transact(); + } + + void set_agc_mode(const std::string &which, const std::string &mode) + { + _clear(); + _args.action = uhd::htonx<boost::uint32_t>(transaction_t::ACTION_SET_AGC_MODE); + + if (which == "TX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX1); + else if (which == "TX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX2); + else if (which == "RX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX1); + else if (which == "RX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX2); + else throw std::runtime_error("e300_remote_codec_ctrl_impl incorrect chain string."); + + if(mode == "slow") { + _args.agc_mode = 0; + } else if (mode == "fast") { + _args.agc_mode = 1; + } else { + throw std::runtime_error("e300_remote_codec_ctrl_impl incorrect agc mode."); + } + + _transact(); + } + + //! set the filter bandwidth for the frontend's analog low pass + double set_bw_filter(const std::string &which, const double bw) + { + _clear(); + _args.action = uhd::htonx<boost::uint32_t>(transaction_t::ACTION_SET_BW); + if (which == "TX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX1); + else if (which == "TX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_TX2); + else if (which == "RX1") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX1); + else if (which == "RX2") _args.which = uhd::htonx<boost::uint32_t>(transaction_t::CHAIN_RX2); + else throw std::runtime_error("e300_remote_codec_ctrl_impl incorrect chain string."); + _args.bw = bw; + + _transact(); + return _retval.bw; + } + + //! List all available filters by name + std::vector<std::string> get_filter_names(const std::string &) + { + UHD_THROW_INVALID_CODE_PATH(); + } + + //! Return a list of all filters + filter_info_base::sptr get_filter(const std::string &, const std::string &) + { + UHD_THROW_INVALID_CODE_PATH(); + } + + //! Write back a filter + void set_filter(const std::string &, const std::string &, const filter_info_base::sptr) + { + UHD_THROW_INVALID_CODE_PATH(); + } + private: void _transact() { { diff --git a/host/lib/usrp/e300/e300_remote_codec_ctrl.hpp b/host/lib/usrp/e300/e300_remote_codec_ctrl.hpp index e21f2ef95..43723e0d5 100644 --- a/host/lib/usrp/e300/e300_remote_codec_ctrl.hpp +++ b/host/lib/usrp/e300/e300_remote_codec_ctrl.hpp @@ -34,6 +34,12 @@ public: double gain; double freq; double rssi; + double temp; + double bw; + boost::uint32_t use_dc_correction; + boost::uint32_t use_iq_correction; + boost::uint32_t use_agc; + boost::uint32_t agc_mode; boost::uint64_t bits; }; @@ -44,7 +50,13 @@ public: static const boost::uint32_t ACTION_TUNE = 13; static const boost::uint32_t ACTION_SET_LOOPBACK = 14; static const boost::uint32_t ACTION_GET_RSSI = 15; - static const boost::uint32_t ACTION_GET_FREQ = 16; + static const boost::uint32_t ACTION_GET_TEMPERATURE = 16; + static const boost::uint32_t ACTION_SET_DC_OFFSET_AUTO = 17; + static const boost::uint32_t ACTION_SET_IQ_BALANCE_AUTO = 18; + static const boost::uint32_t ACTION_SET_AGC = 19; + static const boost::uint32_t ACTION_SET_AGC_MODE = 20; + static const boost::uint32_t ACTION_SET_BW = 21; + static const boost::uint32_t ACTION_GET_FREQ = 22; //Values for "which" static const boost::uint32_t CHAIN_NONE = 0; diff --git a/host/lib/usrp/e300/e300_sensor_manager.cpp b/host/lib/usrp/e300/e300_sensor_manager.cpp index 527cfb91a..a4319fa4b 100644 --- a/host/lib/usrp/e300/e300_sensor_manager.cpp +++ b/host/lib/usrp/e300/e300_sensor_manager.cpp @@ -24,7 +24,6 @@ #include <cstring> #include <uhd/exception.hpp> #include <uhd/utils/byteswap.hpp> -#include <uhd/usrp/gps_ctrl.hpp> namespace uhd { namespace usrp { namespace e300 { @@ -38,17 +37,13 @@ public: std::vector<std::string> get_sensors() { - return boost::assign::list_of("temp")("gps_locked")("gps_time")("ref_locked"); + return boost::assign::list_of("temp")("ref_locked"); } uhd::sensor_value_t get_sensor(const std::string &key) { if (key == "temp") return get_mb_temp(); - else if (key == "gps_locked") - return get_gps_lock(); - else if (key == "gps_time") - return get_gps_time(); else if (key == "ref_locked") return get_ref_lock(); else @@ -94,108 +89,6 @@ public: "C"); } - uhd::sensor_value_t get_gps_time(void) - { - boost::mutex::scoped_lock(_mutex); - sensor_transaction_t transaction; - transaction.which = uhd::htonx<boost::uint32_t>(GPS_TIME); - { - uhd::transport::managed_send_buffer::sptr buff - = _xport->get_send_buff(1.0); - if (not buff or buff->size() < sizeof(transaction)) { - throw uhd::runtime_error("sensor proxy send timeout"); - } - std::memcpy( - buff->cast<void *>(), - &transaction, - sizeof(transaction)); - buff->commit(sizeof(transaction)); - } - { - uhd::transport::managed_recv_buffer::sptr buff - = _xport->get_recv_buff(1.0); - - if (not buff or buff->size() < sizeof(transaction)) - throw uhd::runtime_error("sensor proxy recv timeout"); - - std::memcpy( - &transaction, - buff->cast<const void *>(), - sizeof(transaction)); - } - UHD_ASSERT_THROW(uhd::ntohx<boost::uint32_t>(transaction.which) == GPS_TIME); - // TODO: Use proper serialization here ... - return sensor_value_t("GPS epoch time", int(uhd::ntohx<boost::uint32_t>(transaction.value)), "seconds"); - } - - bool get_gps_found(void) - { - boost::mutex::scoped_lock(_mutex); - sensor_transaction_t transaction; - transaction.which = uhd::htonx<boost::uint32_t>(GPS_FOUND); - { - uhd::transport::managed_send_buffer::sptr buff - = _xport->get_send_buff(1.0); - if (not buff or buff->size() < sizeof(transaction)) { - throw uhd::runtime_error("sensor proxy send timeout"); - } - std::memcpy( - buff->cast<void *>(), - &transaction, - sizeof(transaction)); - buff->commit(sizeof(transaction)); - } - { - uhd::transport::managed_recv_buffer::sptr buff - = _xport->get_recv_buff(1.0); - - if (not buff or buff->size() < sizeof(transaction)) - throw uhd::runtime_error("sensor proxy recv timeout"); - - std::memcpy( - &transaction, - buff->cast<const void *>(), - sizeof(transaction)); - } - UHD_ASSERT_THROW(uhd::ntohx<boost::uint32_t>(transaction.which) == GPS_FOUND); - // TODO: Use proper serialization here ... - return (uhd::ntohx(transaction.value) > 0); - } - - uhd::sensor_value_t get_gps_lock(void) - { - boost::mutex::scoped_lock(_mutex); - sensor_transaction_t transaction; - transaction.which = uhd::htonx<boost::uint32_t>(GPS_LOCK); - { - uhd::transport::managed_send_buffer::sptr buff - = _xport->get_send_buff(1.0); - if (not buff or buff->size() < sizeof(transaction)) { - throw uhd::runtime_error("sensor proxy send timeout"); - } - std::memcpy( - buff->cast<void *>(), - &transaction, - sizeof(transaction)); - buff->commit(sizeof(transaction)); - } - { - uhd::transport::managed_recv_buffer::sptr buff - = _xport->get_recv_buff(1.0); - - if (not buff or buff->size() < sizeof(transaction)) - throw uhd::runtime_error("sensor proxy recv timeout"); - - std::memcpy( - &transaction, - buff->cast<const void *>(), - sizeof(transaction)); - } - UHD_ASSERT_THROW(uhd::ntohx<boost::uint32_t>(transaction.which) == GPS_LOCK); - // TODO: Use proper serialization here ... - return sensor_value_t("GPS lock status", (uhd::ntohx(transaction.value) > 0), "locked", "unlocked"); - } - uhd::sensor_value_t get_ref_lock(void) { boost::mutex::scoped_lock(_mutex); @@ -255,24 +148,20 @@ static const std::string E300_TEMP_SYSFS = "iio:device0"; class e300_sensor_local : public e300_sensor_manager { public: - e300_sensor_local(uhd::gps_ctrl::sptr gps_ctrl, global_regs::sptr global_regs) : - _gps_ctrl(gps_ctrl), _global_regs(global_regs) + e300_sensor_local(global_regs::sptr global_regs) : + _global_regs(global_regs) { } std::vector<std::string> get_sensors() { - return boost::assign::list_of("temp")("gps_locked")("gps_time")("ref_locked"); + return boost::assign::list_of("temp")("ref_locked"); } uhd::sensor_value_t get_sensor(const std::string &key) { if (key == "temp") return get_mb_temp(); - else if (key == "gps_locked") - return get_gps_lock(); - else if (key == "gps_time") - return get_gps_time(); else if (key == "ref_locked") return get_ref_lock(); else @@ -291,21 +180,6 @@ public: return sensor_value_t("temp", (raw + offset) * scale / 1000, "C"); } - bool get_gps_found(void) - { - return _gps_ctrl->gps_detected(); - } - - uhd::sensor_value_t get_gps_lock(void) - { - return _gps_ctrl->get_sensor("gps_locked"); - } - - uhd::sensor_value_t get_gps_time(void) - { - return _gps_ctrl->get_sensor("gps_time"); - } - uhd::sensor_value_t get_ref_lock(void) { //PPSLOOP_LOCKED_MASK is asserted in the following cases: @@ -322,22 +196,21 @@ public: } private: - gps_ctrl::sptr _gps_ctrl; global_regs::sptr _global_regs; }; }}} using namespace uhd::usrp::e300; e300_sensor_manager::sptr e300_sensor_manager::make_local( - uhd::gps_ctrl::sptr gps_ctrl, global_regs::sptr global_regs) + global_regs::sptr global_regs) { - return sptr(new e300_sensor_local(gps_ctrl, global_regs)); + return sptr(new e300_sensor_local(global_regs)); } #else using namespace uhd::usrp::e300; e300_sensor_manager::sptr e300_sensor_manager::make_local( - uhd::gps_ctrl::sptr, global_regs::sptr) + global_regs::sptr) { throw uhd::assertion_error("e300_sensor_manager::make_local() !E300_NATIVE"); } diff --git a/host/lib/usrp/e300/e300_sensor_manager.hpp b/host/lib/usrp/e300/e300_sensor_manager.hpp index 09f889251..bfaf8e90c 100644 --- a/host/lib/usrp/e300/e300_sensor_manager.hpp +++ b/host/lib/usrp/e300/e300_sensor_manager.hpp @@ -39,25 +39,22 @@ struct sensor_transaction_t { -enum sensor {ZYNQ_TEMP=0, GPS_FOUND=1, GPS_TIME=2, - GPS_LOCK=3, REF_LOCK=4}; +enum sensor {ZYNQ_TEMP=0, REF_LOCK=4}; class e300_sensor_manager : boost::noncopyable { public: typedef boost::shared_ptr<e300_sensor_manager> sptr; - virtual bool get_gps_found(void) = 0; virtual uhd::sensor_value_t get_sensor(const std::string &key) = 0; virtual std::vector<std::string> get_sensors(void) = 0; virtual uhd::sensor_value_t get_mb_temp(void) = 0; - virtual uhd::sensor_value_t get_gps_lock(void) = 0; - virtual uhd::sensor_value_t get_gps_time(void) = 0; virtual uhd::sensor_value_t get_ref_lock(void) = 0; + static sptr make_proxy(uhd::transport::zero_copy_if::sptr xport); - static sptr make_local(uhd::gps_ctrl::sptr gps_ctrl, global_regs::sptr global_regs); + static sptr make_local(global_regs::sptr global_regs); // Note: This is a hack static boost::uint32_t pack_float_in_uint32_t(const float &v) diff --git a/host/lib/usrp/e300/e300_ublox_control.hpp b/host/lib/usrp/e300/e300_ublox_control.hpp deleted file mode 100644 index 8705d6c52..000000000 --- a/host/lib/usrp/e300/e300_ublox_control.hpp +++ /dev/null @@ -1,50 +0,0 @@ -#ifndef INCLUDED_UHD_USRP_UBLOX_CONTROL_HPP -#define INCLUDED_UHD_USRP_UBLOX_CONTROL_HPP - -#include <boost/cstdint.hpp> -#include <boost/shared_ptr.hpp> -#include <boost/asio.hpp> -#include <uhd/config.hpp> -#include <uhd/usrp/gps_ctrl.hpp> -#include <uhd/types/sensors.hpp> - -#include "e300_async_serial.hpp" - -namespace uhd { namespace usrp { namespace gps { - -namespace ublox { namespace ubx { - -class control : public virtual uhd::gps_ctrl -{ -public: - typedef boost::shared_ptr<control> sptr; - - static sptr make(const std::string &node, const size_t baud_rate); - - virtual void configure_message_rate( - const boost::uint16_t msg, - const boost::uint8_t rate) = 0; - - virtual void configure_antenna( - const boost::uint16_t flags, - const boost::uint16_t pins) = 0; - - virtual void configure_pps( - const boost::uint32_t interval, - const boost::uint32_t length, - const boost::int8_t status, - const boost::uint8_t time_ref, - const boost::uint8_t flags, - const boost::int16_t antenna_delay, - const boost::int16_t rf_group_delay, - const boost::int32_t user_delay) = 0; - - virtual void configure_rates( - boost::uint16_t meas_rate, - boost::uint16_t nav_rate, - boost::uint16_t time_ref) = 0; -}; -}} // namespace ublox::ubx - -}}} // namespace -#endif // INCLUDED_UHD_USRP_UBLOX_CONTROL_HPP diff --git a/host/lib/usrp/e300/e300_ublox_control_impl.cpp b/host/lib/usrp/e300/e300_ublox_control_impl.cpp deleted file mode 100644 index 389bf79fa..000000000 --- a/host/lib/usrp/e300/e300_ublox_control_impl.cpp +++ /dev/null @@ -1,505 +0,0 @@ -#include <boost/format.hpp> -#include <boost/foreach.hpp> -#include <boost/bind.hpp> -#include <boost/make_shared.hpp> -#include <boost/lexical_cast.hpp> -#include <boost/assign/list_of.hpp> -#include "boost/date_time/posix_time/posix_time.hpp" - -#include <iostream> - - -#include <uhd/utils/byteswap.hpp> -#include <uhd/utils/msg.hpp> -#include <uhd/exception.hpp> - -#include "e300_ublox_control.hpp" - -#ifdef E300_NATIVE -#include "e300_ublox_control_impl.hpp" - - -namespace uhd { namespace usrp { namespace gps { - -namespace ublox { namespace ubx { - -control_impl::control_impl(const std::string &node, const size_t baud_rate) -{ - _decode_init(); - _serial = boost::make_shared<async_serial>(node, baud_rate); - _serial->set_read_callback(boost::bind(&control_impl::_rx_callback, this, _1, _2)); - - _detect(); - - configure_message_rate(MSG_GLL, 0); - configure_message_rate(MSG_GSV, 0); - configure_message_rate(MSG_GGA, 0); - configure_message_rate(MSG_GSA, 0); - configure_message_rate(MSG_RMC, 0); - configure_message_rate(MSG_VTG, 0); - configure_message_rate(MSG_NAV_TIMEUTC, 1); - configure_message_rate(MSG_NAV_SOL, 1); - - configure_antenna(0x001b, 0x8251); - - configure_pps(0xf4240, 0x3d090, 1, 0 /* utc */, 1, 0, 0, 0); - - _sensors = boost::assign::list_of("gps_locked")("gps_time"); -} - -bool control_impl::gps_detected(void) -{ - return _detected; -} - -void control_impl::_detect(void) -{ - _send_message(MSG_MON_VER, NULL, 0); -} - -std::vector<std::string> control_impl::get_sensors(void) -{ - return _sensors; -} - -uhd::sensor_value_t control_impl::get_sensor(std::string key) -{ - if (key == "gps_time") { - bool lock; - _locked.wait_and_see(lock); - return sensor_value_t("GPS epoch time", - lock ? int(_get_epoch_time()) : 0, "seconds"); - } else if (key == "gps_locked") { - bool lock; - _locked.wait_and_see(lock); - return sensor_value_t("GPS lock status", lock, "locked", "unlocked"); - } else - throw uhd::key_error(str(boost::format("sensor %s unknown.") % key)); -} - -std::time_t control_impl::_get_epoch_time(void) -{ - boost::posix_time::ptime ptime; - _ptime.wait_and_see(ptime); - return (ptime - boost::posix_time::from_time_t(0)).total_seconds(); -} - -control_impl::~control_impl(void) -{ -} - -void control_impl::_decode_init(void) -{ - _decode_state = DECODE_SYNC1; - _rx_ck_a = 0; - _rx_ck_b = 0; - _rx_payload_length = 0; - _rx_payload_index = 0; -} - -void control_impl::_add_byte_to_checksum(const boost::uint8_t b) -{ - _rx_ck_a = _rx_ck_a + b; - _rx_ck_b = _rx_ck_b + _rx_ck_a; -} - -void control_impl::_calc_checksum( - const boost::uint8_t *buffer, - const boost::uint16_t length, - checksum_t &checksum) -{ - for (size_t i = 0; i < length; i++) - { - checksum.ck_a = checksum.ck_a + buffer[i]; - checksum.ck_b = checksum.ck_b + checksum.ck_a; - } -} - -void control_impl::configure_rates( - boost::uint16_t meas_rate, - boost::uint16_t nav_rate, - boost::uint16_t time_ref) -{ - payload_tx_cfg_rate_t cfg_rate; - cfg_rate.meas_rate = uhd::htowx<boost::uint16_t>(meas_rate); - cfg_rate.nav_rate = uhd::htowx<boost::uint16_t>(nav_rate); - cfg_rate.time_ref = uhd::htowx<boost::uint16_t>(time_ref); - - _send_message( - MSG_CFG_RATE, - reinterpret_cast<const uint8_t*>(&cfg_rate), - sizeof(cfg_rate)); - - _wait_for_ack(MSG_CFG_RATE, 1.0); -} - -void control_impl::configure_message_rate( - const boost::uint16_t msg, - const uint8_t rate) -{ - payload_tx_cfg_msg_t cfg_msg; - cfg_msg.msg = uhd::htowx<boost::uint16_t>(msg); - cfg_msg.rate[0] = 0;//rate; - cfg_msg.rate[1] = rate; - cfg_msg.rate[2] = 0;//rate; - cfg_msg.rate[3] = 0;//rate; - cfg_msg.rate[4] = 0;//rate; - cfg_msg.rate[5] = 0;//rate; - _send_message( - MSG_CFG_MSG, - reinterpret_cast<const uint8_t*>(&cfg_msg), - sizeof(cfg_msg)); - - _wait_for_ack(MSG_CFG_MSG, 1.0); -} - -void control_impl::configure_antenna( - const boost::uint16_t flags, - const boost::uint16_t pins) -{ - payload_tx_cfg_ant_t cfg_ant; - cfg_ant.pins = uhd::htowx<boost::uint16_t>(pins); - cfg_ant.flags = uhd::htowx<boost::uint16_t>(flags); - _send_message( - MSG_CFG_ANT, - reinterpret_cast<const uint8_t*>(&cfg_ant), - sizeof(cfg_ant)); - if (_wait_for_ack(MSG_CFG_ANT, 1.0) < 0) { - throw uhd::runtime_error("Didn't get an ACK for antenna configuration."); - } - -} - -void control_impl::configure_pps( - const boost::uint32_t interval, - const boost::uint32_t length, - const boost::int8_t status, - const boost::uint8_t time_ref, - const boost::uint8_t flags, - const boost::int16_t antenna_delay, - const boost::int16_t rf_group_delay, - const boost::int32_t user_delay) -{ - payload_tx_cfg_tp_t cfg_tp; - cfg_tp.interval = uhd::htowx<boost::uint32_t>(interval); - cfg_tp.length = uhd::htowx<boost::uint32_t>(length); - cfg_tp.status = status; - cfg_tp.time_ref = time_ref; - cfg_tp.flags = flags; - cfg_tp.antenna_delay = uhd::htowx<boost::int16_t>(antenna_delay); - cfg_tp.rf_group_delay = uhd::htowx<boost::int16_t>(rf_group_delay); - cfg_tp.user_delay = uhd::htowx<boost::int32_t>(user_delay); - _send_message( - MSG_CFG_TP, - reinterpret_cast<const uint8_t*>(&cfg_tp), - sizeof(cfg_tp)); - if (_wait_for_ack(MSG_CFG_TP, 1.0) < 0) { - throw uhd::runtime_error("Didn't get an ACK for PPS configuration."); - } -} - - -void control_impl::_rx_callback(const char *data, unsigned int len) -{ - //std::cout << "IN RX CALLBACK" << std::flush << std::endl; - std::vector<char> v(data, data+len); - BOOST_FOREACH(const char &c, v) - { - _parse_char(c); - } -} - -void control_impl::_parse_char(const boost::uint8_t b) -{ - int ret = 0; - - switch (_decode_state) { - - // we're expecting the first sync byte - case DECODE_SYNC1: - if (b == SYNC1) { // sync1 found goto next step - _decode_state = DECODE_SYNC2; - } // else stay around - break; - - // we're expecting the second sync byte - case DECODE_SYNC2: - if (b == SYNC2) { // sync2 found goto next step - _decode_state = DECODE_CLASS; - } else { - // failed, reset - _decode_init(); - } - break; - - // we're expecting the class byte - case DECODE_CLASS: - _add_byte_to_checksum(b); - _rx_msg = b; - _decode_state = DECODE_ID; - break; - - // we're expecting the id byte - case DECODE_ID: - _add_byte_to_checksum(b); - _rx_msg |= (b << 8); - _decode_state = DECODE_LENGTH1; - break; - - // we're expecting the first length byte - case DECODE_LENGTH1: - _add_byte_to_checksum(b); - _rx_payload_length = b; - _decode_state = DECODE_LENGTH2; - break; - - // we're expecting the second length byte - case DECODE_LENGTH2: - _add_byte_to_checksum(b); - _rx_payload_length |= (b << 8); - if(_payload_rx_init()) { - _decode_init(); // we failed, give up for this one - } else { - _decode_state = _rx_payload_length ? - DECODE_PAYLOAD : DECODE_CHKSUM1; - } - break; - - // we're expecting payload - case DECODE_PAYLOAD: - _add_byte_to_checksum(b); - switch(_rx_msg) { - default: - ret = _payload_rx_add(b); - break; - }; - if (ret < 0) { - // we couldn't deal with the payload, discard the whole thing - _decode_init(); - } else if (ret > 0) { - // payload was complete, let's check the checksum; - _decode_state = DECODE_CHKSUM1; - } else { - // more payload expected, don't move - } - ret = 0; - break; - - case DECODE_CHKSUM1: - if (_rx_ck_a != b) { - // checksum didn't match, barf - std::cout << boost::format("Failed checksum byte1 %lx != %lx") - % int(_rx_ck_a) % int(b) << std::endl; - _decode_init(); - } else { - _decode_state = DECODE_CHKSUM2; - } - break; - - case DECODE_CHKSUM2: - if (_rx_ck_b != b) { - // checksum didn't match, barf - std::cout << boost::format("Failed checksum byte2 %lx != %lx") - % int(_rx_ck_b) % int(b) << std::endl; - - } else { - ret = _payload_rx_done(); // payload done - } - _decode_init(); - break; - - default: - break; - }; -} - -int control_impl::_payload_rx_init(void) -{ - int ret = 0; - - _rx_state = RXMSG_HANDLE; // by default handle - switch(_rx_msg) { - - case MSG_NAV_SOL: - if (not (_rx_payload_length == sizeof(payload_rx_nav_sol_t))) - _rx_state = RXMSG_ERROR_LENGTH; - break; - - case MSG_NAV_TIMEUTC: - if (not (_rx_payload_length == sizeof(payload_rx_nav_timeutc_t))) - _rx_state = RXMSG_ERROR_LENGTH; - break; - - case MSG_MON_VER: - break; // always take this one - - case MSG_ACK_ACK: - if (not (_rx_payload_length == sizeof(payload_rx_ack_ack_t))) - _rx_state = RXMSG_ERROR_LENGTH; - break; - - case MSG_ACK_NAK: - if (not (_rx_payload_length == sizeof(payload_rx_ack_nak_t))) - _rx_state = RXMSG_ERROR_LENGTH; - break; - - default: - _rx_state = RXMSG_DISABLE; - break; - }; - - switch (_rx_state) { - case RXMSG_HANDLE: // handle message - case RXMSG_IGNORE: // ignore message but don't report error - ret = 0; - break; - case RXMSG_DISABLE: // ignore message but don't report error - case RXMSG_ERROR_LENGTH: // the length doesn't match - ret = -1; - break; - default: // invalid, error - ret = -1; - break; - }; - - return ret; -} - -int control_impl::_payload_rx_add(const boost::uint8_t b) -{ - int ret = 0; - _buf.raw[_rx_payload_index] = b; - if (++_rx_payload_index >= _rx_payload_length) - ret = 1; - return ret; -} - -int control_impl::_payload_rx_done(void) -{ - int ret = 0; - if (_rx_state != RXMSG_HANDLE) { - return 0; - } - - switch (_rx_msg) { - case MSG_MON_VER: - _detected = true; - break; - - case MSG_MON_HW: - std::cout << "MON-HW" << std::endl; - break; - - case MSG_ACK_ACK: - if ((_ack_state == ACK_WAITING) and (_buf.payload_rx_ack_ack.msg == _ack_waiting_msg)) - _ack_state = ACK_GOT_ACK; - break; - - case MSG_ACK_NAK: - if ((_ack_state == ACK_WAITING) and (_buf.payload_rx_ack_nak.msg == _ack_waiting_msg)) - _ack_state = ACK_GOT_NAK; - - break; - - case MSG_CFG_ANT: - break; - - case MSG_NAV_TIMEUTC: - _ptime.update(boost::posix_time::ptime( - boost::gregorian::date( - boost::gregorian::greg_year(uhd::wtohx<boost::uint16_t>( - _buf.payload_rx_nav_timeutc.year)), - boost::gregorian::greg_month(_buf.payload_rx_nav_timeutc.month), - boost::gregorian::greg_day(_buf.payload_rx_nav_timeutc.day)), - (boost::posix_time::hours(_buf.payload_rx_nav_timeutc.hour) - + boost::posix_time::minutes(_buf.payload_rx_nav_timeutc.min) - + boost::posix_time::seconds(_buf.payload_rx_nav_timeutc.sec)))); - break; - - case MSG_NAV_SOL: - _locked.update(_buf.payload_rx_nav_sol.gps_fix > 0); - break; - - default: - std::cout << boost::format("Got unknown message %lx , with good checksum [") % int(_rx_msg); - for(size_t i = 0; i < _rx_payload_length; i++) - std::cout << boost::format("%lx, ") % int(_buf.raw[i]); - std::cout << "]"<< std::endl; - break; - }; - return ret; -} - -void control_impl::_send_message( - const boost::uint16_t msg, - const boost::uint8_t *payload, - const boost::uint16_t len) -{ - header_t header = {SYNC1, SYNC2, msg, len}; - checksum_t checksum = {0, 0}; - - // calculate checksums, first header without sync - // then payload - _calc_checksum( - reinterpret_cast<boost::uint8_t*>(&header) + 2, - sizeof(header) - 2, checksum); - if (payload) - _calc_checksum(payload, len, checksum); - - _serial->write( - reinterpret_cast<const char*>(&header), - sizeof(header)); - - if (payload) - _serial->write((const char *) payload, len); - - _serial->write( - reinterpret_cast<const char*>(&checksum), - sizeof(checksum)); -} - -int control_impl::_wait_for_ack( - const boost::uint16_t msg, - const double timeout) -{ - int ret = -1; - - _ack_state = ACK_WAITING; - _ack_waiting_msg = msg; - - boost::system_time timeout_time = - boost::get_system_time() + - boost::posix_time::milliseconds(timeout * 1000.0); - - do { - if(_ack_state == ACK_GOT_ACK) - return 0; - else if (_ack_state == ACK_GOT_NAK) { - return -1; - } - boost::this_thread::sleep(boost::posix_time::milliseconds(20)); - } while (boost::get_system_time() < timeout_time); - - // we get here ... it's a timeout - _ack_state = ACK_IDLE; - return ret; -} - - -}} // namespace ublox::ubx -}}} // namespace - -using namespace uhd::usrp::gps::ublox::ubx; - -control::sptr control::make(const std::string &node, const size_t baud_rate) -{ - return control::sptr(new control_impl(node, baud_rate)); -} -#else -using namespace uhd::usrp::gps::ublox::ubx; - -control::sptr control::make(const std::string& /* node */, const size_t /* baud_rate */) -{ - throw uhd::assertion_error("control::sptr::make: !E300_NATIVE"); -} -#endif // E300_NATIVE diff --git a/host/lib/usrp/e300/e300_ublox_control_impl.hpp b/host/lib/usrp/e300/e300_ublox_control_impl.hpp deleted file mode 100644 index a1dcbfe6c..000000000 --- a/host/lib/usrp/e300/e300_ublox_control_impl.hpp +++ /dev/null @@ -1,457 +0,0 @@ -#ifndef INCLUDED_UHD_USRP_UBLOX_CONTROL_IMPL_HPP -#define INCLUDED_UHD_USRP_UBLOX_CONTROL_IMPL_HPP - -#include <boost/cstdint.hpp> -#include <boost/noncopyable.hpp> -#include <boost/asio.hpp> -#include <uhd/config.hpp> -#include <uhd/usrp/gps_ctrl.hpp> -#include <uhd/types/sensors.hpp> - -#include "e300_async_serial.hpp" - -namespace uhd { namespace usrp { namespace gps { - -namespace ublox { namespace ubx { -// ublox binary sync words -static const boost::uint8_t SYNC1 = 0xB5; -static const boost::uint8_t SYNC2 = 0x62; - -// message classes -static const boost::uint8_t CLASS_NAV = 0x01; -static const boost::uint8_t CLASS_ACK = 0x05; -static const boost::uint8_t CLASS_CFG = 0x06; -static const boost::uint8_t CLASS_MON = 0x0a; -static const boost::uint8_t CLASS_NMEA = 0xf0; - -// Message IDs -static const boost::uint8_t ID_NAV_POSLLH = 0x02; -static const boost::uint8_t ID_NAV_SOL = 0x06; -static const boost::uint8_t ID_NAV_PVT = 0x07; -static const boost::uint8_t ID_NAV_VELNED = 0x12; -static const boost::uint8_t ID_NAV_TIMEUTC = 0x21; -static const boost::uint8_t ID_NAV_SVINFO = 0x30; -static const boost::uint8_t ID_ACK_NAK = 0x00; -static const boost::uint8_t ID_ACK_ACK = 0x01; -static const boost::uint8_t ID_CFG_PRT = 0x00; -static const boost::uint8_t ID_CFG_ANT = 0x13; -static const boost::uint8_t ID_CFG_TP = 0x07; -static const boost::uint8_t ID_CFG_MSG = 0x01; -static const boost::uint8_t ID_CFG_RATE = 0x08; -static const boost::uint8_t ID_CFG_NAV5 = 0x24; -static const boost::uint8_t ID_MON_VER = 0x04; -static const boost::uint8_t ID_MON_HW = 0x09; -static const boost::uint8_t ID_GGA = 0x00; -static const boost::uint8_t ID_GLL = 0x01; -static const boost::uint8_t ID_GSA = 0x02; -static const boost::uint8_t ID_GSV = 0x03; -static const boost::uint8_t ID_RMC = 0x04; -static const boost::uint8_t ID_VTG = 0x05; -static const boost::uint8_t ID_GST = 0x07; - -// Message Classes & IDs // -static const boost::uint16_t MSG_NAV_POSLLH - = CLASS_NAV | (ID_NAV_POSLLH << 8); -static const boost::uint16_t MSG_NAV_SOL - = CLASS_NAV | (ID_NAV_SOL << 8); -static const boost::uint16_t MSG_NAV_PVT - = CLASS_NAV | (ID_NAV_PVT << 8); -static const boost::uint16_t MSG_NAV_VELNED - = CLASS_NAV | (ID_NAV_VELNED << 8); -static const boost::uint16_t MSG_NAV_TIMEUTC - = CLASS_NAV | (ID_NAV_TIMEUTC << 8); -static const boost::uint16_t MSG_NAV_SVINFO - = CLASS_NAV | (ID_NAV_SVINFO << 8); -static const boost::uint16_t MSG_ACK_NAK - = CLASS_ACK | (ID_ACK_NAK << 8); -static const boost::uint16_t MSG_ACK_ACK - = CLASS_ACK | (ID_ACK_ACK << 8); -static const boost::uint16_t MSG_CFG_PRT - = CLASS_CFG | (ID_CFG_PRT << 8); -static const boost::uint16_t MSG_CFG_ANT - = CLASS_CFG | (ID_CFG_ANT << 8); -static const boost::uint16_t MSG_CFG_TP - = CLASS_CFG | (ID_CFG_TP << 8); -static const boost::uint16_t MSG_CFG_MSG - = CLASS_CFG | (ID_CFG_MSG << 8); -static const boost::uint16_t MSG_CFG_RATE - = CLASS_CFG | (ID_CFG_RATE << 8); -static const boost::uint16_t MSG_CFG_NAV5 - = CLASS_CFG | (ID_CFG_NAV5 << 8); -static const boost::uint16_t MSG_MON_HW - = CLASS_MON | (ID_MON_HW << 8); -static const boost::uint16_t MSG_MON_VER - = CLASS_MON | (ID_MON_VER << 8); - -// NMEA ones -static const boost::uint16_t MSG_GGA - = CLASS_NMEA | (ID_GGA << 8); -static const boost::uint16_t MSG_GLL - = CLASS_NMEA | (ID_GLL << 8); -static const boost::uint16_t MSG_GSA - = CLASS_NMEA | (ID_GSA << 8); -static const boost::uint16_t MSG_GSV - = CLASS_NMEA | (ID_GSV << 8); -static const boost::uint16_t MSG_RMC - = CLASS_NMEA | (ID_RMC << 8); -static const boost::uint16_t MSG_VTG - = CLASS_NMEA | (ID_VTG << 8); - -// header -struct header_t -{ - boost::uint8_t sync1; - boost::uint8_t sync2; - boost::uint16_t msg; - boost::uint16_t length; -}; - -// checksum -struct checksum_t -{ - boost::uint8_t ck_a; - boost::uint8_t ck_b; -}; - -// rx rx mon-hw (ubx6) -struct payload_rx_mon_hw_t -{ - boost::uint32_t pin_sel; - boost::uint32_t pin_bank; - boost::uint32_t pin_dir; - boost::uint32_t pin_val; - boost::uint16_t noise_per_ms; - boost::uint16_t agc_cnt; - boost::uint8_t a_status; - boost::uint8_t a_power; - boost::uint8_t flags; - boost::uint8_t reserved1; - boost::uint32_t used_mask; - boost::uint8_t vp[25]; - boost::uint8_t jam_ind; - boost::uint16_t reserved3; - boost::uint32_t pin_irq; - boost::uint32_t pullh; - boost::uint32_t pulll; -}; - -// rx mon-ver -struct payload_rx_mon_ver_part1_t -{ - char sw_version[30]; - char hw_version[10]; -}; - -struct payload_rx_mon_ver_part2_t -{ - boost::uint8_t extension[30]; -}; - -// rx ack-ack -typedef union { - boost::uint16_t msg; - struct { - boost::uint8_t cls_id; - boost::uint8_t msg_id; - }; -} payload_rx_ack_ack_t; - -// rx ack-nak -typedef union { - boost::uint16_t msg; - struct { - boost::uint8_t cls_id; - boost::uint8_t msg_id; - }; -} payload_rx_ack_nak_t; - -// tx cfg-prt (uart) -struct payload_tx_cfg_prt_t -{ - boost::uint8_t port_id; - boost::uint8_t reserved0; - boost::uint16_t tx_ready; - boost::uint32_t mode; - boost::uint32_t baud_rate; - boost::uint16_t in_proto_mask; - boost::uint16_t out_proto_mask; - boost::uint16_t flags; - boost::uint16_t reserved5; -}; - -// tx cfg-rate -struct payload_tx_cfg_rate_t -{ - boost::uint16_t meas_rate; - boost::uint16_t nav_rate; - boost::uint16_t time_ref; -}; - -// tx cfg-msg -struct payload_tx_cfg_msg_t -{ - boost::uint16_t msg; - boost::uint8_t rate[6]; -}; - - -// tx cfg-ant -struct payload_tx_cfg_ant_t -{ - boost::uint16_t flags; - boost::uint16_t pins; -}; - -// tx cfg-tp -struct payload_tx_cfg_tp_t -{ - boost::uint32_t interval; - boost::uint32_t length; - boost::int8_t status; - boost::uint8_t time_ref; - boost::uint8_t flags; - boost::uint8_t reserved1; - boost::int16_t antenna_delay; - boost::int16_t rf_group_delay; - boost::int32_t user_delay; -}; - -struct payload_rx_nav_sol_t -{ - boost::uint32_t i_tow; - boost::int32_t f_tow; - boost::int16_t week; - boost::uint8_t gps_fix; - boost::uint8_t flags; - boost::int32_t ecef_x; - boost::int32_t ecef_y; - boost::int32_t ecef_z; - boost::uint32_t p_acc; - boost::int32_t ecef_vx; - boost::int32_t ecef_vy; - boost::int32_t ecef_vz; - boost::uint32_t s_acc; - boost::uint16_t p_dop; - boost::uint8_t reserved1; - boost::uint8_t num_sv; - boost::uint32_t reserved2; -}; - -struct payload_rx_nav_timeutc_t -{ - boost::uint32_t i_tow; - boost::uint32_t t_acc; - boost::int32_t nano; - boost::uint16_t year; - boost::uint8_t month; - boost::uint8_t day; - boost::uint8_t hour; - boost::uint8_t min; - boost::uint8_t sec; - boost::uint8_t valid; -}; - -typedef union { - payload_rx_mon_hw_t payload_rx_mon_hw; - - payload_rx_mon_ver_part1_t payload_rx_mon_ver_part1; - payload_rx_mon_ver_part2_t payload_rx_mon_ver_part2; - - payload_rx_ack_ack_t payload_rx_ack_ack; - payload_rx_ack_nak_t payload_rx_ack_nak; - - payload_tx_cfg_prt_t payload_tx_cfg_prt; - payload_tx_cfg_ant_t payload_tx_cfg_ant; - payload_tx_cfg_rate_t payload_tx_cfg_rate; - - payload_tx_cfg_msg_t payload_tx_cfg_msg; - - payload_rx_nav_timeutc_t payload_rx_nav_timeutc; - payload_rx_nav_sol_t payload_rx_nav_sol; - boost::uint8_t raw[]; -} buf_t; - - -template <typename T> -class sensor_entry -{ -public: - sensor_entry() : _seen(false) - { - } - - void update(const T &val) - { - boost::mutex::scoped_lock l(_mutex); - _value = val; - _seen = false; - l.unlock(); - _cond.notify_one(); - } - - bool seen() const - { - boost::mutex::scoped_lock l(_mutex); - return _seen; - } - - bool try_and_see(T &val) - { - boost::mutex::scoped_lock l(_mutex); - if (_seen) - return false; - - val = _value; - _seen = true; - return true; - } - - void wait_and_see(T &val) - { - boost::mutex::scoped_lock l(_mutex); - while(_seen) - { - _cond.wait(l); - //std::cout << "Already seen ... " << std::endl; - } - val = _value; - _seen = true; - } - -private: // members - T _value; - boost::mutex _mutex; - boost::condition_variable _cond; - bool _seen; -}; - -class control_impl : public control -{ -public: - control_impl(const std::string &node, const size_t baud_rate); - - virtual ~control_impl(void); - - void configure_message_rate( - const boost::uint16_t msg, - const boost::uint8_t rate); - - void configure_antenna( - const boost::uint16_t flags, - const boost::uint16_t pins); - - void configure_pps( - const boost::uint32_t interval, - const boost::uint32_t length, - const boost::int8_t status, - const boost::uint8_t time_ref, - const boost::uint8_t flags, - const boost::int16_t antenna_delay, - const boost::int16_t rf_group_delay, - const boost::int32_t user_delay); - - void configure_rates( - boost::uint16_t meas_rate, - boost::uint16_t nav_rate, - boost::uint16_t time_ref); - - // gps_ctrl interface - bool gps_detected(void); - std::vector<std::string> get_sensors(void); - uhd::sensor_value_t get_sensor(std::string key); - -private: // types - enum decoder_state_t { - DECODE_SYNC1 = 0, - DECODE_SYNC2, - DECODE_CLASS, - DECODE_ID, - DECODE_LENGTH1, - DECODE_LENGTH2, - DECODE_PAYLOAD, - DECODE_CHKSUM1, - DECODE_CHKSUM2, - }; - - enum rxmsg_state_t { - RXMSG_IGNORE = 0, - RXMSG_HANDLE, - RXMSG_DISABLE, - RXMSG_ERROR_LENGTH - }; - - enum ack_state_t { - ACK_IDLE = 0, - ACK_WAITING, - ACK_GOT_ACK, - ACK_GOT_NAK - }; - -private: // methods - std::time_t _get_epoch_time(void); - - void _decode_init(void); - - void _add_byte_to_checksum(const boost::uint8_t b); - - void _detect(void); - - void _send_message( - const boost::uint16_t msg, - const boost::uint8_t *payload, - const boost::uint16_t len); - - int _wait_for_ack( - const boost::uint16_t msg, - const double timeout); - - void _calc_checksum( - const boost::uint8_t *buffer, - const boost::uint16_t length, - checksum_t &checksum); - - void _rx_callback(const char *data, unsigned len); - - void _parse_char(const boost::uint8_t b); - - int _payload_rx_init(void); - - int _payload_rx_add(const boost::uint8_t b); - - int _payload_rx_done(void); - -private: // members - // gps_ctrl stuff - bool _detected; - std::vector<std::string> _sensors; - - sensor_entry<bool> _locked; - sensor_entry<boost::posix_time::ptime> _ptime; - - // decoder state - decoder_state_t _decode_state; - rxmsg_state_t _rxmsg_state; - - ack_state_t _ack_state; - boost::uint16_t _ack_waiting_msg; - - boost::uint8_t _rx_ck_a; - boost::uint8_t _rx_ck_b; - - boost::uint16_t _rx_payload_length; - size_t _rx_payload_index; - boost::uint16_t _rx_msg; - - rxmsg_state_t _rx_state; - - boost::shared_ptr<async_serial> _serial; - - // this has to be at the end of the - // class to be valid C++ - buf_t _buf; -}; - -}} // namespace ublox::ubx - -}}} // namespace -#endif // INCLUDED_UHD_USRP_UBLOX_CONTROL_IMPL_HPP |