Skip to content
This repository has been archived by the owner on Jan 8, 2024. It is now read-only.

Commit

Permalink
Removed some TODOs and Refactoring
Browse files Browse the repository at this point in the history
  • Loading branch information
iml-dlux committed Feb 6, 2019
1 parent bf7fa68 commit 8106013
Show file tree
Hide file tree
Showing 8 changed files with 53 additions and 48 deletions.
18 changes: 9 additions & 9 deletions scripts/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,6 @@
import signal
import argparse



from include.constants import Constants as C

# Main function.
Expand All @@ -52,30 +50,32 @@
# Get Input
results = parser.parse_args()

# At first determine the config-Folder location (either in firos/config or customly set)
current_path = os.path.dirname(os.path.abspath(__file__))
conf_path = current_path + "/../config"
if results.conf_Fold is not None:
current_path = os.getcwd()
conf_path= current_path + "/" + results.conf_Fold
# TODO DL This re-assignment is currently not working!



# Initialize global variables (Constants.py)
C.init(conf_path)


# Importing firos specific scripts
from setup import launchSetup


from include import confManager
from include.logger import Log
from include.logger import Log, initLog
from include.mapServer import MapServer
from include.server.firosServer import FirosServer

from include.ros.topicHandler import RosTopicHandler, loadMsgHandlers, createConnectionListeners, initPubAndSub
from include.rcm.topicManager import TopicManager



# Overwrite global variables with command line arguments (iff set)
if results.port is not None:
C.MAP_SERVER_PORT = int(results.port)

Expand All @@ -88,14 +88,14 @@
if results.loglevel is not None:
C.LOGLEVEL = results.loglevel



# Starting Up!
initLog()
Log("INFO", "Initializing ROS node: " + C.ROS_NODE_NAME)
rospy.init_node(C.ROS_NODE_NAME)
Log("INFO", "Initialized")



print C.ROS_NODE_NAME
toMa = TopicManager()

try:
Expand Down
11 changes: 5 additions & 6 deletions scripts/include/constants.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ def init(cls, path):
if not cls.configured:
configured = True
cls.PATH = path
print cls.PATH # TODO DL print

configData = cls.setConfiguration(path)

Expand All @@ -70,26 +69,26 @@ def init(cls, path):
cls.CONTEXTBROKER_ADRESS = configData["contextbroker"]["address"]
cls.CONTEXTBROKER_PORT = configData["contextbroker"]["port"]
except:
print "TODO DL"
raise Exception("No Context-Broker specified!")

if "contextbroker" in configData and "subscription" in configData["contextbroker"]:
# Configuration for Subscription
subConfig = configData["contextbroker"]["subscription"]
if "throttling" in subConfig:
cls.CB_THROTTLING = subConfig["throttling"]
cls.CB_THROTTLING = int(subConfig["throttling"])

if "subscription_length" in subConfig:
cls.CB_SUB_LENGTH = subConfig["subscription_length"]
cls.CB_SUB_LENGTH = int(subConfig["subscription_length"])

if "subscription_refresh_delay" in subConfig:
cls.CB_SUB_REFRESH = subConfig["subscription_refresh_delay"]
cls.CB_SUB_REFRESH = float(subConfig["subscription_refresh_delay"])


if "node_name" in configData:
cls.ROS_NODE_NAME = configData["node_name"]

if "ros_subscriber_queue" in configData:
cls.ROS_SUB_QUEUE_SIZE = configData["ros_subscriber_queue"]
cls.ROS_SUB_QUEUE_SIZE = int(configData["ros_subscriber_queue"])

if "cb_type" in configData:
cls.CB_CONTEXT_TYPE = configData["cb_type"]
Expand Down
4 changes: 2 additions & 2 deletions scripts/include/contextbroker/cbPublisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -66,10 +66,10 @@ def publishToCB(self, robotID, topic, rawMsg, msgDefintionDict):
# if struct not initilized, intitilize it even on ContextBroker!
if robotID not in self.posted_history:
self.posted_history[robotID] = {}
self.posted_history[robotID]['type'] = 'ROBOT'
self.posted_history[robotID]['type'] = C.CB_CONTEXT_TYPE
self.posted_history[robotID]['id'] = robotID
# Intitialize Entitiy/Robot-Construct on ContextBroker
jsonStr = ObjectFiwareConverter.obj2Fiware(self.posted_history[robotID], ind=0, ignorePythonMetaData=True)
jsonStr = ObjectFiwareConverter.obj2Fiware(self.posted_history[robotID], ind=0, ignorePythonMetaData=True)
response = requests.post(self.CB_BASE_URL, data=jsonStr, headers=self.CB_HEADER)
self._responseCheck(response, attrAction=0, topEnt=robotID)

Expand Down
11 changes: 5 additions & 6 deletions scripts/include/contextbroker/cbSubscriber.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
import json

from include.FiwareObjectConverter.objectFiwareConverter import ObjectFiwareConverter
# from include.constants import CONTEXTBROKER_ADRESS, CONTEXTBROKER_PORT, MAP_SERVER_ADRESS, MAP_SERVER_PORT, CB_SUB_REFRESH, CB_SUB_LENGTH
from include.constants import Constants as C
from include.logger import Log

Expand Down Expand Up @@ -109,13 +108,13 @@ def subscribeThread(self, robotID, topic):
self.subscriptionIds[robotID][topic] = newSubID

# Wait
time.sleep(int(C.CB_SUB_LENGTH * C.CB_SUB_REFRESH)) # sleep TODO DL from config loaded seconds
time.sleep(int(C.CB_SUB_LENGTH * C.CB_SUB_REFRESH)) # sleep Length * Refresh-Rate (where 0 < Refresh-Rate < 1)
Log("INFO", "Refreshing Subscription for " + robotID + " and topics: " + str(topic))


def subscribeJSONGenerator(self, robotID, topic):
''' This method returns the correct JSON-format to subscribe to the ContextBroker.
The Expiration-Date/Throttle and Type of robots is retreived here via configuration (TODO DL)
The Expiration-Date/Throttle and Type of robots is retreived here via configuration
robotID: The String of the Robot-Id.
topic: The actual topic to subscribe to.
Expand All @@ -127,7 +126,7 @@ def subscribeJSONGenerator(self, robotID, topic):
"entities": [
{
"id": str(robotID),
"type": "ROBOT" # TODO DL load via Configuration
"type": C.CB_CONTEXT_TYPE
}
],
"condition": {
Expand All @@ -140,8 +139,8 @@ def subscribeJSONGenerator(self, robotID, topic):
},
"attrs": [str(topic)]
},
"expires": time.strftime("%Y-%m-%dT%H:%M:%S.00Z", time.gmtime(time.time() + C.CB_SUB_LENGTH)) # TODO DL load via Configuration, ISO 8601
# "throttling": 5 # TODO DL Maybe throttle?
"expires": time.strftime("%Y-%m-%dT%H:%M:%S.00Z", time.gmtime(time.time() + C.CB_SUB_LENGTH)), # ISO 8601
"throttling": C.CB_THROTTLING
}
return json.dumps(struct)

Expand Down
47 changes: 27 additions & 20 deletions scripts/include/logger.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,35 +24,42 @@

SYSLOG_ADDRESS = '/dev/log'

if C.LOGLEVEL == 'CRITICAL':
_logger.setLevel(logging.CRITICAL)
elif C.LOGLEVEL == 'ERROR':
_logger.setLevel(logging.ERROR)
elif C.LOGLEVEL == 'WARNING':
_logger.setLevel(logging.WARNING)
elif C.LOGLEVEL == 'DEBUG':
_logger.setLevel(logging.DEBUG)
elif C.LOGLEVEL == 'INFO':
_logger.setLevel(logging.INFO)

PRIORITIES = {
'CRITICAL': 5,
'ERROR': 3,
'WARNING': 2,
'DEBUG': 1,
'INFO': 0
}
if C.LOGLEVEL == "NONE":
_levelId = -1
else:
_levelId = PRIORITIES[C.LOGLEVEL]

if os.path.exists(SYSLOG_ADDRESS):
handler = logging.handlers.SysLogHandler(address=SYSLOG_ADDRESS)
_logger.addHandler(handler)
else:
handler = None
_levelId = None
handler = None

def initLog():
''' Sets _levelID and handler
'''
global _levelId, handler
if C.LOGLEVEL == 'CRITICAL':
_logger.setLevel(logging.CRITICAL)
elif C.LOGLEVEL == 'ERROR':
_logger.setLevel(logging.ERROR)
elif C.LOGLEVEL == 'WARNING':
_logger.setLevel(logging.WARNING)
elif C.LOGLEVEL == 'DEBUG':
_logger.setLevel(logging.DEBUG)
elif C.LOGLEVEL == 'INFO':
_logger.setLevel(logging.INFO)

if C.LOGLEVEL == "NONE":
_levelId = -1
else:
_levelId = PRIORITIES[C.LOGLEVEL]

if os.path.exists(SYSLOG_ADDRESS):
handler = logging.handlers.SysLogHandler(address=SYSLOG_ADDRESS)
_logger.addHandler(handler)
else:
handler = None

def Log(level, *args):
## \brief Logging function
Expand Down
7 changes: 4 additions & 3 deletions scripts/include/mapServer.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,15 +38,16 @@ def __init__(self):


def _launchMapServer(self):
# TODO DL can this be omitted?
## \brief If map_server is configured launches it
if(C.MAP_SERVER_PORT):
# if not os.path.exists(os.path.join(mapserver_path, 'node_modules')):
# if not os.path.exists(os.path.join(self.mapserver_path, 'node_modules')):
# text = "---------------------------------------------------------------------------------------\n"
# text += "---------------------------------------------------------------------------------------\n"
# text += "FIROS is going to install mapserver's dependencies, to do this it will need root access\n"
# text += "---------------------------------------------------------------------------------------\n"
# text += "---------------------------------------------------------------------------------------"
# print text
# os.system("cd {} && sudo npm install && sudo chown -R {} node_modules".format(mapserver_path, getpass.getuser()))
# subprocess.Popen(["node", mapserver_path + "mapserver.js", str(MAP_SERVER_PORT), str(ROSBRIDGE_PORT)])
# os.system("cd {} && sudo npm install && sudo chown -R {} node_modules".format(self.mapserver_path, getpass.getuser()))
# subprocess.Popen(["node", self.mapserver_path + "mapserver.js", str(C.MAP_SERVER_PORT), str(C.ROSBRIDGE_PORT)])
pass
2 changes: 1 addition & 1 deletion scripts/include/rcm/topicManager.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

from firos.srv import FIROS_Info
from firos.msg import Robot_Event, CB_Event
from include.constants import Constants as C #ROS_SUB_QUEUE_SIZE, ROS_NODE_NAME
from include.constants import Constants as C
from include.ros.topicHandler import robotDisconnection, loadMsgHandlers
from include.rcm.rcmutils import getRobotConfig

Expand Down
1 change: 0 additions & 1 deletion scripts/include/ros/topicHandler.py
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,6 @@ def loadMsgHandlers(robot_data):
ROS_PUBLISHER[robotID][topic] = rospy.Publisher(robotID + "/" + topic, theclass, queue_size=C.ROS_SUB_QUEUE_SIZE)

# After initializing ROS-PUB/SUBs, intitialize ContextBroker-Subscriber based on ROS-Publishers for each robot
print ROS_PUBLISHER
if robotID in ROS_PUBLISHER:
CloudSubscriber.subscribeToCB(str(robotID), ROS_PUBLISHER[robotID].keys())
Log("INFO", "\n")
Expand Down

0 comments on commit 8106013

Please sign in to comment.