phidgets_readdata_synchronous.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2014, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 
35 #include "ros/ros.h"
36 #include <mtt/TargetList.h>
37 #include <sensor_msgs/Range.h>
38 #include <pressure_cells/SenVal.h>
39 #include <odometer/OdometerStatus.h>
40 #include "cmath"
41 #include <iostream>
42 #include <vector>
43 #include <boost/thread.hpp>
44 #include <boost/shared_ptr.hpp>
45 #include <fstream>
46 #include <iostream>
47 
48 using namespace std;
49 
50 // void laserGather(const mtt::TargetList& msg)
51 // {
52 // for(int i=0; i<msg.Targets.size();i++)
53 // {
54 // if (msg.Targets[i].velocity.linear.x >= 0.05)
55 // {
56 // if (msg.Targets[i].id == 302 || msg.Targets[i].id == 27)
57 // {
58 // cout << "Time: " << msg.Targets[i].header.stamp << " | ID: " << msg.Targets[i].id << " | VEL: " << msg.Targets[i].velocity.linear.x << endl;
59 //
60 // ofstream file("/media/Data/Data_Record/velocity.txt",ios::app);
61 //
62 // file << "Time: " << msg.Targets[i].header.stamp << " | ID: " << msg.Targets[i].id << " | VEL: " << msg.Targets[i].velocity.linear.x << endl;
63 //
64 // file.close();
65 //
66 // }
67 // }
68 // }
69 // }
70 
71 void forcevalGather(const pressure_cells::SenVal& msg)
72 {
73 // cout << msg.header.stamp << ":LC 1:" << msg.sen1 << ":FSR 1:" << msg.sen3 << endl;
74 // cout << msg.header.stamp << ":LC 2:" << msg.sen2 << ":FSR 1:" << msg.sen4 << endl;
75  ofstream file("/media/Data/Data_Record/newtests/force_data.txt",ios::app);
76  file << "Time:" << msg.header.stamp << ":LC1:" << msg.sen1 << ":FSR1:" << msg.sen3 << ":LC2:" << msg.sen2 << ":FSR2:" << msg.sen4 << endl;
77  file.close();
78 }
79 
80 void ir1Gather(const sensor_msgs::Range& msg)
81 {
82 // cout << msg.header.stamp << " IR1: " << msg.range << endl;
83  ofstream file("/media/Data/Data_Record/newtests/ir1_data.txt",ios::app);
84  file << "Time:" << msg.header.stamp << ":IR1:" << msg.range << endl;
85  file.close();
86 }
87 
88 void ir2Gather(const sensor_msgs::Range& msg)
89 {
90 // cout << msg.header.stamp << " IR2: " << msg.range << endl;
91  ofstream file("/media/Data/Data_Record/newtests/ir2_data.txt",ios::app);
92  file << "Time:" << msg.header.stamp << ":IR2:" << msg.range << endl;
93  file.close();
94 }
95 
96 void odometerGather(const odometer::OdometerStatus& msg)
97 {
98 // cout << msg.header.stamp << " Velocity: " << msg.velocity << endl;
99 
100  ofstream file("/media/Data/Data_Record/newtests/odometer_data.txt",ios::app);
101  file << "Time:" << msg.header.stamp << ":VEL:" << msg.velocity << endl;
102  file.close();
103 }
104 
105 int main(int argc, char **argv)
106 {
107 
108  ros::init(argc, argv, "data_gather");
109 
110  ros::NodeHandle n;
111 
112 // ros::Subscriber laser_data = n.subscribe("/targets", 1000, laserGather);
113  ros::Subscriber forceval_data = n.subscribe("/pedal_monitor/ForceVal", 1000, forcevalGather);
114  ros::Subscriber ir1_data = n.subscribe("/pedal_monitor/IR_1", 1000, ir1Gather);
115  ros::Subscriber ir2_data = n.subscribe("/pedal_monitor/IR_2", 1000, ir2Gather);
116  ros::Subscriber odometer_data = n.subscribe("/pedal_monitor/odometer", 1000, odometerGather);
117 
118 
119 
120  ros::spin();
121 
122  return 0;
123 }
void ir1Gather(const sensor_msgs::Range &msg)
int main(int argc, char **argv)
void forcevalGather(const pressure_cells::SenVal &msg)
void odometerGather(const odometer::OdometerStatus &msg)
void ir2Gather(const sensor_msgs::Range &msg)


pedal_monitor
Author(s): Pedro Mendes
autogenerated on Mon Mar 2 2015 01:32:33