Public Member Functions | Private Types | Private Member Functions | Private Attributes
mav::SerialCommunication Class Reference

Handles the communication between host computer and the HighLevel Processor (HLP) of the AscTec Autopilot board. More...

#include <serial_communication.h>

List of all members.

Public Member Functions

void close ()
 closes the serial port(s)
bool connect (const std::string &port_rx, const std::string &port_tx, uint32_t baudrate)
 connects to the specified serial port(s) with the given baudrate. The HLP sets it's baudrate automatically.
uint32_t getRxPackets ()
uint32_t getRxPacketsGood ()
void loopOnce ()
template<class T >
void registerCallback (uint8_t id, void(T::*cb_func)(uint8_t *, uint32_t), T *p_obj)
 registers a class method that gets called when the packet specified by id was sent from the HLP
template<typename T >
bool sendPacket (uint8_t packet_id, const T &data)
 sends a packet to the HLP
template<typename T >
bool sendPacketAck (uint8_t packet_id, const T &data, const double &timeout=1.0)
 sends a packet to the HLP and blocks until it got acknowledged or until the timeout is reached
 SerialCommunication ()
 ~SerialCommunication ()

Private Types

typedef boost::asio::serial_port SerialPort
typedef boost::shared_ptr
< SerialPort
SerialPortPtr

Private Member Functions

bool configurePort (SerialPortPtr &serial_port, uint32_t *baudrate)
bool connect (SerialPortPtr &serial_port, const std::string &port, uint32_t baudrate)
uint16_t crc16 (void *data, uint16_t cnt, uint16_t crc=0xff)
uint16_t crc_update (uint16_t crc, uint8_t data)
void processPacketAck (uint8_t *buf, uint32_t length)
void rxReadCallback (const boost::system::error_code &error, size_t bytes_transferred)
void rxReadStart (uint32_t length, uint32_t timeout=0)
void rxTimeoutCallback (const boost::system::error_code &error)
void serializePacket (uint8_t packet_id, const void *data, const int32_t &packet_size, uint8_t flag=0)
bool validateChecksum (uint8_t *buf, uint32_t length, uint16_t checksum)
bool waitForPacketAck (uint8_t ack_id, const double &timeout=1.0)

Private Attributes

bool baudrate_change_successful_
CommCallbackMap callbacks_
std::vector< uint8_t > packet_acks_
SerialPortPtr port_rx_
std::string port_rx_name_
SerialPortPtr port_tx_
std::string port_tx_name_
uint8_t rx_buffer_ [256]
uint32_t rx_packet_cnt_
uint32_t rx_packet_good_cnt_
int rx_state_
boost::asio::deadline_timer rx_timeout_
bool rx_timeout_occurred_
uint8_t tx_buffer_ [256]
uint32_t tx_bytes2send_
const int TX_HEADER_SIZE
boost::mutex tx_mutex_
boost::asio::io_service uart_service_
boost::thread uart_thread_ [2]

Detailed Description

Handles the communication between host computer and the HighLevel Processor (HLP) of the AscTec Autopilot board.

Can connect to either one or two (e.g. for separate rx/tx wireless links) serial ports. The default baudrate can be changed up to 921600 baud. Messages can be sent with Comm::sendPacket or Comm::sendPacketAck . Messages are received by setting a callback function with Comm::registerCallback for the message id to receive.

Definition at line 60 of file serial_communication.h.


Member Typedef Documentation

typedef boost::asio::serial_port mav::SerialCommunication::SerialPort [private]

Definition at line 62 of file serial_communication.h.

typedef boost::shared_ptr<SerialPort> mav::SerialCommunication::SerialPortPtr [private]

Definition at line 63 of file serial_communication.h.


Constructor & Destructor Documentation

Definition at line 37 of file serial_communication.cpp.

Definition at line 48 of file serial_communication.cpp.


Member Function Documentation

closes the serial port(s)

Definition at line 156 of file serial_communication.cpp.

bool mav::SerialCommunication::configurePort ( SerialPortPtr serial_port,
uint32_t *  baudrate 
) [private]

Definition at line 119 of file serial_communication.cpp.

bool mav::SerialCommunication::connect ( SerialPortPtr serial_port,
const std::string &  port,
uint32_t  baudrate 
) [private]

Definition at line 53 of file serial_communication.cpp.

bool mav::SerialCommunication::connect ( const std::string &  port_rx,
const std::string &  port_tx,
uint32_t  baudrate 
)

connects to the specified serial port(s) with the given baudrate. The HLP sets it's baudrate automatically.

The port names can be equal, then it connects only to one serial port (most common operation). It can also connect to different ports for rx and tx. This is useful when e.g. two wireless modules (one for rx, one for tx) such as XBee are used to connect to the helicopter and bandwidth of one link is to low. rx/tx is seen from the host computer running the communication node. Any baudrate can be set. If it doesn't match a standard baudrate, the closest standard baudrate is chosen. If the HLP doesn't "hear" anything from the node for ~10s, it will go into autobaud mode. During connection setup, the node sends 'a' to the HLP, which will then configure its baudrate automatically.

Parameters:
port_rxport to use for rx
port_txport to use for tx
baudratebaudrate to connect with. equal for both ports. The baudrate finally chosen is written to baudrate.
Returns:
connection successful

Definition at line 73 of file serial_communication.cpp.

uint16_t mav::SerialCommunication::crc16 ( void *  data,
uint16_t  cnt,
uint16_t  crc = 0xff 
) [private]

Definition at line 358 of file serial_communication.cpp.

uint16_t mav::SerialCommunication::crc_update ( uint16_t  crc,
uint8_t  data 
) [inline, private]

Definition at line 350 of file serial_communication.cpp.

Definition at line 129 of file serial_communication.h.

Definition at line 134 of file serial_communication.h.

Definition at line 183 of file serial_communication.h.

void mav::SerialCommunication::processPacketAck ( uint8_t *  buf,
uint32_t  length 
) [private]

Definition at line 319 of file serial_communication.cpp.

template<class T >
void mav::SerialCommunication::registerCallback ( uint8_t  id,
void(T::*)(uint8_t *, uint32_t)  cb_func,
T *  p_obj 
) [inline]

registers a class method that gets called when the packet specified by id was sent from the HLP

Currently, only one method/function can be registered per message id. The method has to be prototyped as follows (see e.g. Comm::processBaudrate):

 void class::method(uint8_t *buffer, uint32_t length) 
Parameters:
idthe message id to subscribe to
cb_functhe method that gets called
p_objpointer to the object whose cb_func should get called

Definition at line 175 of file serial_communication.h.

void mav::SerialCommunication::rxReadCallback ( const boost::system::error_code &  error,
size_t  bytes_transferred 
) [private]

Definition at line 194 of file serial_communication.cpp.

void mav::SerialCommunication::rxReadStart ( uint32_t  length,
uint32_t  timeout = 0 
) [private]

Definition at line 171 of file serial_communication.cpp.

void mav::SerialCommunication::rxTimeoutCallback ( const boost::system::error_code &  error) [private]

Definition at line 184 of file serial_communication.cpp.

template<typename T >
bool mav::SerialCommunication::sendPacket ( uint8_t  packet_id,
const T &  data 
) [inline]

sends a packet to the HLP

Definition at line 141 of file serial_communication.h.

template<typename T >
bool mav::SerialCommunication::sendPacketAck ( uint8_t  packet_id,
const T &  data,
const double &  timeout = 1.0 
) [inline]

sends a packet to the HLP and blocks until it got acknowledged or until the timeout is reached

Definition at line 150 of file serial_communication.h.

void mav::SerialCommunication::serializePacket ( uint8_t  packet_id,
const void *  data,
const int32_t &  packet_size,
uint8_t  flag = 0 
) [private]

Definition at line 305 of file serial_communication.cpp.

bool mav::SerialCommunication::validateChecksum ( uint8_t *  buf,
uint32_t  length,
uint16_t  checksum 
) [private]

Definition at line 166 of file serial_communication.cpp.

bool mav::SerialCommunication::waitForPacketAck ( uint8_t  ack_id,
const double &  timeout = 1.0 
) [private]

Definition at line 327 of file serial_communication.cpp.


Member Data Documentation

Definition at line 88 of file serial_communication.h.

CommCallbackMap mav::SerialCommunication::callbacks_ [private]

Definition at line 89 of file serial_communication.h.

std::vector<uint8_t> mav::SerialCommunication::packet_acks_ [private]

Definition at line 84 of file serial_communication.h.

Definition at line 67 of file serial_communication.h.

Definition at line 74 of file serial_communication.h.

Definition at line 68 of file serial_communication.h.

Definition at line 75 of file serial_communication.h.

uint8_t mav::SerialCommunication::rx_buffer_[256] [private]

Definition at line 81 of file serial_communication.h.

Definition at line 77 of file serial_communication.h.

Definition at line 78 of file serial_communication.h.

Definition at line 83 of file serial_communication.h.

boost::asio::deadline_timer mav::SerialCommunication::rx_timeout_ [private]

Definition at line 70 of file serial_communication.h.

Definition at line 71 of file serial_communication.h.

uint8_t mav::SerialCommunication::tx_buffer_[256] [private]

Definition at line 80 of file serial_communication.h.

Definition at line 82 of file serial_communication.h.

Definition at line 86 of file serial_communication.h.

boost::mutex mav::SerialCommunication::tx_mutex_ [private]

Definition at line 85 of file serial_communication.h.

boost::asio::io_service mav::SerialCommunication::uart_service_ [private]

Definition at line 69 of file serial_communication.h.

boost::thread mav::SerialCommunication::uart_thread_[2] [private]

Definition at line 72 of file serial_communication.h.


The documentation for this class was generated from the following files:


flyer_interface
Author(s): Ivan Dryanovski
autogenerated on Thu Jan 2 2014 11:28:38