Main Page
Namespaces
Classes
Files
File List
File Members
scripts
test_halt.py
Go to the documentation of this file.
1
#! /usr/bin/env python
2
3
import
roslib
4
roslib.load_manifest(
'pr2_ethercat'
)
5
import
time
6
import
rospy, sys
7
import
std_srvs.srv
8
from
std_msgs.msg
import
Bool
9
10
halted =
True
11
def
callback
(msg):
12
global
halted
13
print(
"halted: %s"
% msg.data)
14
halted = msg.data
15
16
17
rospy.init_node(
"test_halt"
)
18
rospy.Subscriber(
"motor_state"
, Bool, callback)
19
reset = rospy.ServiceProxy(
"pr2_ethercat/reset_motors"
, std_srvs.srv.Empty)
20
halt = rospy.ServiceProxy(
"pr2_ethercat/halt_motors"
, std_srvs.srv.Empty)
21
time.sleep(1)
22
print(
"Entering main loop: motors %s"
%
"halted"
if
halted
else
"running"
)
23
while
1:
24
old_halted = halted
25
if
old_halted:
26
print(
"Resetting motors"
)
27
reset
()
28
else
:
29
print(
"Halting motors"
)
30
halt
()
31
start = time.time()
32
while
old_halted == halted:
33
time.sleep(0.1)
34
if
time.time() - start > 1:
35
break
36
if
old_halted == halted:
37
print(
"failed! old=%s new=%s"
% (old_halted, halted))
38
break
39
40
test_halt.callback
def callback(msg)
Definition:
test_halt.py:11
test_halt.halt
halt
Definition:
test_halt.py:20
test_halt.reset
reset
Definition:
test_halt.py:19
pr2_ethercat
Author(s): Rob Wheeler
autogenerated on Tue Jun 1 2021 02:50:54