C++ class implementation of the ardusim protocol. More...
#include <inc/Ardusim.h>
Classes | |
| struct | AnemometerCalibData | 
| struct | TopDistances | 
Public Member Functions | |
| Ardusim (std::string port_name) | |
| Constructor.   | |
| int | checkVersion (int timeout) | 
| Check version.   | |
| bool | getAnemometer (std::vector< lse_sensor_msgs::Anemometer > *anemometer) | 
| bool | getNose (std::vector< lse_sensor_msgs::Nostril > *nose) | 
| bool | getRange (std::vector< lse_sensor_msgs::Range > *range) | 
| void | getRequests (std::list< int > *requests) | 
| Get requests.   | |
| bool | getSensorData (int timeout) | 
| Read sensor data from the arduino.   | |
| bool | getThermistor (std::vector< lse_sensor_msgs::Thermistor > *thermistor) | 
| bool | getTPA (std::vector< lse_sensor_msgs::TPA > *tpa) | 
| bool | loadAnemometerCalibFile (std::string *file_path) | 
| Get value.   | |
| bool | sensorDiscovery (int timeout) | 
| Scan i2c sensors.   | |
| bool | setAutoRequests (int timeout) | 
| Ask for connected sensors.   | |
| void | setRequests (int *requests, int num_of_requests) | 
| Set requests.   | |
| ~Ardusim () | |
| Destructor.   | |
Private Member Functions | |
| void | addValue (std::string *data, int value) | 
| Add value.   | |
| bool | autoRequests (int timeout, char mode) | 
| Auto request sensors from the arduino.   | |
| int | getValue (std::string *data) | 
| Get value.   | |
| void | parseAnemometer (std::string *data) | 
| Anemometer data parser.   | |
| bool | parseData (std::string *data) | 
| Parse data.   | |
| void | parseNose (std::string *data) | 
| Nose data parser.   | |
| void | parseRange (std::string *data) | 
| Range data parser.   | |
| void | parseTPA (std::string *data) | 
| TPA data parser.   | |
| bool | sendCommand (int timeout, char mode, std::string *reply) | 
| Send command.   | |
Private Attributes | |
| std::vector < lse_sensor_msgs::Anemometer >  | anemometer_msgs_ | 
| Vector of anemometer messages.   | |
| std::vector< AnemometerCalibData > | calib_data_ | 
| std::vector < lse_sensor_msgs::Nostril >  | nose_msgs_ | 
| Vector of nose messages.   | |
| ros::Time | now_ | 
| Current time.   | |
| std::vector < lse_sensor_msgs::Range >  | range_msgs_ | 
| Vector of range messages.   | |
| std::list< int > | requests_ | 
| List of requests.   | |
| cereal::CerealPort * | serial_port_ | 
| std::vector < lse_sensor_msgs::Thermistor >  | thermistor_msgs_ | 
| Vector of thermistor messages.   | |
| std::vector< lse_sensor_msgs::TPA > | tpa_msgs_ | 
| Vector of tpa messages.   | |
C++ class implementation of the ardusim protocol.
This class implements the ardusim protocol (arduino sensor interface module). This allows for easy ROS publishing of LSE common sensor data.
| ardusim::Ardusim::Ardusim | ( | std::string | port_name | ) | 
Constructor.
| port_name | Name of the serial port to open. | 
Definition at line 49 of file Ardusim.cpp.
Destructor.
Definition at line 80 of file Ardusim.cpp.
| void ardusim::Ardusim::addValue | ( | std::string * | data, | 
| int | value | ||
| ) |  [private] | 
        
Add value.
Parsing helper function. Adds an int value to a std::string.
| data | String. | 
| value | Int value to be added. | 
Definition at line 318 of file Ardusim.cpp.
| bool ardusim::Ardusim::autoRequests | ( | int | timeout, | 
| char | mode | ||
| ) |  [private] | 
        
Auto request sensors from the arduino.
Ask the arduino which sensors are connected to it. This can be user-defined or product of a i2c scan.
| timeout | Timeout in milliseconds. | 
| mode | Ardusim mode. | 
Definition at line 140 of file Ardusim.cpp.
| int ardusim::Ardusim::checkVersion | ( | int | timeout | ) | 
Check version.
Check the software version running in the arduino for compatibility issues.
| timeout | Timeout in milliseconds. | 
Definition at line 126 of file Ardusim.cpp.
| bool ardusim::Ardusim::getAnemometer | ( | std::vector< lse_sensor_msgs::Anemometer > * | anemometer | ) | 
Definition at line 281 of file Ardusim.cpp.
| bool ardusim::Ardusim::getNose | ( | std::vector< lse_sensor_msgs::Nostril > * | nose | ) | 
Definition at line 245 of file Ardusim.cpp.
| bool ardusim::Ardusim::getRange | ( | std::vector< lse_sensor_msgs::Range > * | range | ) | 
Definition at line 227 of file Ardusim.cpp.
| void ardusim::Ardusim::getRequests | ( | std::list< int > * | requests | ) | 
Get requests.
Ask Ardusim which sensors we are getting!
| requests | List of requests. | 
Definition at line 170 of file Ardusim.cpp.
| bool ardusim::Ardusim::getSensorData | ( | int | timeout | ) | 
Read sensor data from the arduino.
Read sensor data from the arduino. The sensors requested are the ones in the list of requests.
| timeout | Timeout in milliseconds. | 
Definition at line 188 of file Ardusim.cpp.
| bool ardusim::Ardusim::getThermistor | ( | std::vector< lse_sensor_msgs::Thermistor > * | thermistor | ) | 
Definition at line 299 of file Ardusim.cpp.
| bool ardusim::Ardusim::getTPA | ( | std::vector< lse_sensor_msgs::TPA > * | tpa | ) | 
Definition at line 263 of file Ardusim.cpp.
| int ardusim::Ardusim::getValue | ( | std::string * | data | ) |  [private] | 
        
Get value.
Parsing helper function. Gets an int value from a std::string.
| data | String. | 
Definition at line 329 of file Ardusim.cpp.
| bool ardusim::Ardusim::loadAnemometerCalibFile | ( | std::string * | file_path | ) | 
Get value.
Load the calibration data for the anemometer from a file.
| file_path | File path. | 
Definition at line 543 of file Ardusim.cpp.
| void ardusim::Ardusim::parseAnemometer | ( | std::string * | data | ) |  [private] | 
        
Anemometer data parser.
Definition at line 431 of file Ardusim.cpp.
| bool ardusim::Ardusim::parseData | ( | std::string * | data | ) |  [private] | 
        
Parse data.
Data parsing function. Parses data comming from the arduino.
| data | String to be parsed. | 
Definition at line 343 of file Ardusim.cpp.
| void ardusim::Ardusim::parseNose | ( | std::string * | data | ) |  [private] | 
        
Nose data parser.
Definition at line 393 of file Ardusim.cpp.
| void ardusim::Ardusim::parseRange | ( | std::string * | data | ) |  [private] | 
        
Range data parser.
Definition at line 375 of file Ardusim.cpp.
| void ardusim::Ardusim::parseTPA | ( | std::string * | data | ) |  [private] | 
        
TPA data parser.
Definition at line 412 of file Ardusim.cpp.
| bool ardusim::Ardusim::sendCommand | ( | int | timeout, | 
| char | mode, | ||
| std::string * | reply | ||
| ) |  [private] | 
        
Send command.
Send a command to the arduino.
| timeout | Timeout in milliseconds. | 
| mode | Ardusim mode. | 
| reply | Reply from the arduino. | 
Definition at line 93 of file Ardusim.cpp.
| bool ardusim::Ardusim::sensorDiscovery | ( | int | timeout | ) |  [inline] | 
        
Scan i2c sensors.
Commands the arduino to perform a i2c scan to detect connected sensors automatically. Wrapper for autoRequests.
| timeout | Timeout in milliseconds. | 
| bool ardusim::Ardusim::setAutoRequests | ( | int | timeout | ) |  [inline] | 
        
Ask for connected sensors.
Asks the arduino which user-defined sensors are connected. Wrapper for autoRequests.
| timeout | Timeout in milliseconds. | 
| void ardusim::Ardusim::setRequests | ( | int * | requests, | 
| int | num_of_requests | ||
| ) | 
Set requests.
Tell the arduino which sensors to read.
| requests | Array of requests to read. | 
| num_of_requests | Number of requests. | 
Definition at line 177 of file Ardusim.cpp.
std::vector<lse_sensor_msgs::Anemometer> ardusim::Ardusim::anemometer_msgs_ [private] | 
        
std::vector<AnemometerCalibData> ardusim::Ardusim::calib_data_ [private] | 
        
std::vector<lse_sensor_msgs::Nostril> ardusim::Ardusim::nose_msgs_ [private] | 
        
ros::Time ardusim::Ardusim::now_ [private] | 
        
std::vector<lse_sensor_msgs::Range> ardusim::Ardusim::range_msgs_ [private] | 
        
std::list<int> ardusim::Ardusim::requests_ [private] | 
        
cereal::CerealPort* ardusim::Ardusim::serial_port_ [private] | 
        
std::vector<lse_sensor_msgs::Thermistor> ardusim::Ardusim::thermistor_msgs_ [private] | 
        
std::vector<lse_sensor_msgs::TPA> ardusim::Ardusim::tpa_msgs_ [private] |