Skip to content
This repository was archived by the owner on Feb 21, 2021. It is now read-only.
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
a9b5e50
[Issue #792] Removes compilation warnings from visionlib/cvblob
lr-morales Jul 27, 2017
df6f66a
[Issue #792] Removes compilation warnings from visionlib/imgAnalyze
lr-morales Jul 27, 2017
1ec8f3d
[Issue #792] Removes compilation warnings from rgbdCalibrator
lr-morales Jul 27, 2017
e494fa0
[Issue #792] Removes compilation warnings from xmlParser
lr-morales Jul 27, 2017
6bbbd19
[Issue #792] Removes compilation warnings from rgbdViewer
lr-morales Jul 27, 2017
a75f1b4
[Issue #792] Removes compilation warnings from Holocar plugin
lr-morales Jul 27, 2017
1bbe0c0
[Issue #792] Removes compilation warnings from F1 plugin
lr-morales Jul 27, 2017
0da4685
[Issue #792] Removes compilation warnings from pioneer plugin
lr-morales Jul 27, 2017
630e5cb
[Issue #792] Removes compilation warnings from openni1Server
lr-morales Jul 28, 2017
63b1ba0
[Issue #792] Removes compilation warnings from F1 plugin
lr-morales Jul 28, 2017
aac41ef
[Issue #792] Removes compilation warnings from car plugin
lr-morales Jul 28, 2017
9c1621a
[Issue #792] Removes compilation warnings from pclRGBDServer driver
lr-morales Jul 28, 2017
9194229
[Issue #792] Removes compilation warnings from kobuki driver
lr-morales Jul 28, 2017
6d1fd02
[Issue #792] Removes compilation warnings from kobuki driver
lr-morales Jul 29, 2017
60d9456
[Issue #792] Removes compilation warnings from driver laser_server
lr-morales Jul 28, 2017
b1e8c6c
[Issue #792] Removes compilation warnings from tool navigatorCamera
lr-morales Jul 28, 2017
22c06f5
[Issue #792] Removes compilation warnings from tool rgbdCalibrator
lr-morales Jul 28, 2017
51fa133
[Issue #792] Removes compilation warnings from tool giraffeClient
lr-morales Jul 28, 2017
e6dfc25
[Issue #792] Removes compilation warnings from tool uav viewer
lr-morales Jul 28, 2017
81d2c56
[Issue #792] Removes compilation warnings from tool kobuki viewer
lr-morales Jul 29, 2017
abac192
[Issue #792] Removes compilation warnings from opencvdemo samples
lr-morales Jul 29, 2017
2be59b8
[Issue #792] Removes compilation warnings from libs visionlib/imgAnalyze
lr-morales Jul 29, 2017
0e6a18b
[Issue #792] Removes compilation warnings from tool visualStates
lr-morales Aug 1, 2017
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/drivers/gazeboserver/plugins/car/carMotors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -258,7 +258,7 @@ namespace gazebo
std::cerr << e << std::endl;
}
}

return NULL;
}
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(Motors)
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/gazeboserver/plugins/car/pose3d.cc
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ namespace gazebo {
std::cerr << e << std::endl;
}
}

return NULL;
}

}
5 changes: 3 additions & 2 deletions src/drivers/gazeboserver/plugins/f1/camera_dump.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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&) {
Expand Down Expand Up @@ -302,5 +302,6 @@ void *myMain(void* v)
std::cerr << e << std::endl;
}
}


return NULL;
}
1 change: 1 addition & 0 deletions src/drivers/gazeboserver/plugins/f1/laser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -172,4 +172,5 @@ void *mainLaser(void* v)
}
}

return NULL;
}
1 change: 1 addition & 0 deletions src/drivers/gazeboserver/plugins/f1/motors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -260,6 +260,7 @@ namespace gazebo
}
}

return NULL;
}
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(Motors)
Expand Down
1 change: 1 addition & 0 deletions src/drivers/gazeboserver/plugins/f1/pose3d.cc
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,7 @@ namespace gazebo {
}
}

return NULL;
}

}
2 changes: 1 addition & 1 deletion src/drivers/gazeboserver/plugins/holo_car/holoCarMotors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ namespace gazebo
std::cerr << e << std::endl;
}
}

return NULL;
}
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(Motors)
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/gazeboserver/plugins/holo_car/holoCarPose3d.cc
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ namespace gazebo {
std::cerr << e << std::endl;
}
}

return NULL;
}

}
5 changes: 3 additions & 2 deletions src/drivers/gazeboserver/plugins/pioneer/camera_dump.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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&) {
Expand Down Expand Up @@ -302,5 +302,6 @@ void *myMain(void* v)
std::cerr << e << std::endl;
}
}


return NULL;
}
2 changes: 2 additions & 0 deletions src/drivers/gazeboserver/plugins/pioneer/laser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -143,4 +143,6 @@ void *mainLaser(void* v)
}
}

return NULL;

}
1 change: 1 addition & 0 deletions src/drivers/gazeboserver/plugins/pioneer/motors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -236,5 +236,6 @@ std::cout << argv[0] << " loaded" << std::endl;
}
}

return NULL;
}
}
2 changes: 2 additions & 0 deletions src/drivers/gazeboserver/plugins/pioneer/pose3d.cc
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,8 @@ namespace gazebo {
}
}

return NULL;

}

}
13 changes: 8 additions & 5 deletions src/drivers/gazeboserver/plugins/pioneer/pose3dencoders.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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----------


Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -489,7 +491,8 @@ namespace gazebo {
std::cerr << e << std::endl;
}
}


return NULL;
}


Expand Down
6 changes: 4 additions & 2 deletions src/drivers/kobuki_driver/actuators/motors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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&)
Expand All @@ -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&)
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/kobuki_driver/kobukimanager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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] << ", ";
}

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/kobuki_driver/sensors/pose3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ Pose3D::Pose3D(KobukiManager *kobuki)
int Pose3D::setPose3DData(const jderobot::Pose3DDataPtr& pose3dData,
const Ice::Current&)
{

return 0;
}


Expand Down
8 changes: 4 additions & 4 deletions src/drivers/laser_server/hokuyo/hokuyomanager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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();

Expand Down
4 changes: 1 addition & 3 deletions src/drivers/openni1Server/myprogeo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
52 changes: 23 additions & 29 deletions src/drivers/openni1Server/openni1Server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -714,8 +713,6 @@ void CalculateJoints(){
}

virtual void run(){
int test;


jderobot::ImageDataPtr reply(new jderobot::ImageData);
reply->description = mycameradepth->imageDescription;
Expand All @@ -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;
Expand All @@ -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;
Expand Down Expand Up @@ -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<unsigned int>(mycameradepth->imageDescription->width) != sensors[SELCAM].imageMD.XRes()) ||
(static_cast<unsigned int>(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);
}
Expand Down Expand Up @@ -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;
Expand All @@ -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<unsigned int>(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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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<unsigned int>(n_devices); ++i)
{
if (busId == sensors[i].bus && address == sensors[i].address)
device_id = i;
Expand Down Expand Up @@ -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
Expand All @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/pclRGBDServer/cameraRGB.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ namespace kinect{
}

virtual std::string startCameraStreaming(const Ice::Current&){

return "";
}

virtual void stopCameraStreaming(const Ice::Current&) {
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/pclRGBDServer/cameradepth.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ namespace kinect{
}

virtual std::string startCameraStreaming(const Ice::Current&){

return "";
}

virtual void stopCameraStreaming(const Ice::Current&) {
Expand Down
Loading