From a9b5e50cd7bfa879c7e1629011e1324529280688 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Thu, 27 Jul 2017 03:50:15 +0200 Subject: [PATCH 01/23] [Issue #792] Removes compilation warnings from visionlib/cvblob --- src/libs/visionlib/cvblob/cvcolor.cpp | 10 +-- src/libs/visionlib/cvblob/cvcontour.cpp | 22 +++++-- src/libs/visionlib/cvblob/cvlabel.cpp | 84 +++++++++++++------------ src/libs/visionlib/cvblob/cvtrack.cpp | 11 ++-- 4 files changed, 73 insertions(+), 54 deletions(-) diff --git a/src/libs/visionlib/cvblob/cvcolor.cpp b/src/libs/visionlib/cvblob/cvcolor.cpp index fda20d465..f2cefaa06 100644 --- a/src/libs/visionlib/cvblob/cvcolor.cpp +++ b/src/libs/visionlib/cvblob/cvcolor.cpp @@ -45,8 +45,8 @@ namespace cvb int imgLabel_width = imgLabel->width; int imgLabel_height = imgLabel->height; int imgLabel_offset = 0; - int img_width = img->width; - int img_height = img->height; + // int img_width = img->width; // Unused but set + // int img_height = img->height; // Unused but set int img_offset = 0; if(imgLabel->roi) { @@ -56,8 +56,8 @@ namespace cvb } if(img->roi) { - img_width = img->roi->width; - img_height = img->roi->height; + // img_width = img->roi->width; // Unused but set + // img_height = img->roi->height; // Unused but set img_offset = (img->nChannels * img->roi->xOffset) + (img->roi->yOffset * stepImg); } @@ -99,6 +99,8 @@ namespace cvb return cvScalar(mr, mg, mb); } __CV_END__; + + return cvScalar(0, 0, 0); // Remove return warning } } diff --git a/src/libs/visionlib/cvblob/cvcontour.cpp b/src/libs/visionlib/cvblob/cvcontour.cpp index 71b514d08..62aa0a965 100644 --- a/src/libs/visionlib/cvblob/cvcontour.cpp +++ b/src/libs/visionlib/cvblob/cvcontour.cpp @@ -53,14 +53,14 @@ namespace cvb CV_ASSERT(img&&(img->depth==IPL_DEPTH_8U)&&(img->nChannels==3)); int stepDst = img->widthStep/(img->depth/8); - int img_width = img->width; - int img_height = img->height; + // int img_width = img->width; // Unused but set + // int img_height = img->height; // Unused but set int img_offset = 0; if(img->roi) { - img_width = img->roi->width; - img_height = img->roi->height; + // img_width = img->roi->width; // Unused but set + // img_height = img->roi->height; // Unused but set img_offset = (img->nChannels * img->roi->xOffset) + (img->roi->yOffset * stepDst); } @@ -121,6 +121,8 @@ namespace cvb return contour; } __CV_END__; + + return NULL; } void cvRenderContourPolygon(CvContourPolygon const *contour, IplImage *img, CvScalar const &color) @@ -175,6 +177,8 @@ namespace cvb return a*0.5; } __CV_END__; + + return 0; } double cvContourChainCodePerimeter(CvContourChainCode const *c) @@ -197,6 +201,8 @@ namespace cvb return perimeter; } __CV_END__; + + return 0; // Remove return warning } double cvContourPolygonPerimeter(CvContourPolygon const *p) @@ -214,6 +220,8 @@ namespace cvb return perimeter; } __CV_END__; + + return 0; // Return-type warning fix } double cvContourPolygonCircularity(const CvContourPolygon *p) @@ -232,6 +240,8 @@ namespace cvb return 0.; } __CV_END__; + + return 0; // Remove return warning } void simplifyPolygonRecursive(CvContourPolygon const *p, int const i1, int const i2, bool *pnUseFlag, double const delta) @@ -321,6 +331,8 @@ namespace cvb return result; } __CV_END__; + + return NULL; } CvContourPolygon *cvPolygonContourConvexHull(CvContourPolygon const *p) @@ -375,6 +387,8 @@ namespace cvb return new CvContourPolygon(dq.begin(), dq.end()); } __CV_END__; + + return NULL; } void cvWriteContourPolygonCSV(const CvContourPolygon& p, const string& filename) diff --git a/src/libs/visionlib/cvblob/cvlabel.cpp b/src/libs/visionlib/cvblob/cvlabel.cpp index 5cec261ab..2d36b98c7 100644 --- a/src/libs/visionlib/cvblob/cvlabel.cpp +++ b/src/libs/visionlib/cvblob/cvlabel.cpp @@ -64,8 +64,8 @@ namespace cvb unsigned int imgIn_width = img->width; unsigned int imgIn_height = img->height; unsigned int imgIn_offset = 0; - unsigned int imgOut_width = imgOut->width; - unsigned int imgOut_height = imgOut->height; + // unsigned int imgOut_width = imgOut->width; // Unused but set + // unsigned int imgOut_height = imgOut->height; // Unused but set unsigned int imgOut_offset = 0; if(img->roi) { @@ -75,8 +75,8 @@ namespace cvb } if(imgOut->roi) { - imgOut_width = imgOut->roi->width; - imgOut_height = imgOut->roi->height; + // imgOut_width = imgOut->roi->width; // Unused but set + // imgOut_height = imgOut->roi->height; // Unused but set imgOut_offset = imgOut->roi->xOffset + (imgOut->roi->yOffset * stepOut); } @@ -143,9 +143,9 @@ namespace cvb for (unsigned char i=0; i<3; i++) { - int nx = xx+movesE[direction][i][0]; - int ny = yy+movesE[direction][i][1]; - if ((nx=0)&&(ny=0)) + unsigned int nx = xx + movesE[direction][i][0]; + unsigned int ny = yy + movesE[direction][i][1]; + if ((nx < imgIn_width) && (nx >= 0) && (ny < imgIn_height) && (ny >= 0)) { if (imageIn(nx, ny)) { @@ -153,10 +153,10 @@ namespace cvb blob->contour.chainCode.push_back(movesE[direction][i][3]); - xx=nx; - yy=ny; + xx = nx; + yy = ny; - direction=movesE[direction][i][2]; + direction = movesE[direction][i][2]; break; } else @@ -167,7 +167,7 @@ namespace cvb } if (!found) - direction=(direction+1)%4; + direction = (direction + 1) % 4; else { if (imageOut(xx, yy) != label) @@ -175,21 +175,21 @@ namespace cvb imageOut(xx, yy) = label; numPixels++; - if (xxminx) blob->minx = xx; - else if (xx>blob->maxx) blob->maxx = xx; - if (yyminy) blob->miny = yy; - else if (yy>blob->maxy) blob->maxy = yy; + if (xx < blob->minx) blob->minx = xx; + else if (xx > blob->maxx) blob->maxx = xx; + if (yy < blob->miny) blob->miny = yy; + else if (yy > blob->maxy) blob->maxy = yy; blob->area++; - blob->m10+=xx; blob->m01+=yy; - blob->m11+=xx*yy; - blob->m20+=xx*xx; blob->m02+=yy*yy; + blob->m10 += xx; blob->m01 += yy; + blob->m11 += xx*yy; + blob->m20 += xx*xx; blob->m02 += yy * yy; } break; } - if (contourEnd = ((xx==x) && (yy==y) && (direction==1))) + if ( (contourEnd = ((xx == x) && (yy == y) && (direction == 1))) ) break; } } @@ -197,7 +197,7 @@ namespace cvb } - if ((y+1area++; - blob->m10+=x; blob->m01+=y; - blob->m11+=x*y; - blob->m20+=x*x; blob->m02+=y*y; + blob->m10 += x; blob->m01 += y; + blob->m11 += x*y; + blob->m20 += x*x; blob->m02 += y*y; } else { @@ -246,7 +246,7 @@ namespace cvb } // XXX This is not necessary (I believe). I only do this for consistency. - imageOut(x, y+1) = CV_BLOB_MAX_LABEL; + imageOut(x, y + 1) = CV_BLOB_MAX_LABEL; CvContourChainCode *contour = new CvContourChainCode; contour->startingPoint = cvPoint(x, y); @@ -263,8 +263,8 @@ namespace cvb for (unsigned char i=0; i<3; i++) { - int nx = xx+movesI[direction][i][0]; - int ny = yy+movesI[direction][i][1]; + unsigned int nx = xx + movesI[direction][i][0]; + unsigned int ny = yy + movesI[direction][i][1]; if (imageIn(nx, ny)) { found = true; @@ -293,9 +293,9 @@ namespace cvb numPixels++; blob->area++; - blob->m10+=xx; blob->m01+=yy; - blob->m11+=xx*yy; - blob->m20+=xx*xx; blob->m02+=yy*yy; + blob->m10 += xx; blob->m01 += yy; + blob->m11 += xx*yy; + blob->m20 += xx*xx; blob->m02 += yy*yy; } break; @@ -326,9 +326,9 @@ namespace cvb lastBlob = blob; } blob->area++; - blob->m10+=x; blob->m01+=y; - blob->m11+=x*y; - blob->m20+=x*x; blob->m02+=y*y; + blob->m10 += x; blob->m01 += y; + blob->m11 += x*y; + blob->m20 += x*x; blob->m02 += y*y; } } } @@ -358,6 +358,8 @@ namespace cvb } __CV_END__; + + return 0; // Remove return warning } void cvFilterLabels(IplImage *imgIn, IplImage *imgOut, const CvBlobs &blobs) @@ -373,8 +375,8 @@ namespace cvb int imgIn_width = imgIn->width; int imgIn_height = imgIn->height; int imgIn_offset = 0; - int imgOut_width = imgOut->width; - int imgOut_height = imgOut->height; + //int imgOut_width = imgOut->width; // Set but unused + //int imgOut_height = imgOut->height; // Set but unused int imgOut_offset = 0; if(imgIn->roi) { @@ -384,8 +386,8 @@ namespace cvb } if(imgOut->roi) { - imgOut_width = imgOut->roi->width; - imgOut_height = imgOut->roi->height; + //imgOut_width = imgOut->roi->width; // Set but unused + //imgOut_height = imgOut->roi->height; // Set but unused imgOut_offset = imgOut->roi->xOffset + (imgOut->roi->yOffset * stepOut); } @@ -419,9 +421,9 @@ namespace cvb CV_ASSERT(img&&(img->depth==IPL_DEPTH_LABEL)&&(img->nChannels==1)); int step = img->widthStep / (img->depth / 8); - int img_width = 0; - int img_height= 0; - int img_offset = 0; + unsigned int img_width = 0; + unsigned int img_height= 0; + unsigned int img_offset = 0; if(img->roi) { img_width = img->roi->width; @@ -434,7 +436,7 @@ namespace cvb img_height= img->height; } - CV_ASSERT((x>=0)&&(x=0)&&(y= 0) && (x < img_width) && (y >= 0)&&(y < img_height)); return ((CvLabel *)(img->imageData + img_offset))[x + y*step]; } diff --git a/src/libs/visionlib/cvblob/cvtrack.cpp b/src/libs/visionlib/cvblob/cvtrack.cpp index 6bc8ca115..598de7cf6 100644 --- a/src/libs/visionlib/cvblob/cvtrack.cpp +++ b/src/libs/visionlib/cvblob/cvtrack.cpp @@ -189,9 +189,9 @@ namespace cvb } // Proximity matrix calculation and "used blob" list inicialization: - for (i=0; isecond->centroid.x, (int)it->second->centroid.y), font, CV_RGB(0.,255.,0.)); } - if (mode&CV_TRACK_RENDER_BOUNDING_BOX) + if (mode & CV_TRACK_RENDER_BOUNDING_BOX) + { if (it->second->inactive) cvRectangle(imgDest, cvPoint(it->second->minx, it->second->miny), cvPoint(it->second->maxx-1, it->second->maxy-1), CV_RGB(0., 0., 50.)); else cvRectangle(imgDest, cvPoint(it->second->minx, it->second->miny), cvPoint(it->second->maxx-1, it->second->maxy-1), CV_RGB(0., 0., 255.)); - + } if (mode&CV_TRACK_RENDER_TO_LOG) { clog << "Track " << it->second->id << endl; From df6f66aeccb9f53cb9f3ba71dab78223c8d3d849 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Thu, 27 Jul 2017 13:00:28 +0200 Subject: [PATCH 02/23] [Issue #792] Removes compilation warnings from visionlib/imgAnalyze --- src/libs/visionlib/imgAnalyze/linesDetection.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/libs/visionlib/imgAnalyze/linesDetection.cpp b/src/libs/visionlib/imgAnalyze/linesDetection.cpp index fc8e28968..3975fc29f 100644 --- a/src/libs/visionlib/imgAnalyze/linesDetection.cpp +++ b/src/libs/visionlib/imgAnalyze/linesDetection.cpp @@ -84,7 +84,7 @@ namespace visionLibrary { cv::findContours(imgTmp2, vecContours, CV_RETR_LIST, CV_CHAIN_APPROX_NONE); /*Run through found coutours*/ - for(int contour=0; contour Date: Thu, 27 Jul 2017 04:14:44 +0200 Subject: [PATCH 03/23] [Issue #792] Removes compilation warnings from rgbdCalibrator --- src/tools/rgbdCalibrator/calibration.cpp | 10 +++++----- src/tools/rgbdCalibrator/viewer.cpp | 6 ++++-- src/tools/rgbdCalibrator/viewer.h | 2 +- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/src/tools/rgbdCalibrator/calibration.cpp b/src/tools/rgbdCalibrator/calibration.cpp index b07f289ec..df510cb80 100644 --- a/src/tools/rgbdCalibrator/calibration.cpp +++ b/src/tools/rgbdCalibrator/calibration.cpp @@ -432,7 +432,7 @@ bool Calibration::addPatternPixel (Eigen::Vector3d pixel, std::vector mDepthVector; - const int MAX_MAPS; + const unsigned int MAX_MAPS; bool handlerDepth; // Extrinsics variables From e494fa0c6bd49480588cb69dadd6c00f4535cc57 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Thu, 27 Jul 2017 10:25:01 +0200 Subject: [PATCH 04/23] [Issue #792] Removes compilation warnings from xmlParser --- src/libs/xmlParser/xmlWriterParser.cpp | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/src/libs/xmlParser/xmlWriterParser.cpp b/src/libs/xmlParser/xmlWriterParser.cpp index 85e3d37ba..6eb264928 100644 --- a/src/libs/xmlParser/xmlWriterParser.cpp +++ b/src/libs/xmlParser/xmlWriterParser.cpp @@ -99,31 +99,31 @@ bool xmlWriterParser::elementExists(std::string key){ xmlpp::Element* xmlWriterParser::lookForKeyAndMakeway(std::string key){ std::vector s; - splitString(key,s); - if (s.size()!=1){ + splitString(key, s); + if (s.size() != 1){ std::string completeKey(s[0]); std::string parentKey(s[0]); - for (int i=0; i!= s.size()-1; i++){ + for (unsigned int i = 0; i != s.size() - 1; i++){ if (!elementExists(completeKey)){ - if (i==0){ + if (i == 0){ //we have to create the node under the parent document. xmlpp::Element* n1= document.get_root_node(); xmlpp::Element* n2= n1->add_child(parentKey); n2->set_child_text(""); } else{ - xmlpp::NodeSet ns1=document.get_root_node()->find(parentKey); + xmlpp::NodeSet ns1 = document.get_root_node()->find(parentKey); xmlpp::Element* n1 = ns1[0]->add_child(s[i]); n1->set_child_text(""); } } - if (i!=s.size()-2) - completeKey+="/"+s[i+1]; - if (i!=0) - parentKey+="/"+s[i]; + if (i != s.size() - 2) + completeKey += "/" + s[i + 1]; + if (i != 0) + parentKey += "/" + s[i]; } - xmlpp::NodeSet ns1=document.get_root_node()->find(parentKey); - xmlpp::Element* n1 = ns1[0]->add_child(s[s.size()-1]); + xmlpp::NodeSet ns1 = document.get_root_node()->find(parentKey); + xmlpp::Element* n1 = ns1[0]->add_child(s[s.size() - 1]); return n1; } else{ From 6bbbd197363d7a66942e0c254dec53979144d8b5 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Thu, 27 Jul 2017 13:01:06 +0200 Subject: [PATCH 05/23] [Issue #792] Removes compilation warnings from rgbdViewer --- src/tools/rgbdViewer/myprogeo.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/tools/rgbdViewer/myprogeo.cpp b/src/tools/rgbdViewer/myprogeo.cpp index 3838df9fe..4eab71b61 100644 --- a/src/tools/rgbdViewer/myprogeo.cpp +++ b/src/tools/rgbdViewer/myprogeo.cpp @@ -62,8 +62,6 @@ void myprogeo::new_camera(){ /* gets the calibration of the camera from a file */ void myprogeo::load_cam(char *fich_in,int cam, int w, int h) { - FILE *entrada; - int i; if (strlen(fich_in) ==0 ){ Eigen::Matrix3d K; K(0,0) = 511; @@ -102,7 +100,6 @@ void myprogeo::load_cam(char *fich_in,int cam, int w, int h) } else{ this->cameras[cam]->readFromFile(std::string(fich_in)); - //this->cameras[cam]->updateKMatrix(); this->cameras[cam]->updateRTMatrix(); } this->cameras[cam]->displayCameraInfo(); From a75f1b4ee3fba60953cb9f99d6fc9c2c19ba25a2 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Thu, 27 Jul 2017 14:10:34 +0200 Subject: [PATCH 06/23] [Issue #792] Removes compilation warnings from Holocar plugin --- src/drivers/gazeboserver/plugins/holo_car/holoCarMotors.cc | 2 +- src/drivers/gazeboserver/plugins/holo_car/holoCarPose3d.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/gazeboserver/plugins/holo_car/holoCarMotors.cc b/src/drivers/gazeboserver/plugins/holo_car/holoCarMotors.cc index 6b0c6c171..1e6258471 100644 --- a/src/drivers/gazeboserver/plugins/holo_car/holoCarMotors.cc +++ b/src/drivers/gazeboserver/plugins/holo_car/holoCarMotors.cc @@ -171,7 +171,7 @@ namespace gazebo std::cerr << e << std::endl; } } - + return NULL; } // Register this plugin with the simulator GZ_REGISTER_MODEL_PLUGIN(Motors) diff --git a/src/drivers/gazeboserver/plugins/holo_car/holoCarPose3d.cc b/src/drivers/gazeboserver/plugins/holo_car/holoCarPose3d.cc index b99015a52..20671d966 100644 --- a/src/drivers/gazeboserver/plugins/holo_car/holoCarPose3d.cc +++ b/src/drivers/gazeboserver/plugins/holo_car/holoCarPose3d.cc @@ -148,7 +148,7 @@ namespace gazebo { std::cerr << e << std::endl; } } - + return NULL; } } From 1bbe0c0a6ca33f19aea1d09a57ff7fc3dc9ea1cd Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Thu, 27 Jul 2017 14:21:50 +0200 Subject: [PATCH 07/23] [Issue #792] Removes compilation warnings from F1 plugin --- src/drivers/gazeboserver/plugins/f1/camera_dump.cc | 3 ++- src/drivers/gazeboserver/plugins/f1/laser.cc | 1 + src/drivers/gazeboserver/plugins/f1/motors.cc | 1 + src/drivers/gazeboserver/plugins/f1/pose3d.cc | 1 + 4 files changed, 5 insertions(+), 1 deletion(-) diff --git a/src/drivers/gazeboserver/plugins/f1/camera_dump.cc b/src/drivers/gazeboserver/plugins/f1/camera_dump.cc index ad3251286..cb5794aaf 100644 --- a/src/drivers/gazeboserver/plugins/f1/camera_dump.cc +++ b/src/drivers/gazeboserver/plugins/f1/camera_dump.cc @@ -302,5 +302,6 @@ void *myMain(void* v) std::cerr << e << std::endl; } } - + + return NULL; } diff --git a/src/drivers/gazeboserver/plugins/f1/laser.cc b/src/drivers/gazeboserver/plugins/f1/laser.cc index 64cd2fea1..4c424696e 100644 --- a/src/drivers/gazeboserver/plugins/f1/laser.cc +++ b/src/drivers/gazeboserver/plugins/f1/laser.cc @@ -172,4 +172,5 @@ void *mainLaser(void* v) } } + return NULL; } diff --git a/src/drivers/gazeboserver/plugins/f1/motors.cc b/src/drivers/gazeboserver/plugins/f1/motors.cc index 4b2cfd412..fe490e6dc 100644 --- a/src/drivers/gazeboserver/plugins/f1/motors.cc +++ b/src/drivers/gazeboserver/plugins/f1/motors.cc @@ -260,6 +260,7 @@ namespace gazebo } } + return NULL; } // Register this plugin with the simulator GZ_REGISTER_MODEL_PLUGIN(Motors) diff --git a/src/drivers/gazeboserver/plugins/f1/pose3d.cc b/src/drivers/gazeboserver/plugins/f1/pose3d.cc index fb78989be..efb253c02 100644 --- a/src/drivers/gazeboserver/plugins/f1/pose3d.cc +++ b/src/drivers/gazeboserver/plugins/f1/pose3d.cc @@ -149,6 +149,7 @@ namespace gazebo { } } + return NULL; } } From 0da468592845ad3e42afef4e896e7d66a1233fd7 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Thu, 27 Jul 2017 14:32:55 +0200 Subject: [PATCH 08/23] [Issue #792] Removes compilation warnings from pioneer plugin --- .../gazeboserver/plugins/pioneer/camera_dump.cc | 5 +++-- src/drivers/gazeboserver/plugins/pioneer/laser.cc | 2 ++ src/drivers/gazeboserver/plugins/pioneer/motors.cc | 1 + src/drivers/gazeboserver/plugins/pioneer/pose3d.cc | 2 ++ .../gazeboserver/plugins/pioneer/pose3dencoders.cc | 13 ++++++++----- 5 files changed, 16 insertions(+), 7 deletions(-) diff --git a/src/drivers/gazeboserver/plugins/pioneer/camera_dump.cc b/src/drivers/gazeboserver/plugins/pioneer/camera_dump.cc index bb9fc5e5d..415a66e59 100644 --- a/src/drivers/gazeboserver/plugins/pioneer/camera_dump.cc +++ b/src/drivers/gazeboserver/plugins/pioneer/camera_dump.cc @@ -147,7 +147,7 @@ class CameraI: virtual public jderobot::Camera { } virtual std::string startCameraStreaming(const Ice::Current&){ - + return ""; // Remove return warning } virtual void stopCameraStreaming(const Ice::Current&) { @@ -302,5 +302,6 @@ void *myMain(void* v) std::cerr << e << std::endl; } } - + + return NULL; } diff --git a/src/drivers/gazeboserver/plugins/pioneer/laser.cc b/src/drivers/gazeboserver/plugins/pioneer/laser.cc index 9c05337bb..efbde08aa 100644 --- a/src/drivers/gazeboserver/plugins/pioneer/laser.cc +++ b/src/drivers/gazeboserver/plugins/pioneer/laser.cc @@ -143,4 +143,6 @@ void *mainLaser(void* v) } } + return NULL; + } diff --git a/src/drivers/gazeboserver/plugins/pioneer/motors.cc b/src/drivers/gazeboserver/plugins/pioneer/motors.cc index 7a9dd617e..f49b67da0 100644 --- a/src/drivers/gazeboserver/plugins/pioneer/motors.cc +++ b/src/drivers/gazeboserver/plugins/pioneer/motors.cc @@ -236,5 +236,6 @@ std::cout << argv[0] << " loaded" << std::endl; } } + return NULL; } } diff --git a/src/drivers/gazeboserver/plugins/pioneer/pose3d.cc b/src/drivers/gazeboserver/plugins/pioneer/pose3d.cc index 61d95b429..38b2d4659 100644 --- a/src/drivers/gazeboserver/plugins/pioneer/pose3d.cc +++ b/src/drivers/gazeboserver/plugins/pioneer/pose3d.cc @@ -149,6 +149,8 @@ namespace gazebo { } } + return NULL; + } } diff --git a/src/drivers/gazeboserver/plugins/pioneer/pose3dencoders.cc b/src/drivers/gazeboserver/plugins/pioneer/pose3dencoders.cc index ff34dbe36..fb957a8f6 100644 --- a/src/drivers/gazeboserver/plugins/pioneer/pose3dencoders.cc +++ b/src/drivers/gazeboserver/plugins/pioneer/pose3dencoders.cc @@ -122,10 +122,10 @@ namespace gazebo { this->cameraRight.encoder.tilt = this->cameraRight.camera_link_tilt->GetRelativePose().rot.GetAsEuler().y * 180.0 / M_PI; //std::cout << this->cameraRight.encoder.tilt << std::endl; - double setPanRight = -50; - double setPanLeft = -50; - double setTiltRight = -10; - double setTiltLeft = -10; + // double setPanRight = -50; + // double setPanLeft = -50; + // double setTiltRight = -10; + // double setTiltLeft = -10; // ----------MOTORS---------- @@ -343,6 +343,7 @@ namespace gazebo { pose->cameraLeft.motor.tiltSpeed = data->tiltSpeed; pthread_mutex_unlock(&pose->mutex); + return 0; // Remove return warning } gazebo::Pose3DEncoders* pose; @@ -411,6 +412,7 @@ namespace gazebo { pose->cameraRight.motor.tiltSpeed = data->tiltSpeed; pthread_mutex_unlock(&pose->mutex); + return 0; // Remove return warning } gazebo::Pose3DEncoders* pose; @@ -489,7 +491,8 @@ namespace gazebo { std::cerr << e << std::endl; } } - + + return NULL; } From 630e5cb7a0c712b1794a626b96bae9e445e155d7 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Fri, 28 Jul 2017 19:42:00 +0200 Subject: [PATCH 09/23] [Issue #792] Removes compilation warnings from openni1Server --- src/drivers/openni1Server/myprogeo.cpp | 4 +- src/drivers/openni1Server/openni1Server.cpp | 52 +++++++++------------ 2 files changed, 24 insertions(+), 32 deletions(-) diff --git a/src/drivers/openni1Server/myprogeo.cpp b/src/drivers/openni1Server/myprogeo.cpp index a02e688b0..28b347c88 100644 --- a/src/drivers/openni1Server/myprogeo.cpp +++ b/src/drivers/openni1Server/myprogeo.cpp @@ -38,7 +38,6 @@ int myprogeo::load_cam_line(FILE *myfile,int cam) char word1[MAX_BUFFER],word2[MAX_BUFFER]; int i=0; char buffer_file[MAX_BUFFER]; - double roll; buffer_file[0]=fgetc(myfile); if (feof(myfile)) return EOF; @@ -150,8 +149,7 @@ void myprogeo::load_cam(char *fich_in,int cam, int w, int h) { this->w=w; this->h=h; - FILE *entrada; - int i; + if (strlen(fich_in) ==0 ) { std::cout << w << ", " << h << std::endl; this->cameras[cam].fdistx=515; diff --git a/src/drivers/openni1Server/openni1Server.cpp b/src/drivers/openni1Server/openni1Server.cpp index 1e667440d..7aaf8178f 100644 --- a/src/drivers/openni1Server/openni1Server.cpp +++ b/src/drivers/openni1Server/openni1Server.cpp @@ -469,11 +469,10 @@ void CalculateJoints(){ g_pTexMap = (XnRGB24Pixel*)malloc(g_nTexMapX * g_nTexMapY * sizeof(XnRGB24Pixel)); SceneMetaData smd; - struct timeval a, b; + struct timeval a; int cycle; // duración del ciclo long totala; long totalpre=0; - long diff; std::cout << "RGB FPS: " << fps << std::endl; cycle=(float)(1/(float)fps)*1000000; @@ -714,8 +713,6 @@ void CalculateJoints(){ } virtual void run(){ - int test; - jderobot::ImageDataPtr reply(new jderobot::ImageData); reply->description = mycameradepth->imageDescription; @@ -727,11 +724,10 @@ void CalculateJoints(){ g_pTexMap = (XnRGB24Pixel*)malloc(g_nTexMapX * g_nTexMapY * sizeof(XnRGB24Pixel)); distances.resize(width*height); - struct timeval a, b; + struct timeval a; int cycle; // duración del ciclo long totala; long totalpre=0; - long diff; //std::cout << "FPS depth: " << fps << std::endl; cycle=(float)(1/(float)fps)*1000000; @@ -754,7 +750,6 @@ void CalculateJoints(){ XnDepthPixel* pDepth = (XnDepthPixel* )pDepthRow; for (XnUInt x = 0; x < sensors[SELCAM].depthMD.XRes(); ++x, ++pDepth) { - test= *pDepth; if ((!segmentation)||(*pLabels!=0)){ distances[(y*sensors[SELCAM].depthMD.XRes() + x)] = *pDepth; @@ -783,7 +778,9 @@ void CalculateJoints(){ } //cvFlip(src, NULL, 1); - if ((mycameradepth->imageDescription->width != sensors[SELCAM].imageMD.XRes()) || (mycameradepth->imageDescription->height != sensors[SELCAM].imageMD.YRes())){ + if ( (static_cast(mycameradepth->imageDescription->width) != sensors[SELCAM].imageMD.XRes()) || + (static_cast(mycameradepth->imageDescription->height) != sensors[SELCAM].imageMD.YRes()) + ) { cvResize(src,dst_resize); memcpy(&(reply->pixelData[0]),(unsigned char *) dst_resize->imageData,dst_resize->width*dst_resize->height * 3); } @@ -942,7 +939,7 @@ void CalculateJoints(){ mypro= new openni1Server::myprogeo(); mypro->load_cam((char*)path.c_str(),0, cWidth, cHeight); - struct timeval a, b; + struct timeval a; int cycle; // duración del ciclo long totala; long totalpre=0; @@ -955,14 +952,15 @@ void CalculateJoints(){ totala=a.tv_sec*1000000+a.tv_usec; pthread_mutex_lock(&mutex); data2->p.clear(); - for( unsigned int i = 0 ; (i < cWidth*cHeight)&&(distances.size()>0); i=i+9) { - distance=(float)distances[i]; - if (distance!=0){ + for( unsigned int i = 0 ; + (i < static_cast(cWidth * cHeight)) && + (distances.size()>0); i=i+9) { + + distance = (float)distances[i]; + if (distance != 0){ //if (((unsigned char)srcRGB->imageData[3*i]!=0) && ((unsigned char)srcRGB->imageData[3*i+1]!=0) && ((unsigned char)srcRGB->imageData[3*i+2]!=0)){ float xp,yp,zp,camx,camy,camz; float ux,uy,uz; - float x,y; - float k; float c1x, c1y, c1z; float fx,fy,fz; float fmod; @@ -1285,7 +1283,7 @@ int main(int argc, char** argv){ width=prop->getPropertyAsIntWithDefault("openni1Server.Width", 640); localDebug=prop->getPropertyAsIntWithDefault("openni1Server.Debug", 0); height=prop->getPropertyAsIntWithDefault("openni1Server.Height",480); - int fps=prop->getPropertyAsIntWithDefault("openni1Server.Fps",30); + //int fps=prop->getPropertyAsIntWithDefault("openni1Server.Fps",30); #ifndef WITH_NITE playerdetection=0; @@ -1390,7 +1388,7 @@ int main(int argc, char** argv){ uint8_t address = libusb_get_device_address (device); int device_id = -1; - for (size_t i = 0; device_id < 0 && i < n_devices; ++i) + for (size_t i = 0; device_id < 0 && i < static_cast(n_devices); ++i) { if (busId == sensors[i].bus && address == sensors[i].address) device_id = i; @@ -1467,14 +1465,10 @@ int main(int argc, char** argv){ } delete[] aModeD; - - - - XnMapOutputMode depth_mode; - depth_mode.nXRes = width; - depth_mode.nYRes = height; - depth_mode.nFPS = 30; - + //XnMapOutputMode depth_mode; + //depth_mode.nXRes = width; + //depth_mode.nYRes = height; + //depth_mode.nFPS = 30; CHECK_RC(rc, "Create Depth"); // now create a image generator over this device @@ -1497,11 +1491,11 @@ int main(int argc, char** argv){ CHECK_RC(rc, "Find user generator"); #endif - XnMapOutputMode rgb_mode; - rgb_mode.nXRes = width; - rgb_mode.nYRes = height; - rgb_mode.nFPS = fps; - sensors[i].image.SetMapOutputMode(aModeD[2]); + // XnMapOutputMode rgb_mode; + // rgb_mode.nXRes = width; + // rgb_mode.nYRes = height; + // rgb_mode.nFPS = fps; + sensors[i].image.SetMapOutputMode(aModeD[2]); sensors[i].depth.GetAlternativeViewPointCap().SetViewPoint(sensors[i].image); From 63b1ba0cd0a776ee7390103c8e9beb570c6a6930 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Fri, 28 Jul 2017 19:45:07 +0200 Subject: [PATCH 10/23] [Issue #792] Removes compilation warnings from F1 plugin --- src/drivers/gazeboserver/plugins/f1/camera_dump.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/gazeboserver/plugins/f1/camera_dump.cc b/src/drivers/gazeboserver/plugins/f1/camera_dump.cc index cb5794aaf..3822de47b 100644 --- a/src/drivers/gazeboserver/plugins/f1/camera_dump.cc +++ b/src/drivers/gazeboserver/plugins/f1/camera_dump.cc @@ -146,7 +146,7 @@ class CameraI: virtual public jderobot::Camera { } virtual std::string startCameraStreaming(const Ice::Current&){ - + return ""; // Remove return warning } virtual void stopCameraStreaming(const Ice::Current&) { From aac41ef402224c99385a2aaf6cf1d6584fb8492d Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Fri, 28 Jul 2017 19:47:11 +0200 Subject: [PATCH 11/23] [Issue #792] Removes compilation warnings from car plugin --- src/drivers/gazeboserver/plugins/car/carMotors.cc | 2 +- src/drivers/gazeboserver/plugins/car/pose3d.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/gazeboserver/plugins/car/carMotors.cc b/src/drivers/gazeboserver/plugins/car/carMotors.cc index 8fa1f6b89..d4e6879ad 100644 --- a/src/drivers/gazeboserver/plugins/car/carMotors.cc +++ b/src/drivers/gazeboserver/plugins/car/carMotors.cc @@ -258,7 +258,7 @@ namespace gazebo std::cerr << e << std::endl; } } - + return NULL; } // Register this plugin with the simulator GZ_REGISTER_MODEL_PLUGIN(Motors) diff --git a/src/drivers/gazeboserver/plugins/car/pose3d.cc b/src/drivers/gazeboserver/plugins/car/pose3d.cc index 4c57668a1..bb73baed5 100644 --- a/src/drivers/gazeboserver/plugins/car/pose3d.cc +++ b/src/drivers/gazeboserver/plugins/car/pose3d.cc @@ -148,7 +148,7 @@ namespace gazebo { std::cerr << e << std::endl; } } - + return NULL; } } From 9c1621a07703d79014105aa09ff497d10d7b15ae Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Fri, 28 Jul 2017 19:49:39 +0200 Subject: [PATCH 12/23] [Issue #792] Removes compilation warnings from pclRGBDServer driver --- src/drivers/pclRGBDServer/cameraRGB.h | 2 +- src/drivers/pclRGBDServer/cameradepth.h | 2 +- src/drivers/pclRGBDServer/pointcloud.h | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/drivers/pclRGBDServer/cameraRGB.h b/src/drivers/pclRGBDServer/cameraRGB.h index 8534b990c..e13f7a713 100644 --- a/src/drivers/pclRGBDServer/cameraRGB.h +++ b/src/drivers/pclRGBDServer/cameraRGB.h @@ -55,7 +55,7 @@ namespace kinect{ } virtual std::string startCameraStreaming(const Ice::Current&){ - + return ""; } virtual void stopCameraStreaming(const Ice::Current&) { diff --git a/src/drivers/pclRGBDServer/cameradepth.h b/src/drivers/pclRGBDServer/cameradepth.h index cf53a3ffa..7e95e254a 100644 --- a/src/drivers/pclRGBDServer/cameradepth.h +++ b/src/drivers/pclRGBDServer/cameradepth.h @@ -62,7 +62,7 @@ namespace kinect{ } virtual std::string startCameraStreaming(const Ice::Current&){ - + return ""; } virtual void stopCameraStreaming(const Ice::Current&) { diff --git a/src/drivers/pclRGBDServer/pointcloud.h b/src/drivers/pclRGBDServer/pointcloud.h index a367efe4c..f9c628995 100644 --- a/src/drivers/pclRGBDServer/pointcloud.h +++ b/src/drivers/pclRGBDServer/pointcloud.h @@ -21,8 +21,8 @@ namespace kinect{ if(cloud.points.size()){ KData->p.resize(cloud.points.size()); - int index = 0; - for(int i = 0; i < cloud.points.size(); i++){ + unsigned int index = 0; + for(unsigned int i = 0; i < cloud.points.size(); i++){ KData->p[index].x = cloud.points[i].x; KData->p[index].y = cloud.points[i].y; KData->p[index].z = cloud.points[i].z; From 9194229965335b1489832611b05595b3d07e3566 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Fri, 28 Jul 2017 20:53:37 +0200 Subject: [PATCH 13/23] [Issue #792] Removes compilation warnings from kobuki driver --- src/drivers/kobuki_driver/actuators/motors.cpp | 6 ++++-- src/drivers/kobuki_driver/sensors/pose3d.cpp | 2 +- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/src/drivers/kobuki_driver/actuators/motors.cpp b/src/drivers/kobuki_driver/actuators/motors.cpp index d3aab25d6..29a9d88ef 100644 --- a/src/drivers/kobuki_driver/actuators/motors.cpp +++ b/src/drivers/kobuki_driver/actuators/motors.cpp @@ -12,12 +12,12 @@ Motors::~Motors() float Motors::getV(const Ice::Current&) { - + return 0.; } float Motors::getW(const Ice::Current&) { - + return 0.; } float Motors::getL(const Ice::Current&) @@ -28,11 +28,13 @@ float Motors::getL(const Ice::Current&) Ice::Int Motors::setV(Ice::Float v, const Ice::Current&) { kobuki_manager->setV(v); + return 0; } Ice::Int Motors::setW(Ice::Float _w, const Ice::Current&) { kobuki_manager->setW(_w); + return 0; } Ice::Int Motors::setL(Ice::Float l, const Ice::Current&) diff --git a/src/drivers/kobuki_driver/sensors/pose3d.cpp b/src/drivers/kobuki_driver/sensors/pose3d.cpp index 3615adebc..ce56f5a27 100644 --- a/src/drivers/kobuki_driver/sensors/pose3d.cpp +++ b/src/drivers/kobuki_driver/sensors/pose3d.cpp @@ -8,7 +8,7 @@ Pose3D::Pose3D(KobukiManager *kobuki) int Pose3D::setPose3DData(const jderobot::Pose3DDataPtr& pose3dData, const Ice::Current&) { - + return 0; } From 6d1fd021f40a4dadd46680aa325df365abda167e Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Sat, 29 Jul 2017 03:49:35 +0200 Subject: [PATCH 14/23] [Issue #792] Removes compilation warnings from kobuki driver --- src/drivers/kobuki_driver/kobukimanager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/kobuki_driver/kobukimanager.cpp b/src/drivers/kobuki_driver/kobukimanager.cpp index 3c7f7ba5e..7629f7091 100644 --- a/src/drivers/kobuki_driver/kobukimanager.cpp +++ b/src/drivers/kobuki_driver/kobukimanager.cpp @@ -96,7 +96,7 @@ void KobukiManager::update() std::cout << "ir: " << ir.docking.size()<< std::endl; - for(int i =0; i < ir.docking.size(); i++){ + for(unsigned int i =0; i < ir.docking.size(); i++){ std::cout << (unsigned char)ir.docking[i] << ", "; } From 60d94565bf8d4732a271609f806670af8144cd73 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Fri, 28 Jul 2017 21:10:59 +0200 Subject: [PATCH 15/23] [Issue #792] Removes compilation warnings from driver laser_server --- src/drivers/laser_server/hokuyo/hokuyomanager.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/drivers/laser_server/hokuyo/hokuyomanager.cpp b/src/drivers/laser_server/hokuyo/hokuyomanager.cpp index 0b78c65b0..65330b5c9 100644 --- a/src/drivers/laser_server/hokuyo/hokuyomanager.cpp +++ b/src/drivers/laser_server/hokuyo/hokuyomanager.cpp @@ -14,7 +14,7 @@ namespace hokuyo{ this->timeout = timeout; this->faceup = faceup; std::cout << "open: " << port << std::endl; - hokuyo:LaserConfig config; + LaserConfig config; laser_.getConfig(config); std::cout<< "min_range: " << config.min_range << std::endl; std::cout<< "max_range: " << config.max_range << std::endl; @@ -65,9 +65,9 @@ std::cout<< "range_res: " << config.range_res << std::endl; data->maxAngle = this->max_ang; hokuyo::LaserScan scan; - int res; - mutex.lock(); - res = laser_.pollScan(scan,this->min_ang,this->max_ang,this->clustering,this->timeout); + + mutex.lock(); + //res = laser_.pollScan(scan,this->min_ang,this->max_ang,this->clustering,this->timeout); mutex.unlock(); From b1e8c6c05647f86995e79acc51ac4a11e5070a3e Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Sat, 29 Jul 2017 00:43:26 +0200 Subject: [PATCH 16/23] [Issue #792] Removes compilation warnings from tool navigatorCamera --- src/tools/navigatorCamera/gui.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/tools/navigatorCamera/gui.cpp b/src/tools/navigatorCamera/gui.cpp index b8eda5e05..f173c9b2e 100644 --- a/src/tools/navigatorCamera/gui.cpp +++ b/src/tools/navigatorCamera/gui.cpp @@ -213,6 +213,8 @@ namespace navigatorCamera { //api->setYawValue(yaw_normalized); //api->setPitchValue(pitch_normalized); //pthread_mutex_unlock(&api->controlGui);*/ + + return true; } void Gui::teleoperateTrl() { @@ -294,6 +296,8 @@ namespace navigatorCamera { //api->setYawValue(yaw_normalized); //api->setPitchValue(pitch_normalized); //pthread_mutex_unlock(&api->controlGui); + + return true; } void Gui::teleoperateRtt() { From 22c06f571b967302c73c063d346a7af64556c05c Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Sat, 29 Jul 2017 00:46:15 +0200 Subject: [PATCH 17/23] [Issue #792] Removes compilation warnings from tool rgbdCalibrator --- src/tools/rgbdCalibrator/geoUtils.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/src/tools/rgbdCalibrator/geoUtils.cpp b/src/tools/rgbdCalibrator/geoUtils.cpp index 94d450e6b..a23076552 100644 --- a/src/tools/rgbdCalibrator/geoUtils.cpp +++ b/src/tools/rgbdCalibrator/geoUtils.cpp @@ -36,9 +36,13 @@ namespace rgbdCalibrator bool GeoUtils::Line3D::isPointInLine (HPoint3D p) { - return ((p.X - point.X)/vector.X) == - ((p.Y - point.Y)/vector.Y) == - ((p.Z - point.Z)/vector.Z); + return ( + ((p.X - point.X)/vector.X) == + ( + ((p.Y - point.Y)/vector.Y) == + ((p.Z - point.Z)/vector.Z) + ) + ); } HPoint3D GeoUtils::Line3D::getPointByZ (float z) From 51fa1332f26bbebe1de4794bbd6e62aa7b56af8e Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Sat, 29 Jul 2017 00:47:48 +0200 Subject: [PATCH 18/23] [Issue #792] Removes compilation warnings from tool giraffeClient --- src/tools/giraffeClient/cameraconf.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/tools/giraffeClient/cameraconf.cpp b/src/tools/giraffeClient/cameraconf.cpp index 2e68f9833..80d6ebab0 100644 --- a/src/tools/giraffeClient/cameraconf.cpp +++ b/src/tools/giraffeClient/cameraconf.cpp @@ -269,7 +269,7 @@ namespace giraffeClient { void CameraConf::getAngles(float x, float y, float z, float &pan, float &tilt) { - float rx, ry, rz; + float rx, /*ry,*/ rz; /*Set pan with X-Y*/ if(x == 0.0) @@ -279,7 +279,7 @@ namespace giraffeClient { /*Calc relative position of point from tilt motor*/ rx = x - CAM_RIGHT_X*1000; - ry = y - CAM_RIGHT_Y*1000; + //ry = y - CAM_RIGHT_Y*1000; rz = z - CAM_RIGHT_Z*1000 - NECK_LENGTH*1000; /*Set tilt with X-Z*/ From e6dfc25e84d5480e390fee450df829d57fc1ceed Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Sat, 29 Jul 2017 00:52:23 +0200 Subject: [PATCH 19/23] [Issue #792] Removes compilation warnings from tool uav viewer --- src/tools/uav_viewer/gui/mainwindow.cpp | 34 ++++++++++++------------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/src/tools/uav_viewer/gui/mainwindow.cpp b/src/tools/uav_viewer/gui/mainwindow.cpp index 3b3a38256..1d3041b43 100644 --- a/src/tools/uav_viewer/gui/mainwindow.cpp +++ b/src/tools/uav_viewer/gui/mainwindow.cpp @@ -94,7 +94,7 @@ void MainWindow::updateGUI_recieved() QImage::Format_RGB888); - int camera=0; + //int camera=0; //640x360 ArDrone2 //320x240 ArDrone1 frontal //174x144 ArDrone 1 ventral @@ -134,7 +134,7 @@ void MainWindow::updateGUI_recieved() ui->imageLLabel->setPixmap(QPixmap::fromImage(imageQt)); jderobot::NavdataDataPtr navdata=this->sensors->getNavdata(); - int batteryPer=navdata->batteryPercent; + //int batteryPer=navdata->batteryPercent; //ui->battery->setValue(batteryPer); this->setDroneStatus(navdata->state); @@ -167,34 +167,34 @@ void MainWindow::printNavdata(jderobot::NavdataDataPtr data) std::cout << "WindCompAngle:\t"<< data->windCompAngle << "\n" << std::endl; std::cout << "\t--Tag Detection--" << std::endl; std::cout << "\tTagCount: "<< data->tagsCount << std::endl; - if(data->tagsCount!=0){ - for(int i=0;itagsType.size();i++) + if(data->tagsCount != 0){ + for(unsigned int i = 0; i < data->tagsType.size(); i++) { - std::cout << "\t"<tagsType[i] << std::endl; + std::cout << "\t"<< data->tagsType[i] << std::endl; } - for(int i=0;itagsXc.size();i++) + for(unsigned int i = 0; i < data->tagsXc.size(); i++) { - std::cout << "\t"<tagsXc[i] << std::endl; + std::cout << "\t"<< data->tagsXc[i] << std::endl; } - for(int i=0;itagsYc.size();i++) + for(unsigned int i = 0; i < data->tagsYc.size(); i++) { - std::cout << "\t"<tagsYc[i] << std::endl; + std::cout << "\t"<< data->tagsYc[i] << std::endl; } - for(int i=0;itagsWidth.size();i++) + for(unsigned int i = 0; i < data->tagsWidth.size(); i++) { - std::cout << "\t"<tagsWidth[i] << std::endl; + std::cout << "\t"<< data->tagsWidth[i] << std::endl; } - for(int i=0;itagsHeight.size();i++) + for(unsigned int i = 0; i < data->tagsHeight.size(); i++) { - std::cout << "\t"<tagsHeight[i] << std::endl; + std::cout << "\t"<< data->tagsHeight[i] << std::endl; } - for(int i=0;itagsOrientation.size();i++) + for(unsigned int i = 0; i < data->tagsOrientation.size(); i++) { - std::cout << "\t"<tagsOrientation[i] << std::endl; + std::cout << "\t"<< data->tagsOrientation[i] << std::endl; } - for(int i=0;itagsDistance.size();i++) + for(unsigned int i = 0; i < data->tagsDistance.size(); i++) { - std::cout << "\t"<tagsDistance[i] << std::endl; + std::cout << "\t"<< data->tagsDistance[i] << std::endl; } } std::cout << "---------------------------------------" << std::endl; From 81d2c5672387d4e982945e7cfb55fccbb87b936f Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Sat, 29 Jul 2017 03:44:29 +0200 Subject: [PATCH 20/23] [Issue #792] Removes compilation warnings from tool kobuki viewer --- src/tools/kobukiViewer/gui/gui.cpp | 2 +- src/tools/kobukiViewer/gui/widget/laserwidget.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/tools/kobukiViewer/gui/gui.cpp b/src/tools/kobukiViewer/gui/gui.cpp index 36d522c30..a1cd4ab4f 100644 --- a/src/tools/kobukiViewer/gui/gui.cpp +++ b/src/tools/kobukiViewer/gui/gui.cpp @@ -26,7 +26,7 @@ GUI::GUI(Robot* robot, Ice::CommunicatorPtr ic) laserWidget =new LaserWidget(); - int indiceFilaGui = 0; + //int indiceFilaGui = 0; layoutControl->addWidget(canvasVW, 0, 0); layoutButtons->addWidget(InfoCurrentV, 0); diff --git a/src/tools/kobukiViewer/gui/widget/laserwidget.cpp b/src/tools/kobukiViewer/gui/widget/laserwidget.cpp index 3567d4183..f8a711b49 100644 --- a/src/tools/kobukiViewer/gui/widget/laserwidget.cpp +++ b/src/tools/kobukiViewer/gui/widget/laserwidget.cpp @@ -58,10 +58,10 @@ void LaserWidget::paintEvent(QPaintEvent *) ang = this->laserData.minAngle; - for (int i = 0; i < this->laserData.values.size(); i++) { + for (unsigned int i = 0; i < this->laserData.values.size(); i++) { - ang = this->laserData.minAngle + i*step; + ang = this->laserData.minAngle + i * step; x1 = cx + (this->laserData.values[i] / d) * cos(ang); y1 = cy - ((this->laserData.values[i] / d) * sin(ang)); From abac192ac96a4e38094d2a1f0d53f2492e392a4d Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Sat, 29 Jul 2017 03:49:57 +0200 Subject: [PATCH 21/23] [Issue #792] Removes compilation warnings from opencvdemo samples --- src/samples/opencvdemo/viewer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/samples/opencvdemo/viewer.cpp b/src/samples/opencvdemo/viewer.cpp index 7648fcf6d..747de1d5b 100644 --- a/src/samples/opencvdemo/viewer.cpp +++ b/src/samples/opencvdemo/viewer.cpp @@ -1100,7 +1100,7 @@ void Viewer::harris( Mat image ) img_rgb8.step);*/ Size img_mat_size=img_mat.size(); - Size imagesize = image.size(); + //Size imagesize = image.size(); //std::cout << img_mat_size.height << std::endl; //std::cout << img_mat_size.width << std::endl; From 2be59b843ced0ccc463729c392ce1e7fa16f618a Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Sat, 29 Jul 2017 04:16:08 +0200 Subject: [PATCH 22/23] [Issue #792] Removes compilation warnings from libs visionlib/imgAnalyze --- src/libs/visionlib/imgAnalyze/linesDetection.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/libs/visionlib/imgAnalyze/linesDetection.cpp b/src/libs/visionlib/imgAnalyze/linesDetection.cpp index 3975fc29f..a62f3910e 100644 --- a/src/libs/visionlib/imgAnalyze/linesDetection.cpp +++ b/src/libs/visionlib/imgAnalyze/linesDetection.cpp @@ -93,7 +93,7 @@ namespace visionLibrary { i = 0; first = true; - while ((i < (vecContours[contour].size() - (i_jump - 1)))) { + while ((static_cast(i) < (vecContours[contour].size() - (i_jump - 1)))) { counter++; From 0e6a18bb99122c4737dff59c53a7de2dc2140004 Mon Sep 17 00:00:00 2001 From: Luis Roberto Morales Iglesias Date: Tue, 1 Aug 2017 16:05:40 +0200 Subject: [PATCH 23/23] [Issue #792] Removes compilation warnings from tool visualStates --- src/tools/visualStates/generate.cpp | 38 +++++++++++------------ src/tools/visualStates/guisubautomata.cpp | 3 +- 2 files changed, 20 insertions(+), 21 deletions(-) diff --git a/src/tools/visualStates/generate.cpp b/src/tools/visualStates/generate.cpp index eb3f1f0e2..b68bbb80e 100644 --- a/src/tools/visualStates/generate.cpp +++ b/src/tools/visualStates/generate.cpp @@ -400,7 +400,7 @@ void Generate::generateSubautomatas () { transListIterator != transList.end(); transListIterator++ ) { if (transListIterator->getIdOrigin() == idNode) { int idDestiny = transListIterator->getIdDestiny(); - int idOrigin = transListIterator->getIdOrigin(); + //int idOrigin = transListIterator->getIdOrigin(); if (transListIterator->getType().compare("condition") == 0) { this->fs << "\t\t\t\tif (" << transListIterator->getCodeTrans().c_str() << ") {" << std::endl; this->fs << "\t\t\t\t\tsub_" << id << " = " << subListIterator->getNodeName(idDestiny) << ";" << std::endl; @@ -831,25 +831,25 @@ void Generate::generateVariables_py(){ } int Generate::getIdNodeFather(int subId, int subFatherId){ - if (subFatherId == 0){ - return 0; - } - for (std::list::iterator subListIterator = this->subautomataList.begin(); - subListIterator != this->subautomataList.end(); subListIterator++ ){ - - if (subListIterator->getId() == subFatherId){ - std::list nodeList = subListIterator->getNodeList(); - std::list::iterator nodeListIterator = nodeList.begin(); - while(nodeListIterator != nodeList.end()){ - if (nodeListIterator->getIdSubautomataSon() == subId){ - return nodeListIterator->getId(); - } - nodeListIterator++; - } - return 0; - } - } + if (subFatherId != 0){ + for (std::list::iterator subListIterator = this->subautomataList.begin(); + subListIterator != this->subautomataList.end(); subListIterator++ ){ + + if (subListIterator->getId() == subFatherId){ + std::list nodeList = subListIterator->getNodeList(); + std::list::iterator nodeListIterator = nodeList.begin(); + while(nodeListIterator != nodeList.end()){ + if (nodeListIterator->getIdSubautomataSon() == subId){ + return nodeListIterator->getId(); + } + nodeListIterator++; + } + return 0; + } + } + } + return 0; } void Generate::generateCreateGuiSubautomataList_py(){ diff --git a/src/tools/visualStates/guisubautomata.cpp b/src/tools/visualStates/guisubautomata.cpp index 687da3dd9..6855b11ab 100644 --- a/src/tools/visualStates/guisubautomata.cpp +++ b/src/tools/visualStates/guisubautomata.cpp @@ -545,7 +545,6 @@ int GuiSubautomata::getIdSubautomataSon ( const Glib::RefPtr& i while ( (!nodeListIterator->hasThisItem(item)) && (nodeListIterator != this->nodeList.end()) ){ - int id = nodeListIterator->getId(); nodeListIterator++; } @@ -871,4 +870,4 @@ void GuiSubautomata::renameGuiTransition ( Glib::RefPtr item ) RenameDialogTransition* rdialog = new RenameDialogTransition(&*nodeTransIterator); rdialog->init(); } -} \ No newline at end of file +}