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 #define NODE_VERSION 0.01
00038 
00039 #include "SensorNet.h"
00040 
00041 int main(int argc, char** argv)
00042 {
00043         ros::init(argc, argv, "sensornet_node");
00044 
00045         ROS_INFO("SensorNet for ROS %.2f", NODE_VERSION);
00046         
00047         ros::NodeHandle n;
00048         
00049         std::vector<lse_sensor_msgs::Nostril> odorMsgs;
00050         std::vector<lse_sensor_msgs::Nostril>::iterator odorIt;
00051         ros::Publisher odor_pub = n.advertise<lse_sensor_msgs::Nostril>("/sensornet_odor", 1200);
00052         
00053         std::string port;
00054         n.param<std::string>("sensornet/port", port, "/dev/ttyUSB0");
00055         
00056         SensorNet sn(port, 19200);
00057         std::vector<SensorNet::Node>::iterator node;
00058         
00059         ROS_INFO("SensorNet - Scanning nodes...");
00060         sn.scanNodes(1);
00061         if(sn.nodes.size()==0)
00062         {
00063                 ROS_ERROR("SensorNet - Found 0 nodes! Quitting program...");
00064                 return -1;
00065         }
00066         ROS_INFO("SensorNet - Found %d node%s", sn.nodes.size(), sn.nodes.size()==1 ? "!" : "s!");
00067         
00068         for(node=sn.nodes.begin() ; node!=sn.nodes.end() ; node++)
00069         {
00070                 sn.getSensors(&(*node));
00071                 ros::Duration(0.1).sleep();
00072         }
00073         
00074         ROS_INFO("SensorNet - Syncing nodes...");
00075         sn.syncNodes();
00076         
00077         ros::Duration(0.5).sleep();
00078         
00079         double delay = 3.0;
00080         ros::Time start = ros::Time::now();
00081         for(node=sn.nodes.begin() ; node!=sn.nodes.end() ; node++)
00082         {
00083                 sn.setTime(&(*node), start + ros::Duration(delay));
00084                 ros::Duration(0.1).sleep();
00085         }
00086         ROS_INFO("SensorNet - Syncing complete, initiating data publish...");
00087         ros::Duration(delay+10).sleep();
00088         
00089         ros::Rate r(0.1);
00090         while(ros::ok())
00091         {
00092                 odorMsgs.clear();
00093                 for(node=sn.nodes.begin() ; node!=sn.nodes.end() ; node++)
00094                 {
00095                         sn.getSensorReadings(&(*node), &odorMsgs, NULL);
00096                         ros::Duration(0.1).sleep();
00097                 }
00098                 
00099                 int n=0;
00100                 for(odorIt=odorMsgs.begin() ; odorIt!=odorMsgs.end() ; odorIt++)
00101                 {
00102                         odor_pub.publish(*odorIt);
00103                         n++;
00104                 }
00105                         
00106                 ros::spinOnce();
00107                 r.sleep();
00108         }
00109         
00110         return 0;
00111 }
00112 
00113