Skip to content
Snippets Groups Projects
Commit de88cc46 authored by Tommy Persson's avatar Tommy Persson
Browse files

Python 3 fixes.

parent 8b3acd76
No related tags found
No related merge requests found
...@@ -24,35 +24,34 @@ class QSim: ...@@ -24,35 +24,34 @@ class QSim:
def set_ref_data(self, x, y, z, xyspeed, zspeed): def set_ref_data(self, x, y, z, xyspeed, zspeed):
ns = self.ns ns = self.ns
print "set_ref_data: {0} {1} {2} {3} {4} {5}".format(ns, x, y, z, print("set_ref_data: {0} {1} {2} {3} {4} {5}".format(ns, x, y, z, xyspeed, zspeed))
xyspeed, zspeed)
try: try:
set_rd = rospy.ServiceProxy(ns + "sim/set_ref_data", LQSetRefData) set_rd = rospy.ServiceProxy(ns + "sim/set_ref_data", LQSetRefData)
rd = RefData (x, y, z, xyspeed, zspeed, 0, 1) rd = RefData (x, y, z, xyspeed, zspeed, 0, 1)
resp = set_rd(rd) resp = set_rd(rd)
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
exit (1) exit (1)
return resp return resp
def get_ref_data(self): def get_ref_data(self):
ns = self.ns ns = self.ns
print "get_ref_data: {0}".format(ns) print("get_ref_data: {0}".format(ns))
try: try:
get_rd = rospy.ServiceProxy(ns + "sim/get_ref_data", LQGetRefData) get_rd = rospy.ServiceProxy(ns + "sim/get_ref_data", LQGetRefData)
resp = get_rd() resp = get_rd()
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
exit (1) exit (1)
return resp return resp
def new_simulator(unit): def new_simulator(unit):
print "get_ext_data: {0}".format(unit) print("get_ext_data: {0}".format(unit))
try: try:
ns = rospy.ServiceProxy("uav/{0}/sim/new_simulator".format(unit), LQNewSimulator) ns = rospy.ServiceProxy("uav/{0}/sim/new_simulator".format(unit), LQNewSimulator)
resp = ns() resp = ns()
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
exit (1) exit (1)
return resp return resp
...@@ -60,97 +59,97 @@ class QSim: ...@@ -60,97 +59,97 @@ class QSim:
def set_sticks(self, throttle, aileron, elevator, rudder, flight_mode, pan, tilt): def set_sticks(self, throttle, aileron, elevator, rudder, flight_mode, pan, tilt):
ns = self.ns ns = self.ns
print "set_sticks: {0} {1} {2} {3} {4} {5} {6}".format(ns, throttle, aileron, print("set_sticks: {0} {1} {2} {3} {4} {5} {6}".format(ns, throttle, aileron,
elevator, rudder, elevator, rudder,
flight_mode, pan, tilt) flight_mode, pan, tilt))
resp = LQSetSticksResponse() resp = LQSetSticksResponse()
try: try:
set_st = rospy.ServiceProxy(ns + "sim/set_sticks", LQSetSticks) set_st = rospy.ServiceProxy(ns + "sim/set_sticks", LQSetSticks)
resp = set_st(throttle, aileron, elevator, rudder, flight_mode, pan, tilt) resp = set_st(throttle, aileron, elevator, rudder, flight_mode, pan, tilt)
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
resp.res = 128 resp.res = 128
return resp return resp
def set_use_sticks(self, flag): def set_use_sticks(self, flag):
print "set_use_sticks: {0}".format(flag) print("set_use_sticks: {0}".format(flag))
ns = self.ns ns = self.ns
resp = LQSetUseSticksResponse() resp = LQSetUseSticksResponse()
try: try:
set_use_sticks = rospy.ServiceProxy(ns+ "sim/set_use_sticks", LQSetUseSticks) set_use_sticks = rospy.ServiceProxy(ns+ "sim/set_use_sticks", LQSetUseSticks)
resp = set_use_sticks(flag) resp = set_use_sticks(flag)
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
resp.res = 128 resp.res = 128
return resp return resp
def set_motor(self, flag): def set_motor(self, flag):
ns = self.ns ns = self.ns
print "set_motor: {0}".format(flag) print("set_motor: {0}".format(flag))
try: try:
set_motor = rospy.ServiceProxy(ns + "sim/set_motor", LQSetMotor) set_motor = rospy.ServiceProxy(ns + "sim/set_motor", LQSetMotor)
resp = set_motor(flag) resp = set_motor(flag)
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
exit (1) exit (1)
return resp return resp
def set_loop_rate(self, rate): def set_loop_rate(self, rate):
ns = self.ns ns = self.ns
print "set_loop_rate: {0}".format(rate) print("set_loop_rate: {0}".format(rate))
try: try:
client = rospy.ServiceProxy(ns + "sim/set_loop_rate", LQSetLoopRate) client = rospy.ServiceProxy(ns + "sim/set_loop_rate", LQSetLoopRate)
resp = client(rate) resp = client(rate)
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
exit (1) exit (1)
return resp return resp
def get_queue_statistics(self): def get_queue_statistics(self):
ns = self.ns ns = self.ns
print "get_queue_statistics" print("get_queue_statistics")
try: try:
client = rospy.ServiceProxy(ns + "sim/get_queue_statistics", LQGetQueueStatistics) client = rospy.ServiceProxy(ns + "sim/get_queue_statistics", LQGetQueueStatistics)
resp = client() resp = client()
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
exit (1) exit (1)
return resp return resp
def get_queue_commands(self): def get_queue_commands(self):
ns = self.ns ns = self.ns
print "get_queue_commands" print("get_queue_commands")
try: try:
client = rospy.ServiceProxy(ns + "sim/get_queue_commands", LQGetQueueCommands) client = rospy.ServiceProxy(ns + "sim/get_queue_commands", LQGetQueueCommands)
resp = client() resp = client()
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
exit (1) exit (1)
return resp return resp
def start_logging(self, csvfilename): def start_logging(self, csvfilename):
print "start_logging" print("start_logging")
ns = self.ns ns = self.ns
try: try:
start_logging = rospy.ServiceProxy(ns+"sim/start_logging", LQStartLogging) start_logging = rospy.ServiceProxy(ns+"sim/start_logging", LQStartLogging)
resp = start_logging(csvfilename) resp = start_logging(csvfilename)
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
exit (1) exit (1)
return resp return resp
def stop_logging(self): def stop_logging(self):
ns = self.ns ns = self.ns
print "stop_logging" print("stop_logging")
try: try:
stop_logging = rospy.ServiceProxy(ns + "sim/stop_logging", LQStopLogging) stop_logging = rospy.ServiceProxy(ns + "sim/stop_logging", LQStopLogging)
resp = stop_logging() resp = stop_logging()
except rospy.ServiceException, e: except rospy.ServiceException as e:
print "Service call failed: %s"%e print("Service call failed: %s"%e)
exit (1) exit (1)
return resp return resp
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment