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
00033 #include <ros/ros.h>
00034 #include <std_msgs/String.h>
00035 #include <visualization_msgs/Marker.h>
00036
00037 #include <sys/types.h>
00038 #include <unistd.h>
00039 #include <stdlib.h>
00040
00041 #include <sstream>
00042 #include <unistd.h>
00043
00044 #include <pressure_cells/arduino.h>
00045 #include <pressure_cells/BufferedAsyncSerial.h>
00046 #include <pressure_cells/SenVal.h>
00047
00048 using namespace ros;
00049 using namespace std;
00050
00051 double ee_calibrate(double adc, int cell)
00052 {
00053
00054 if(cell==1)
00055 {
00056 cout<<"cell1: "<<adc<< "sen"<<(0.026574084375916 * adc -0.834411121568734)<< endl;
00057
00058 return (double)(0.026574084375916 * adc -0.834411121568734);
00059 }
00060 if(cell==2)
00061 {
00062 cout<<"cell2: "<<adc<<"sen"<<(0.026233317081797 * adc -4.311235918674921)<<endl;
00063
00064 return (double)(0.026233317081797 * adc -4.311235918674921);
00065 }
00066 if(cell==3)
00067 {
00068
00069
00070 return (double)(0.027158321888210 * adc -1.748472910437862);
00071 }
00072 if(cell==4)
00073 {
00074 cout<<"cell4: "<<adc<<(0.026998009432107 * adc -3.485178371297848)<<endl;
00075
00076 return (double)(0.026998009432107 * adc -3.485178371297848);
00077 }
00078 if(cell==5)
00079 {
00080 cout<<"cell5: "<<adc<<"sen"<<(0.061665094219161 * adc -0.037584380861199)<<endl;
00081
00082 return (double)(0.061665094219161 * adc -0.037584380861199);
00083 }
00084 if(cell==6)
00085 {
00086 cout<<"cell6: "<<adc<<"sen"<<(0.059355778053492 * adc -0.971028934842100)<<endl;
00087
00088 return (double)(0.059355778053492 * adc -0.971028934842100);
00089 }
00090 if(cell==7)
00091 {
00092 cout<<"cell7: "<<adc<<"sen"<<(0.061558158124062 * adc -1.514361056192554)<<endl;
00093
00094 return (double)(0.061558158124062 * adc -1.514361056192554);
00095 }
00096 if(cell==8)
00097 {
00098 cout<<"cell8: "<<adc<<"sen"<<(0.022712489442863 * adc -5.845013447028478)<<endl;
00099
00100 return (double)(0.017712489442863 * adc -5.845013447028478);
00101 }
00102
00103 return -1;
00104 }
00105
00110 int main ( int argc, char **argv )
00111 {
00112
00113
00114 bool viz=0;
00115
00116 init( argc, argv, "arduino" );
00117
00118 NodeHandle n("~");
00119
00120 ros::Publisher pub_viz;
00121
00122 string device;
00123 string device_default = "default_device";
00124 n.param("/device", device, device_default );
00125
00126
00127 string tf_feet;
00128 string tf_feet_default = "tf_default_feet";
00129 n.param( "tf_feet", tf_feet, tf_feet_default );
00130
00131
00132 string markers;
00133 string markers_default = "default_markers";
00134 n.param("markers", markers, markers_default );
00135
00136
00137 std::string check_markers;
00138 n.getParam("markers", check_markers);
00139
00140 if (check_markers!=markers_default)
00141 {
00142 ROS_INFO("Setting markers parameter to %s", check_markers.c_str());
00143 viz=1;
00144 }
00145
00146
00147
00148 int cell1;
00149 int cell1_default = 1;
00150 n.param("cell1", cell1, cell1_default );
00151
00152 int cell2;
00153 int cell2_default = 2;
00154 n.param("cell2", cell2, cell2_default );
00155
00156 int cell3;
00157 int cell3_default = 3;
00158 n.param("cell3", cell3, cell3_default );
00159
00160 int cell4;
00161 int cell4_default = 4;
00162 n.param("cell4", cell4, cell4_default );
00163
00164
00165 pub_viz = n.advertise<visualization_msgs::Marker>( markers, 0 );
00166
00167 Publisher pub_sen_val = n.advertise< pressure_cells::SenVal >( "/values", 1000 );
00168
00169 Rate loop_rate ( 1400 );
00170
00171 pressure_cells::SenVal senval;
00172
00173 BufferedAsyncSerial serial( device, 115200 );
00174
00175 string data;
00176 double adc1, adc2, adc3, adc4;
00177
00178
00179
00180
00181
00182
00183
00184
00185 while ( ok () )
00186 {
00187
00188
00189 try
00190 {
00191
00192
00193 data = serial.readStringUntil ( "\n" );
00194
00195
00196 if(data.size()==0)
00197 continue;
00198
00199 cout<<"Processing message: "<<data<<endl;
00200
00201 istringstream buffer(data);
00202
00203 double v1,v2,v3,v4;
00204 buffer >> v1;
00205 buffer >> v2;
00206 buffer >> v3;
00207 buffer >> v4;
00208
00209
00210 adc1=v1; adc2=v2; adc3=v4; adc4=v3;
00211
00212
00213
00214
00215
00216 senval.sen1=ee_calibrate(adc1, cell1); if(senval.sen1<=0) senval.sen1=0.001;
00217 senval.sen2=ee_calibrate(adc2, cell2); if(senval.sen2<=0) senval.sen2=0.001;
00218 senval.sen3=ee_calibrate(adc3, cell3); if(senval.sen3<=0) senval.sen3=0.001;
00219 senval.sen4=ee_calibrate(adc4, cell4); if(senval.sen4<=0) senval.sen4=0.001;
00220
00221
00222 senval.header.stamp = ros::Time::now ( );
00223
00224 pub_sen_val.publish ( senval );
00225
00226 if(viz)
00227 {
00228 geometry_msgs::Point f1_p1;
00229 geometry_msgs::Point f1_p2;
00230 geometry_msgs::Point f2_p1;
00231 geometry_msgs::Point f2_p2;
00232 geometry_msgs::Point f3_p1;
00233 geometry_msgs::Point f3_p2;
00234 geometry_msgs::Point f4_p1;
00235 geometry_msgs::Point f4_p2;
00236
00237 visualization_msgs::Marker force1;
00238 visualization_msgs::Marker force2;
00239 visualization_msgs::Marker force3;
00240 visualization_msgs::Marker force4;
00241
00242
00243 force1.header.frame_id = tf_feet;
00244 force1.header.stamp = ros::Time();
00245 force1.ns = "force1";
00246 force1.id = 0;
00247 force1.type = visualization_msgs::Marker::ARROW;
00248 force1.action = visualization_msgs::Marker::ADD;
00249 force1.scale.x = 0.02;
00250 force1.scale.y = 0.02;
00251 force1.scale.z = 0;
00252 force1.color.a = 1.0;
00253 force1.color.r = 1.0;
00254 force1.color.g = 0.5;
00255 force1.color.b = 0.0;
00256
00257 force1.points.clear();
00258 f1_p1.x = 0.044;
00259 f1_p1.y = 0.022;
00260 f1_p1.z = 0;
00261 force1.points.push_back(f1_p1);
00262 f1_p2.x = 0.044;
00263 f1_p2.y = 0.022;
00264 f1_p2.z = senval.sen1/25;
00265 force1.points.push_back(f1_p2);
00266
00267
00268 force2.header.frame_id = tf_feet;
00269 force2.header.stamp = ros::Time();
00270 force2.ns = "force2";
00271 force2.id = 0;
00272 force2.type = visualization_msgs::Marker::ARROW;
00273 force2.action = visualization_msgs::Marker::ADD;
00274 force2.scale.x = 0.02;
00275 force2.scale.y = 0.02;
00276 force2.scale.z = 0;
00277 force2.color.a = 1.0;
00278 force2.color.r = 0.02;
00279 force2.color.g = 0.8;
00280 force2.color.b = 0.02;
00281
00282 force2.points.clear();
00283 f2_p1.x = 0.044;
00284 f2_p1.y = -0.022;
00285 f2_p1.z = 0;
00286 force2.points.push_back(f2_p1);
00287 f2_p2.x = 0.044;
00288 f2_p2.y = -0.022;
00289 f2_p2.z = senval.sen2/25;
00290 force2.points.push_back(f2_p2);
00291
00292
00293 force3.header.frame_id = tf_feet;
00294 force3.header.stamp = ros::Time();
00295 force3.ns = "force3";
00296 force3.id = 0;
00297 force3.type = visualization_msgs::Marker::ARROW;
00298 force3.action = visualization_msgs::Marker::ADD;
00299 force3.scale.x = 0.02;
00300 force3.scale.y = 0.02;
00301 force3.scale.z = 0;
00302 force3.color.a = 1.0;
00303 force3.color.r = 0.02;
00304 force3.color.g = 0.37;
00305 force3.color.b = 0.8;
00306
00307 force3.points.clear();
00308 f3_p1.x = -0.046;
00309 f3_p1.y = -0.023;
00310 f3_p1.z = 0;
00311 force3.points.push_back(f3_p1);
00312 f3_p2.x = -0.046;
00313 f3_p2.y = -0.023;
00314 f3_p2.z = senval.sen3/25;
00315 force3.points.push_back(f3_p2);
00316
00317
00318 force4.header.frame_id = tf_feet;
00319 force4.header.stamp = ros::Time();
00320 force4.ns = "force4";
00321 force4.id = 0;
00322 force4.type = visualization_msgs::Marker::ARROW;
00323 force4.action = visualization_msgs::Marker::ADD;
00324 force4.scale.x = 0.02;
00325 force4.scale.y = 0.02;
00326 force4.scale.z = 0;
00327 force4.color.a = 1.0;
00328 force4.color.r = 0.37;
00329 force4.color.g = 0.02;
00330 force4.color.b = 0.8;
00331
00332 force4.points.clear();
00333 f4_p1.x = -0.046;
00334 f4_p1.y = 0.023;
00335 f4_p1.z = 0;
00336 force4.points.push_back(f4_p1);
00337 f4_p2.x = -0.046;
00338 f4_p2.y = 0.023;
00339 f4_p2.z = senval.sen4/25;
00340 force4.points.push_back(f4_p2);
00341
00342 pub_viz.publish( force1 );
00343 pub_viz.publish( force2 );
00344 pub_viz.publish( force3 );
00345 pub_viz.publish( force4 );
00346
00347 }
00348
00349
00350 }
00351 catch ( boost::system::system_error& e )
00352 {
00353 cout << "Error: " << e.what ( ) << endl;
00354 return 1;
00355 }
00356
00357 loop_rate.sleep();
00358 spinOnce();
00359
00360 }
00361
00362 return 0;
00363 }