Skip to content

Commit

Permalink
Fixed node interpreter
Browse files Browse the repository at this point in the history
  • Loading branch information
khaledhazime committed Oct 23, 2019
1 parent dec420b commit ee3799b
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 2 deletions.
4 changes: 2 additions & 2 deletions butia_navigation_launchfiles/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,6 @@ project(butia_navigation_launchfiles)
# )

install(PROGRAMS
nodes/enable_motors.py
nodes/enable_motors_r.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
)
25 changes: 25 additions & 0 deletions butia_navigation_launchfiles/nodes/enable_motors_r.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
#!/usr/bin/env python
import rospy
from std_msgs.msg import Bool

flag = False

def callBackEM(response):
global flag
if response.data:
flag = True
else:
flag = False


if __name__ == "__main__":
rospy.init_node("enable_motors")
motors_sub = rospy.Subscriber("/RosAria/motors_state", Bool, callBackEM, queue_size=1)
rospy.wait_for_service("/RosAria/enable_motors")
try:
enable_motors = rospy.ServiceProxy("/RosAria/enable_motors", Bool)
except rospy.ServiceException, e:
print "Service call failed %s"%e
while not rospy.is_shutdown():
if not flag:
enable_motors(True)

0 comments on commit ee3799b

Please sign in to comment.