
Private Member Functions | |
| virtual size_t | endpoint_read (boost::asio::mutable_buffer buf, boost::system::error_code &err) | 
| void | endpoint_try_open () | 
| virtual size_t | endpoint_write (boost::asio::const_buffer buf, boost::system::error_code &err) | 
Additional Inherited Members | |
  Public Member Functions inherited from novatel_oem7_driver::Oem7Receiver< T::socket > | |
| virtual bool | initialize (ros::NodeHandle &h) | 
| Oem7Receiver () | |
| virtual bool | read (boost::asio::mutable_buffer buf, size_t &rlen) | 
| virtual bool | write (boost::asio::const_buffer buf) | 
| virtual | ~Oem7Receiver () | 
  Public Member Functions inherited from novatel_oem7_driver::Oem7ReceiverIf | |
| virtual | ~Oem7ReceiverIf () | 
  Protected Member Functions inherited from novatel_oem7_driver::Oem7Receiver< T::socket > | |
| void | endpoint_close () | 
| bool | in_error_state () | 
  Protected Attributes inherited from novatel_oem7_driver::Oem7Receiver< T::socket > | |
| T | endpoint_ | 
| boost::asio communication endoint; socket, serial port, etc.  More... | |
| int | max_num_io_errors_ | 
| Number of consecutive io errors before declaring failure and quitting.  More... | |
| ros::NodeHandle | nh_ | 
| int | num_io_errors_ | 
| Number of consecuitive io errors.  More... | |
Definition at line 38 of file oem7_receiver_net.cpp.
      
  | 
  inlineprivatevirtual | 
Read some data from the endpoint.
Implements novatel_oem7_driver::Oem7Receiver< T::socket >.
Definition at line 69 of file oem7_receiver_net.cpp.
      
  | 
  inlineprivatevirtual | 
Attempt to opena the endpoint.
Implements novatel_oem7_driver::Oem7Receiver< T::socket >.
Definition at line 40 of file oem7_receiver_net.cpp.
      
  | 
  inlineprivatevirtual | 
Write some data to the endpoint
Implements novatel_oem7_driver::Oem7Receiver< T::socket >.
Definition at line 75 of file oem7_receiver_net.cpp.