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
00032 #include <unistd.h>
00033
00034 #include <iostream>
00035 #include <string>
00036 #include <vector>
00037 #include <map>
00038 #include <fstream>
00039
00040 #include <ros/ros.h>
00041
00042 #include <tf/transform_listener.h>
00043
00044 #include <visualization_msgs/Marker.h>
00045 #include <visualization_msgs/MarkerArray.h>
00046
00047 #include <phantom_control/Force.h>
00048 #include <pressure_cells/Cop.h>
00049 #include <phantom_control/State.h>
00050 #include <phantom_filter/Phantom.h>
00051 #include <humanoid_control/Humanoid.h>
00052 #include <pressure_cells/SenVal.h>
00053
00054 using namespace std;
00055 using namespace ros;
00056
00057 class Conversion
00058 {
00059 public:
00060
00061 Conversion():
00062 n_("~")
00063 {
00064 arduino_1_values_report_name_ = ros::names::remap("arduino_1_values_report");
00065 arduino_2_values_report_name_ = ros::names::remap("arduino_2_values_report");
00066
00067 cop_left_right_report_name_ = ros::names::remap("cop_left_right_report");
00068 cop_left_report_name_ = ros::names::remap("cop_left_report");
00069 cop_right_report_name_ = ros::names::remap("cop_right_report");
00070
00071 force_report_name_ = ros::names::remap("force_report_name_");
00072 humanoid_state_report_name_ = ros::names::remap("humanoid_state_report");
00073 phantom_state_report_name_ = ros::names::remap("phantom_state_report");
00074
00075 phantom_filter_report_name_ = ros::names::remap("phantom_filter_report");
00076
00077 remove(arduino_1_values_report_name_.c_str());
00078 remove(arduino_2_values_report_name_.c_str());
00079
00080 remove(cop_left_right_report_name_.c_str());
00081 remove(cop_left_report_name_.c_str());
00082 remove(cop_right_report_name_.c_str());
00083
00084 remove(force_report_name_.c_str());
00085 remove(humanoid_state_report_name_.c_str());
00086 remove(phantom_state_report_name_.c_str());
00087 remove(phantom_filter_report_name_.c_str());
00088
00089 arduino_1_handler_ = n_.subscribe<pressure_cells::SenVal> ("/arduino_1_values",1000,boost::bind(&Conversion::ArduinoHandler,this,_1,arduino_1_values_report_name_));
00090 arduino_2_handler_ = n_.subscribe<pressure_cells::SenVal> ("/arduino_2_values",1000,boost::bind(&Conversion::ArduinoHandler,this,_1,arduino_2_values_report_name_));
00091
00092 cop_left_right_handler_ = n_.subscribe<pressure_cells::Cop> ("/cop_left_right",1000,boost::bind(&Conversion::COPHandler,this,_1,cop_left_right_report_name_));
00093 cop_left_handler_ = n_.subscribe<pressure_cells::Cop> ("/cop_left",1000,boost::bind(&Conversion::COPHandler,this,_1,cop_left_report_name_));
00094 cop_right_handler_ = n_.subscribe<pressure_cells::Cop> ("/cop_right",1000,boost::bind(&Conversion::COPHandler,this,_1,cop_right_report_name_));
00095
00096 force_report_handler_ = n_.subscribe ("/force",1000, &Conversion::ForceHandler, this);
00097
00098 humanoid_state_handler_ = n_.subscribe("/humanoid_state",1000, &Conversion::HumanoidHandler, this);
00099
00100 phantom_state_handler_ = n_.subscribe ("/phantom_state",1000, &Conversion::PhantomHandler, this);
00101
00102 phantom_filter_handler_ = n_.subscribe ("/phantom_filter",1000, &Conversion::PhantomFHandler, this);
00103
00104 }
00105
00106 ~Conversion()
00107 {
00108
00109 }
00110
00111 void ArduinoHandler(const pressure_cells::SenVal::ConstPtr& ard_values, string report_name)
00112 {
00113 ofstream report_ard;
00114 report_ard.open(report_name.c_str(),ios::app);
00115
00116 boost::format fm("%.6f");
00117 fm % ard_values->header.stamp.toSec();
00118
00119 report_ard<<ard_values->header.seq<<" "<<fm.str()<<" "<< ard_values->sen1<<" "<< ard_values->sen2 <<" "<< ard_values->sen3 <<" "<<ard_values->sen4<<endl;
00120
00121 report_ard.close();
00122 }
00123
00124 void COPHandler(const pressure_cells::Cop::ConstPtr& cop_values, string report_name)
00125 {
00126 ofstream report_cop;
00127 report_cop.open(report_name.c_str(),ios::app);
00128
00129 boost::format fm("%.6f");
00130 fm % cop_values->header.stamp.toSec() ;
00131
00132 report_cop<<cop_values->header.seq<<" "<<fm.str()<<" "<< cop_values->copx <<" "<<cop_values->copy<<endl;
00133
00134 report_cop.close();
00135 }
00136
00137 void ForceHandler(const phantom_control::ForcePtr& force_values)
00138 {
00139 ofstream report_force;
00140 report_force.open(force_report_name_.c_str(),ios::app);
00141
00142 boost::format fm("%.6f");
00143 fm % force_values->header.stamp.toSec();
00144
00145 report_force<<force_values->header.seq<<" "<<fm.str()<<" "<< force_values->force[0]<<" "<< force_values->force[1]<<" "<< force_values->force[2]<<endl;
00146
00147 report_force.close();
00148
00149 }
00150
00151 void HumanoidHandler(const humanoid_control::HumanoidPtr& humanoid_values)
00152 {
00153 ofstream report_humanoid;
00154 report_humanoid.open(humanoid_state_report_name_.c_str(),ios::app);
00155
00156 boost::format fm("%.6f");
00157 fm % humanoid_values->header.stamp.toSec();
00158
00159 report_humanoid<<humanoid_values->header.seq<<" "<<fm.str();
00160
00161 report_humanoid<<" ";
00162 for (int i = 0; i < 12; i++)
00163 {
00164 report_humanoid<<" "<<humanoid_values->speed_now[i];
00165 }
00166 report_humanoid<<" ";
00167 for (int i = 0; i < 12; i++)
00168 {
00169 report_humanoid<<" "<<humanoid_values->speed_wanted[i];
00170 }
00171 report_humanoid<<" ";
00172 for (int i = 0; i < 12; i++)
00173 {
00174 report_humanoid<<" "<<humanoid_values->joint_now[i];
00175 }
00176 report_humanoid<<" ";
00177 for (int i = 0; i < 12; i++)
00178 {
00179 report_humanoid<<" "<<humanoid_values->joint_wanted[i];
00180 }
00181
00182 report_humanoid<<endl;
00183
00184 report_humanoid.close();
00185
00186 }
00187
00188 void PhantomHandler(const phantom_control::StatePtr& phantom_values)
00189 {
00190 ofstream report_phantom;
00191 report_phantom.open(phantom_state_report_name_.c_str(),ios::app);
00192
00193 boost::format fm("%.6f");
00194 fm % phantom_values->header.stamp.toSec();
00195
00196 report_phantom<<phantom_values->header.seq<<" "<<fm.str();
00197
00198 for (int i = 0; i < 3; i++)
00199 {
00200 report_phantom<<" "<<phantom_values->position[i];
00201 }
00202 for (int i = 0; i < 3; i++)
00203 {
00204 report_phantom<<" "<<phantom_values->rot[i];
00205 }
00206 for (int i = 0; i < 3; i++)
00207 {
00208 report_phantom<<" "<<phantom_values->joints[i];
00209 }
00210 for (int i = 0; i < 3; i++)
00211 {
00212 report_phantom<<" "<<phantom_values->force[i];
00213 }
00214 for (int i = 0; i < 2; i++)
00215 {
00216 report_phantom<<" "<<phantom_values->buttons[i];
00217 }
00218
00219 report_phantom<<" "<<phantom_values->home;
00220
00221 for (int i = 0; i < 3; i++)
00222 {
00223 report_phantom<<" "<<phantom_values->home_pos[i];
00224 }
00225
00226 report_phantom<<endl;
00227
00228 report_phantom.close();
00229
00230 }
00231
00232
00233 void PhantomFHandler(const phantom_filter::PhantomPtr& phantom_values)
00234 {
00235 ofstream report_phantomF;
00236 report_phantomF.open(phantom_filter_report_name_.c_str(),ios::app);
00237
00238 boost::format fm("%.6f");
00239 fm % phantom_values->header.stamp.toSec();
00240
00241 report_phantomF<<phantom_values->header.seq<<" "<<fm.str();
00242
00243 for (int i = 0; i < 3; i++)
00244 {
00245 report_phantomF<<" "<<phantom_values->Position[i];
00246 }
00247 for (int i = 0; i < 3; i++)
00248 {
00249 report_phantomF<<" "<<phantom_values->Rot[i];
00250 }
00251
00252 for (int i = 0; i < 2; i++)
00253 {
00254 report_phantomF<<" "<<phantom_values->Button[i];
00255 }
00256
00257
00258 report_phantomF<<endl;
00259
00260 report_phantomF.close();
00261
00262 }
00263
00264 string arduino_1_values_report_name_;
00265 string arduino_2_values_report_name_;
00266
00267 string cop_left_right_report_name_;
00268 string cop_left_report_name_;
00269 string cop_right_report_name_;
00270
00271 string force_report_name_;
00272 string humanoid_state_report_name_;
00273 string phantom_state_report_name_;
00274 string phantom_filter_report_name_;
00275
00276 ros::Subscriber arduino_1_handler_;
00277 ros::Subscriber arduino_2_handler_;
00278
00279 ros::Subscriber cop_left_right_handler_;
00280 ros::Subscriber cop_left_handler_;
00281 ros::Subscriber cop_right_handler_;
00282
00283 ros::Subscriber force_report_handler_;
00284 ros::Subscriber humanoid_state_handler_;
00285 ros::Subscriber phantom_state_handler_;
00286 ros::Subscriber phantom_filter_handler_;
00287
00288 ros::NodeHandle n_;
00289 };
00290
00291 int main(int argc,char**argv)
00292 {
00293 ros::init(argc, argv, "bag2txt");
00294
00295 Conversion convert;
00296
00297 cout<<"spining ..."<<endl;
00298 ros::spin();
00299
00300 return 0;
00301 }