3 @file check_camera_service_power_force_off_and_on_with_subscriber.py 14 is_log_contains_keyword, LOGFILE
15 BASEDIR = os.path.abspath(os.path.join(os.path.dirname(__file__)))
17 PKG =
"realsense_camera" 18 NAME =
"check_camera_service_power_force_off_and_on_with_subscriber" 23 @class CheckCameraServicePowerForceOffAndOnWithSubscriber: check reponse for power operation like 24 force off and on when camera has subscriber 28 @fn setUp: make sure camera is powered on 31 rospy.init_node(NAME, anonymous=
True, log_level=rospy.DEBUG)
33 output = os.popen(
"rosservice call /camera/driver/is_powered")
34 if output.read().find(
'True') == -1:
35 self.assertTrue(
False,
'Camera is not powered on.')
39 @fn test_force_camera_off_and_on_with_subscriber 40 check camera power can be forced off and on when subscribers exist 45 (ret, output) = commands.getstatusoutput(
46 BASEDIR +
'/libs/roscd_path.bash realsense_camera')
47 cmd =
"cd " + output +
"; rosrun rviz rviz -d rviz/realsenseRvizConfiguration1.rviz" 48 subprocess.Popen(cmd, stderr=subprocess.STDOUT,
49 stdout=subprocess.PIPE, shell=
True,
52 cmd =
"rosservice call /camera/driver/force_power false" 53 cmd_proc = subprocess.Popen(cmd, stderr=subprocess.STDOUT,
54 stdout=subprocess.PIPE, shell=
True,
57 output = os.popen(
"rosservice call /camera/driver/is_powered")
58 self.assertNotEqual(-1, output.read().find(
'False'))
59 cmd =
"rosservice call /camera/driver/force_power true" 60 subprocess.Popen(cmd, stderr=subprocess.STDOUT,
61 stdout=subprocess.PIPE, shell=
True,
64 output = os.popen(
"rosservice call /camera/driver/is_powered")
65 self.assertNotEqual(-1, output.read().find(
'True'))
67 LOGFILE, stop_camera_info))
69 LOGFILE, start_camera_info))
70 os.system(
'killall rviz')
72 if __name__ ==
'__main__':
74 start_camera_info = param_dict[
'start_camera_info'].replace(
'*',
' ')
75 stop_camera_info = param_dict[
'stop_camera_info'].replace(
'*',
' ')
76 rostest.rosrun(PKG, NAME, CheckCameraServicePowerForceOffAndOnWithSubscriber, sys.argv)
def test_force_camera_off_and_on_with_subscriber(self)
def is_log_contains_keyword(log_file, keyword)
def get_camera_params_and_values(args)