Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <stdlib.h>
00038 #include <stdio.h>
00039 #include <math.h>
00040 #include <string.h>
00041
00042 #include "ardusim/Ardusim.h"
00043
00044 using namespace ardusim;
00045
00046 int main(int argc, char** argv)
00047 {
00048 ros::init(argc, argv, "nose_node");
00049
00050 ros::NodeHandle n;
00051 ros::NodeHandle pn("~");
00052
00053 std::vector<lse_sensor_msgs::Nostril> nose_msgs;
00054
00055 ros::Publisher nose_pub = n.advertise<lse_sensor_msgs::Nostril>("/nose", 1);
00056
00057
00058 std::string port;
00059 pn.param<std::string>("port", port, "/dev/ttyUSB1");
00060 std::string frame_id;
00061 pn.param<std::string>("frame_id", frame_id, "/base_nose");
00062
00063 double clean_air_2620;
00064 pn.param("clean_air_2620", clean_air_2620, 0.0);
00065 double clean_air_2600;
00066 pn.param("clean_air_2600", clean_air_2600, 0.0);
00067
00068 double min_2620;
00069 pn.param("min_2620", min_2620, 0.0);
00070 double max_2620;
00071 pn.param("max_2620", max_2620, 0.0);
00072
00073 double min_2600;
00074 pn.param("min_2600", min_2600, 1000.0);
00075 double max_2600;
00076 pn.param("max_2600", max_2600, 1000.0);
00077
00078 double a_2620;
00079 pn.param("a_2620", a_2620, 1.0);
00080 double b_2620;
00081 pn.param("b_2620", b_2620, 1.0);
00082 double a_2600;
00083 pn.param("a_2600", a_2600, 1.0);
00084 double b_2600;
00085 pn.param("b_2600", b_2600, 1.0);
00086
00087 Ardusim ardusim(port);
00088
00089 int requests[] = {ARDUSIM_NOSE};
00090 ardusim.setRequests(requests, 1);
00091
00092 ros::Rate r(10);
00093 while(ros::ok())
00094 {
00095 if(ardusim.getSensorData(100))
00096 {
00097 if(ardusim.getNose(&nose_msgs))
00098 {
00099 nose_msgs[0].sensor_model = "Figaro 2620";
00100 nose_msgs[0].gas_type.push_back(lse_sensor_msgs::Nostril::ORGANIC_SOLVENTS);
00101 nose_msgs[0].clean_air = clean_air_2620;
00102 nose_msgs[0].reading = exp((nose_msgs[0].raw_data-b_2620)/a_2620);
00103 nose_msgs[0].min_reading = min_2620;
00104 nose_msgs[0].max_reading = max_2620;
00105
00106 nose_msgs[1].sensor_model = "Figaro 2600";
00107 nose_msgs[1].gas_type.push_back(lse_sensor_msgs::Nostril::AIR_CONTAMINANTS);
00108 nose_msgs[1].clean_air = clean_air_2600;
00109 nose_msgs[1].reading = exp((nose_msgs[1].raw_data-b_2600)/a_2600);
00110 nose_msgs[1].min_reading = min_2600;
00111 nose_msgs[1].max_reading = max_2600;
00112
00113 for(int i=0 ; i<nose_msgs.size() ; i++)
00114 {
00115 nose_msgs[i].header.frame_id = frame_id;
00116 nose_pub.publish(nose_msgs.at(i));
00117 }
00118 }
00119 }
00120
00121 r.sleep();
00122 }
00123
00124 return(0);
00125 }
00126
00127
00128