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
30 changes: 0 additions & 30 deletions src/drivers/MAVLinkServer/MAVProxy/uav_viewer_py.yml

This file was deleted.

3 changes: 1 addition & 2 deletions src/drivers/YoutubeServer/youtubeserver.yml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
youtubeServer:
ImageSrv:
Server: 1 # 0 -> Deactivate, 1 -> Ice , 2 -> ROS (Not supported)
Server: Ice #Deactivate, Ice , ROS (Not supported)
Proxy: "default -h 0.0.0.0 -p 9999"
URL: "https://www.youtube.com/watch?v=zw47_q9wbBE"
LiveBroadcast: False #True for youtube live events
Expand All @@ -10,4 +10,3 @@ youtubeServer:
Name: youtubeServer_py

NodeName: youtubeServerCfg

7 changes: 3 additions & 4 deletions src/examples/basic_component/basic_component.yml
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
basic_component:
Motors:
Server: 1 # 0 -> Deactivate, 1 -> Ice , 2 -> ROS
Server: Ice # Deactivate, Ice , ROS
Proxy: "Motors:default -h localhost -p 9001"
Topic: "/turtlebotROS/mobile_base/commands/velocity"
Name: basic_componentCamera
maxW: 0.7
maxV: 4

Camera:
Server: 1 # 0 -> Deactivate, 1 -> Ice , 2 -> ROS
Server: Ice # Deactivate, Ice , ROS
Proxy: "CameraL:default -h localhost -p 9001"
Format: RGB8
Topic: "/TurtlebotROS/cameraL/image_raw"
Expand All @@ -17,4 +17,3 @@ basic_component:
NodeName: basic_component
Vmax: 5
Wmax: 0.5

6 changes: 3 additions & 3 deletions src/examples/basic_component_py/basic_component_py.yml
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
basic_component:
Motors:
Server: 1 # 0 -> Deactivate, 1 -> Ice , 2 -> ROS
Server: Ice # Deactivate, Ice , ROS
Proxy: "Motors:default -h localhost -p 9001"
Topic: "/turtlebotROS/mobile_base/commands/velocity"
Name: basic_component_pyCamera
maxW: 0.7
maxV: 4

Camera:
Server: 1 # 0 -> Deactivate, 1 -> Ice , 2 -> ROS
Server: Ice # Deactivate, Ice , ROS
Proxy: "CameraL:default -h localhost -p 9001"
Format: RGB8
Topic: "/TurtlebotROS/cameraL/image_raw"
Expand Down
13 changes: 11 additions & 2 deletions src/libs/comm_cpp/src/ardroneextraClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,21 @@

namespace Comm {

ArDroneExtraClient*
ArDroneExtraClient*
getArDroneExtraClient(Comm::Communicator* jdrc, std::string prefix){
ArDroneExtraClient* client = 0;

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;

int server = jdrc->getConfig().asIntWithDefault(prefix+".Server", 0);
switch (server){
case 0:
{
Expand Down
14 changes: 12 additions & 2 deletions src/libs/comm_cpp/src/bumperClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,21 @@

namespace Comm {

BumperClient*
BumperClient*
getBumperClient(Comm::Communicator* jdrc, std::string prefix){
BumperClient* client = 0;

int server = jdrc->getConfig().asIntWithDefault(prefix+".Server", 0);
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;

switch (server){
case 0:
{
Expand Down
15 changes: 12 additions & 3 deletions src/libs/comm_cpp/src/cameraClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,21 @@

namespace Comm {

CameraClient*
CameraClient*
getCameraClient(Comm::Communicator* jdrc, std::string prefix){
CameraClient* client = 0;

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;

int server = jdrc->getConfig().asIntWithDefault(prefix+".Server", 0);
switch (server){
case 0:
{
Expand Down Expand Up @@ -76,4 +85,4 @@ getCameraClient(Comm::Communicator* jdrc, std::string prefix){

}

}//NS
}//NS
13 changes: 11 additions & 2 deletions src/libs/comm_cpp/src/cmdvelClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,21 @@

namespace Comm {

CMDVelClient*
CMDVelClient*
getCMDVelClient(Comm::Communicator* jdrc, std::string prefix){
CMDVelClient* client = 0;

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;

int server = jdrc->getConfig().asIntWithDefault(prefix+".Server", 0);
switch (server){
case 0:
{
Expand Down
14 changes: 12 additions & 2 deletions src/libs/comm_cpp/src/laserClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,21 @@

namespace Comm {

LaserClient*
LaserClient*
getLaserClient(Comm::Communicator* jdrc, std::string prefix){
LaserClient* client = 0;

int server = jdrc->getConfig().asIntWithDefault(prefix+".Server", 0);
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;

switch (server){
case 0:
{
Expand Down
13 changes: 11 additions & 2 deletions src/libs/comm_cpp/src/motorsClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,21 @@

namespace Comm {

MotorsClient*
MotorsClient*
getMotorsClient(Comm::Communicator* jdrc, std::string prefix){
MotorsClient* client = 0;

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;

int server = jdrc->getConfig().asIntWithDefault(prefix+".Server", 0);
switch (server){
case 0:
{
Expand Down
14 changes: 12 additions & 2 deletions src/libs/comm_cpp/src/navdataClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,21 @@

namespace Comm {

NavdataClient*
NavdataClient*
getNavdataClient(Comm::Communicator* jdrc, std::string prefix){
NavdataClient* client = 0;

int server = jdrc->getConfig().asIntWithDefault(prefix+".Server", 0);
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;

switch (server){
case 0:
{
Expand Down
15 changes: 12 additions & 3 deletions src/libs/comm_cpp/src/pose3dClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,21 @@

namespace Comm {

Pose3dClient*
Pose3dClient*
getPose3dClient(Comm::Communicator* jdrc, std::string prefix){
Pose3dClient* client = 0;

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;

int server = jdrc->getConfig().asIntWithDefault(prefix+".Server", 0);
switch (server){
case 0:
{
Expand Down Expand Up @@ -57,4 +66,4 @@ getPose3dClient(Comm::Communicator* jdrc, std::string prefix){

}

}//NS
}//NS
15 changes: 12 additions & 3 deletions src/libs/comm_cpp/src/rgbdClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,21 @@

namespace Comm {

RgbdClient*
RgbdClient*
getRgbdClient(Comm::Communicator* jdrc, std::string prefix){
RgbdClient* client = 0;

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;

int server = jdrc->getConfig().asIntWithDefault(prefix+".Server", 0);
switch (server){
case 0:
{
Expand Down Expand Up @@ -77,4 +86,4 @@ getRgbdClient(Comm::Communicator* jdrc, std::string prefix){

}

}//NS
}//NS
11 changes: 7 additions & 4 deletions src/libs/comm_py/comm/ardroneextraClient.py.only-ice.in
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ def __getPublisherArDroneExtra(jdrc, prefix):
@return ArDroneExtra ROS Publisher

'''

print(prefix + ": ROS msg are diabled")
return None

Expand Down Expand Up @@ -71,9 +71,12 @@ def getArDroneExtraClient (jdrc, prefix):

'''
server = jdrc.getConfig().getProperty(prefix+".Server")
if not server:
server=0
if server.lower() == "ice":
server=1
elif server.lower() == "ros":
server=2
else : server = 0

cons = [__ArDroneExtradisabled, __getArDroneExtraIceClient, __getPublisherArDroneExtra]

return cons[server](jdrc, prefix)
return cons[server](jdrc, prefix)
11 changes: 7 additions & 4 deletions src/libs/comm_py/comm/ardroneextraClient.py.ros.in
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ def __getPublisherArDroneExtra(jdrc, prefix):
@return ArDroneExtra ROS Publisher

'''

print(prefix + ": This Interface doesn't support ROS msg")
return None

Expand Down Expand Up @@ -71,9 +71,12 @@ def getArDroneExtraClient (jdrc, prefix):

'''
server = jdrc.getConfig().getProperty(prefix+".Server")
if not server:
server=0
if server.lower() == "ice":
server=1
elif server.lower() == "ros":
server=2
else : server = 0

cons = [__ArDroneExtradisabled, __getArDroneExtraIceClient, __getPublisherArDroneExtra]

return cons[server](jdrc, prefix)
return cons[server](jdrc, prefix)
9 changes: 7 additions & 2 deletions src/libs/comm_py/comm/bumperClient.py.only-ice.in
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,13 @@ def getBumperClient (jdrc, prefix):
@return None if Bumper is disabled

'''
server = jdrc.getConfig().getPropertyWithDefault(prefix+".Server", 0)
server = jdrc.getConfig().getProperty(prefix+".Server")
if server.lower() == "ice":
server=1
elif server.lower() == "ros":
server=2
else : server = 0

cons = [__Bumperdisabled, __getBumperIceClient, __getListenerBumper]

return cons[server](jdrc, prefix)
return cons[server](jdrc, prefix)
Loading