blmc_drivers
serial_reader.hpp
Go to the documentation of this file.
1 
10 #pragma once
11 
12 #include <cstdlib>
13 #include <iostream>
14 #include <mutex>
15 #include <unistd.h>
16 #include <vector>
17 
18 #include "real_time_tools/thread.hpp"
19 
20 namespace blmc_drivers
21 {
22 
24 {
25 public:
30  SerialReader(const std::string &serial_port, const int &num_values);
31 
32  ~SerialReader();
33 
39  int fill_vector(std::vector<int>& values);
40 
41 private:
49  static THREAD_FUNCTION_RETURN_TYPE loop(void* instance_pointer)
50  {
51  static_cast<SerialReader*>(instance_pointer)->loop();
52  return THREAD_FUNCTION_RETURN_VALUE;
53  }
54 
59  void loop();
60 
66 
71  real_time_tools::RealTimeThread rt_thread_;
72 
76  int fd_;
77 
81  bool has_error_;
82 
86  bool is_active_;
87 
91  int new_data_counter_;
92 
93  int missed_data_counter_;
94 
98  std::vector<int> latest_values_;
99 
103  std::mutex mutex_;
104 };
105 
106 } // namespace blmc_robots
std::mutex mutex_
mutex_ multithreading safety
Definition: serial_reader.hpp:103
bool is_active_
If the communication is active.
Definition: serial_reader.hpp:86
This namespace is the standard namespace of the package.
Definition: const_torque_control.cpp:12
void loop()
This is the real time thread that streams the data to/from the main board.
Definition: serial_reader.cpp:77
std::vector< int > latest_values_
Holds vector with the latest double values.
Definition: serial_reader.hpp:98
SerialReader(const std::string &serial_port, const int &num_values)
Definition: serial_reader.cpp:28
Definition: serial_reader.hpp:23
int fill_vector(std::vector< int > &values)
Fills a vector with the latest values.
Definition: serial_reader.cpp:131
real_time_tools::RealTimeThread rt_thread_
This is the thread object that allow to spwan a real-time thread or not dependening on the current OS...
Definition: serial_reader.hpp:71
bool is_loop_active_
This boolean makes sure that the loop is stopped upon destruction of this object. ...
Definition: serial_reader.hpp:65
bool has_error_
If false, the communication is workinng as expected.
Definition: serial_reader.hpp:81
static THREAD_FUNCTION_RETURN_TYPE loop(void *instance_pointer)
This is the helper function used for spawning the real time thread.
Definition: serial_reader.hpp:49
int fd_
Holds the device serial port.
Definition: serial_reader.hpp:76