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
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: 2 additions & 0 deletions src/libs/comm_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ include_directories(

set(HEADERS
include/jderobot/comm/communicator.hpp
include/jderobot/comm/tools.hpp
include/jderobot/comm/laserClient.hpp
include/jderobot/comm/interfaces/laserClient.hpp
include/jderobot/comm/ice/laserIceClient.hpp
Expand Down Expand Up @@ -65,6 +66,7 @@ set(HEADERS

set(SOURCES
src/communicator.cpp
src/tools.cpp
src/laserClient.cpp
src/ice/laserIceClient.cpp
src/cameraClient.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,13 @@


#include <Ice/Communicator.h>
#include <jderobot/comm/tools.hpp>
#include <jderobot/comm/communicator.hpp>
#include <jderobot/comm/interfaces/ardroneextraClient.hpp>
#include <jderobot/comm/ice/ardroneextraIceClient.hpp>
#ifdef JDERROS
//#include <jderobot/comm/ros/publisherArDroneExtra.hpp>
#endif



Expand Down
5 changes: 5 additions & 0 deletions src/libs/comm_cpp/include/jderobot/comm/bumperClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,13 @@

#include <jderobot/types/bumperData.h>
#include <Ice/Communicator.h>
#include <jderobot/comm/tools.hpp>
#include <jderobot/comm/communicator.hpp>
#include <jderobot/comm/interfaces/bumperClient.hpp>
#include <jderobot/comm/ice/bumperIceClient.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/listenerBumper.hpp>
#endif



Expand Down
5 changes: 5 additions & 0 deletions src/libs/comm_cpp/include/jderobot/comm/cameraClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,13 @@

#include <jderobot/types/image.h>
#include <Ice/Communicator.h>
#include <jderobot/comm/tools.hpp>
#include <jderobot/comm/communicator.hpp>
#include <jderobot/comm/interfaces/cameraClient.hpp>
#include <jderobot/comm/ice/cameraIceClient.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/listenerCamera.hpp>
#endif



Expand Down
5 changes: 5 additions & 0 deletions src/libs/comm_cpp/include/jderobot/comm/cmdvelClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,13 @@

#include <jderobot/types/cmdvel.h>
#include <Ice/Communicator.h>
#include <jderobot/comm/tools.hpp>
#include <jderobot/comm/communicator.hpp>
#include <jderobot/comm/interfaces/cmdvelClient.hpp>
#include <jderobot/comm/ice/cmdvelIceClient.hpp>
#ifdef JDERROS
//#include <jderobot/comm/ros/publisherCMDVel.hpp>
#endif



Expand Down
1 change: 1 addition & 0 deletions src/libs/comm_cpp/include/jderobot/comm/communicator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <Ice/Communicator.h>
#include <Ice/Initialize.h>
#include <jderobot/config/properties.hpp>
#include <jderobot/comm/tools.hpp>


namespace Comm {
Expand Down
5 changes: 5 additions & 0 deletions src/libs/comm_cpp/include/jderobot/comm/laserClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,13 @@

#include <jderobot/types/laserData.h>
#include <Ice/Communicator.h>
#include <jderobot/comm/tools.hpp>
#include <jderobot/comm/communicator.hpp>
#include <jderobot/comm/interfaces/laserClient.hpp>
#include <jderobot/comm/ice/laserIceClient.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/listenerLaser.hpp>
#endif



Expand Down
6 changes: 6 additions & 0 deletions src/libs/comm_cpp/include/jderobot/comm/motorsClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,14 @@

#include <jderobot/types/cmdvel.h>
#include <Ice/Communicator.h>
#include <jderobot/comm/tools.hpp>
#include <jderobot/comm/communicator.hpp>
#include <jderobot/comm/interfaces/motorsClient.hpp>
#include <jderobot/comm/ice/motorsIceClient.hpp>
#include <jderobot/comm/tools.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/publisherMotors.hpp>
#endif



Expand Down
5 changes: 5 additions & 0 deletions src/libs/comm_cpp/include/jderobot/comm/navdataClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,13 @@

#include <jderobot/types/navdataData.h>
#include <Ice/Communicator.h>
#include <jderobot/comm/tools.hpp>
#include <jderobot/comm/communicator.hpp>
#include <jderobot/comm/interfaces/navdataClient.hpp>
#include <jderobot/comm/ice/navdataIceClient.hpp>
#ifdef JDERROS
//#include <jderobot/comm/ros/listenerNavdata.hpp>
#endif



Expand Down
5 changes: 5 additions & 0 deletions src/libs/comm_cpp/include/jderobot/comm/pose3dClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,13 @@

#include <jderobot/types/laserData.h>
#include <Ice/Communicator.h>
#include <jderobot/comm/tools.hpp>
#include <jderobot/comm/communicator.hpp>
#include <jderobot/comm/interfaces/pose3dClient.hpp>
#include <jderobot/comm/ice/pose3dIceClient.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/listenerPose.hpp>
#endif



Expand Down
5 changes: 5 additions & 0 deletions src/libs/comm_cpp/include/jderobot/comm/rgbdClient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,13 @@

#include <jderobot/types/rgbd.h>
#include <Ice/Communicator.h>
#include <jderobot/comm/tools.hpp>
#include <jderobot/comm/communicator.hpp>
#include <jderobot/comm/interfaces/rgbdClient.hpp>
#include <jderobot/comm/ice/rgbdIceClient.hpp>
#ifdef JDERROS
//#include <jderobot/comm/ros/listenerRgbd.hpp>
#endif



Expand Down
33 changes: 33 additions & 0 deletions src/libs/comm_cpp/include/jderobot/comm/tools.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
/*
* Copyright (C) 1997-2018 JDE Developers Team
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
* Authors :
* Aitor Martinez Fernandez <aitor.martinez.fernandez@gmail.com>
*/

#ifndef JDEROBOTCOMM_TOOLS_H
#define JDEROBOTCOMM_TOOLS_H

#include <jderobot/config/properties.hpp>


namespace Comm {

int server2int (std::string server);


} //NS

#endif // JDEROBOTCOMM_TOOLS_H
14 changes: 2 additions & 12 deletions src/libs/comm_cpp/src/ardroneextraClient.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
#include <jderobot/comm/ardroneextraClient.hpp>
#include <jderobot/comm/ice/ardroneextraIceClient.hpp>
#ifdef JDERROS
//#include <jderobot/comm/ros/publisherArDroneExtra.hpp>
#endif


namespace Comm {

Expand All @@ -12,14 +9,7 @@ getArDroneExtraClient(Comm::Communicator* jdrc, std::string prefix){

int server;
std::string server_name = jdrc->getConfig().asString(prefix+".Server");
std::transform(server_name.begin(), server_name.end(), server_name.begin(), ::tolower);
if(server_name == "ice"){
server = 1;
}
else if(server_name == "ros"){
server = 2;
}
else server = 0;
server = server2int(server_name);

switch (server){
case 0:
Expand Down
16 changes: 3 additions & 13 deletions src/libs/comm_cpp/src/bumperClient.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
#include <jderobot/comm/interfaces/bumperClient.hpp>
#include <jderobot/comm/ice/bumperIceClient.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/listenerBumper.hpp>
#endif
#include <jderobot/comm/bumperClient.hpp>


namespace Comm {

Expand All @@ -12,14 +9,7 @@ getBumperClient(Comm::Communicator* jdrc, std::string prefix){

int server;
std::string server_name = jdrc->getConfig().asString(prefix+".Server");
std::transform(server_name.begin(), server_name.end(), server_name.begin(), ::tolower);
if(server_name == "ice"){
server = 1;
}
else if(server_name == "ros"){
server = 2;
}
else server = 0;
server = server2int(server_name);

switch (server){
case 0:
Expand Down
14 changes: 2 additions & 12 deletions src/libs/comm_cpp/src/cameraClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,7 @@
* Aitor Martinez Fernandez <aitor.martinez.fernandez@gmail.com>
*/
#include <jderobot/comm/cameraClient.hpp>
#include <jderobot/comm/ice/cameraIceClient.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/listenerCamera.hpp>
#endif


namespace Comm {

Expand All @@ -30,14 +27,7 @@ getCameraClient(Comm::Communicator* jdrc, std::string prefix){

int server;
std::string server_name = jdrc->getConfig().asString(prefix+".Server");
std::transform(server_name.begin(), server_name.end(), server_name.begin(), ::tolower);
if(server_name == "ice"){
server = 1;
}
else if(server_name == "ros"){
server = 2;
}
else server = 0;
server = server2int(server_name);

switch (server){
case 0:
Expand Down
14 changes: 2 additions & 12 deletions src/libs/comm_cpp/src/cmdvelClient.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
#include <jderobot/comm/cmdvelClient.hpp>
#include <jderobot/comm/ice/cmdvelIceClient.hpp>
#ifdef JDERROS
//#include <jderobot/comm/ros/publisherCMDVel.hpp>
#endif


namespace Comm {

Expand All @@ -12,14 +9,7 @@ getCMDVelClient(Comm::Communicator* jdrc, std::string prefix){

int server;
std::string server_name = jdrc->getConfig().asString(prefix+".Server");
std::transform(server_name.begin(), server_name.end(), server_name.begin(), ::tolower);
if(server_name == "ice"){
server = 1;
}
else if(server_name == "ros"){
server = 2;
}
else server = 0;
server = server2int(server_name);

switch (server){
case 0:
Expand Down
16 changes: 3 additions & 13 deletions src/libs/comm_cpp/src/laserClient.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
#include <jderobot/comm/interfaces/laserClient.hpp>
#include <jderobot/comm/ice/laserIceClient.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/listenerLaser.hpp>
#endif
#include <jderobot/comm/laserClient.hpp>


namespace Comm {

Expand All @@ -12,14 +9,7 @@ getLaserClient(Comm::Communicator* jdrc, std::string prefix){

int server;
std::string server_name = jdrc->getConfig().asString(prefix+".Server");
std::transform(server_name.begin(), server_name.end(), server_name.begin(), ::tolower);
if(server_name == "ice"){
server = 1;
}
else if(server_name == "ros"){
server = 2;
}
else server = 0;
server = server2int(server_name);

switch (server){
case 0:
Expand Down
13 changes: 1 addition & 12 deletions src/libs/comm_cpp/src/motorsClient.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,4 @@
#include <jderobot/comm/motorsClient.hpp>
#include <jderobot/comm/ice/motorsIceClient.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/publisherMotors.hpp>
#endif

namespace Comm {

Expand All @@ -12,14 +8,7 @@ getMotorsClient(Comm::Communicator* jdrc, std::string prefix){

int server;
std::string server_name = jdrc->getConfig().asString(prefix+".Server");
std::transform(server_name.begin(), server_name.end(), server_name.begin(), ::tolower);
if(server_name == "ice"){
server = 1;
}
else if(server_name == "ros"){
server = 2;
}
else server = 0;
server = server2int(server_name);

switch (server){
case 0:
Expand Down
15 changes: 3 additions & 12 deletions src/libs/comm_cpp/src/navdataClient.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
#include <jderobot/comm/interfaces/navdataClient.hpp>
#include <jderobot/comm/ice/navdataIceClient.hpp>
#ifdef JDERROS
//#include <jderobot/comm/ros/listenerNavdata.hpp>
#endif
#include <jderobot/comm/navdataClient.hpp>


namespace Comm {

Expand All @@ -13,13 +10,7 @@ getNavdataClient(Comm::Communicator* jdrc, std::string prefix){
int server;
std::string server_name = jdrc->getConfig().asString(prefix+".Server");
std::transform(server_name.begin(), server_name.end(), server_name.begin(), ::tolower);
if(server_name == "ice"){
server = 1;
}
else if(server_name == "ros"){
server = 2;
}
else server = 0;
server = server2int(server_name);

switch (server){
case 0:
Expand Down
13 changes: 2 additions & 11 deletions src/libs/comm_cpp/src/pose3dClient.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
#include <jderobot/comm/pose3dClient.hpp>
#include <jderobot/comm/ice/pose3dIceClient.hpp>
#ifdef JDERROS
#include <jderobot/comm/ros/listenerPose.hpp>
#endif


namespace Comm {

Expand All @@ -13,13 +10,7 @@ getPose3dClient(Comm::Communicator* jdrc, std::string prefix){
int server;
std::string server_name = jdrc->getConfig().asString(prefix+".Server");
std::transform(server_name.begin(), server_name.end(), server_name.begin(), ::tolower);
if(server_name == "ice"){
server = 1;
}
else if(server_name == "ros"){
server = 2;
}
else server = 0;
server = server2int(server_name);

switch (server){
case 0:
Expand Down
Loading