[Jderobot-admin] jderobot-r924 - in trunk/src: components/calibratorKinect components/kinectViewer libs/jderobotice
frivas en jderobot.org
frivas en jderobot.org
Vie Mayo 31 17:57:29 CEST 2013
Author: frivas
Date: 2013-05-31 17:56:29 +0200 (Fri, 31 May 2013)
New Revision: 924
Modified:
trunk/src/components/calibratorKinect/calibratorKinect.cpp
trunk/src/components/kinectViewer/kinectViewer.cpp
trunk/src/libs/jderobotice/cameraClient.cpp
trunk/src/libs/jderobotice/cameraClient.h
trunk/src/libs/jderobotice/pointcloudClient.cpp
trunk/src/libs/jderobotice/pointcloudClient.h
Log:
modificado para a?\195?\177adir nivel de debug
Modified: trunk/src/components/calibratorKinect/calibratorKinect.cpp
===================================================================
--- trunk/src/components/calibratorKinect/calibratorKinect.cpp 2013-05-30 14:48:41 UTC (rev 923)
+++ trunk/src/components/calibratorKinect/calibratorKinect.cpp 2013-05-31 15:56:29 UTC (rev 924)
@@ -59,9 +59,9 @@
std::ostringstream sTemp;
std::ostringstream sTemp2;
sTemp << "CalibratorKinect.CameraRGB." << i << ".";
- sources[i].RGB=new jderobot::cameraClient(ic, sTemp.str());
+ sources[i].RGB=new jderobot::cameraClient(ic, sTemp.str(),false);
sTemp2 << "CalibratorKinect.CameraDEPTH." << i << ".";
- sources[i].DEPTH=new jderobot::cameraClient(ic, sTemp2.str());
+ sources[i].DEPTH=new jderobot::cameraClient(ic, sTemp2.str(),false);
if (sources[i].RGB==NULL)
Modified: trunk/src/components/kinectViewer/kinectViewer.cpp
===================================================================
--- trunk/src/components/kinectViewer/kinectViewer.cpp 2013-05-30 14:48:41 UTC (rev 923)
+++ trunk/src/components/kinectViewer/kinectViewer.cpp 2013-05-31 15:56:29 UTC (rev 924)
@@ -140,7 +140,7 @@
return 1;
}
if (prop->getPropertyAsIntWithDefault("kinectViewer.CameraRGBActive",0)){
- camRGB = new jderobot::cameraClient(ic,"kinectViewer.CameraRGB.");
+ camRGB = new jderobot::cameraClient(ic,"kinectViewer.CameraRGB.",false);
if (camRGB != NULL){
rgbCamSelected=true;
camRGB->start();
@@ -149,7 +149,7 @@
}
if (prop->getPropertyAsIntWithDefault("kinectViewer.CameraDEPTHActive",0)){
- camDEPTH = new jderobot::cameraClient(ic,"kinectViewer.CameraDEPTH.");
+ camDEPTH = new jderobot::cameraClient(ic,"kinectViewer.CameraDEPTH.",false);
if (camDEPTH != NULL){
depthCamSelected=true;
camDEPTH->start();
@@ -159,7 +159,7 @@
if (prop->getPropertyAsIntWithDefault("kinectViewer.pointCloudActive",0)){
- pcClient = new jderobot::pointcloudClient(ic,"kinectViewer.pointCloud.");
+ pcClient = new jderobot::pointcloudClient(ic,"kinectViewer.pointCloud.",false);
if (pcClient!= NULL){
pcClient->start();
pointCloudSelected=true;
Modified: trunk/src/libs/jderobotice/cameraClient.cpp
===================================================================
--- trunk/src/libs/jderobotice/cameraClient.cpp 2013-05-30 14:48:41 UTC (rev 923)
+++ trunk/src/libs/jderobotice/cameraClient.cpp 2013-05-31 15:56:29 UTC (rev 924)
@@ -24,9 +24,10 @@
namespace jderobot {
-cameraClient::cameraClient(Ice::CommunicatorPtr ic, std::string prefix) {
+cameraClient::cameraClient(Ice::CommunicatorPtr ic, std::string prefix, bool debug) {
// TODO Auto-generated constructor stubcameraClient* client = new cameraClient;
this->prefix=prefix;
+ this->debug=debug;
Ice::PropertiesPtr prop;
prop = ic->getProperties();
Ice::ObjectPrx baseCamera;
@@ -84,7 +85,8 @@
if (totalpre !=0){
if ((totalpost - totalpre) > this->cycle ){
- std::cout<<"--------" << prefix << " adquisition timeout-" << std::endl;
+ if (this->debug)
+ std::cout<<"--------" << prefix << " adquisition timeout-" << std::endl;
}
else{
usleep(this->cycle - (totalpost - totalpre));
Modified: trunk/src/libs/jderobotice/cameraClient.h
===================================================================
--- trunk/src/libs/jderobotice/cameraClient.h 2013-05-30 14:48:41 UTC (rev 923)
+++ trunk/src/libs/jderobotice/cameraClient.h 2013-05-31 15:56:29 UTC (rev 924)
@@ -36,7 +36,7 @@
class cameraClient: public IceUtil::Thread {
public:
- cameraClient(Ice::CommunicatorPtr ic, std::string prefix);
+ cameraClient(Ice::CommunicatorPtr ic, std::string prefix, bool debug);
virtual ~cameraClient();
virtual void run();
@@ -49,6 +49,7 @@
//int type; //0 color 1 depth
IceUtil::Mutex controlMutex;
std::string prefix;
+ bool debug;
};
Modified: trunk/src/libs/jderobotice/pointcloudClient.cpp
===================================================================
--- trunk/src/libs/jderobotice/pointcloudClient.cpp 2013-05-30 14:48:41 UTC (rev 923)
+++ trunk/src/libs/jderobotice/pointcloudClient.cpp 2013-05-31 15:56:29 UTC (rev 924)
@@ -22,10 +22,10 @@
namespace jderobot {
-pointcloudClient::pointcloudClient(Ice::CommunicatorPtr ic, std::string prefix) {
+pointcloudClient::pointcloudClient(Ice::CommunicatorPtr ic, std::string prefix, bool debug) {
// TODO Auto-generated constructor stub
this->prefix=prefix;
-
+ this->debug= debug;
Ice::PropertiesPtr prop;
prop = ic->getProperties();
@@ -74,7 +74,8 @@
this->controlMutex.unlock();
if (totalpre !=0){
if ((totalpost - totalpre) > this->cycle ){
- std::cout<< prefix << ": pointCloud adquisition timeout-" << std::endl;
+ if (this->debug)
+ std::cout<< prefix << ": pointCloud adquisition timeout-" << std::endl;
}
else{
usleep(this->cycle - (totalpost - totalpre));
Modified: trunk/src/libs/jderobotice/pointcloudClient.h
===================================================================
--- trunk/src/libs/jderobotice/pointcloudClient.h 2013-05-30 14:48:41 UTC (rev 923)
+++ trunk/src/libs/jderobotice/pointcloudClient.h 2013-05-31 15:56:29 UTC (rev 924)
@@ -35,7 +35,7 @@
class pointcloudClient: public IceUtil::Thread {
public:
- pointcloudClient(Ice::CommunicatorPtr ic, std::string prefix);
+ pointcloudClient(Ice::CommunicatorPtr ic, std::string prefix, bool debug);
virtual ~pointcloudClient();
virtual void run();
@@ -48,6 +48,7 @@
jderobot::pointCloudPrx prx;
long long int cycle;
IceUtil::Mutex controlMutex;
+ bool debug;
};
More information about the Jderobot-admin
mailing list