3 @file check_camera_service_power_set_off_and_on_with_no_subscriber.py 14 is_log_contains_keyword, LOGFILE
16 PKG =
"realsense_camera" 17 NAME =
"check_camera_service_power_set_off_and_on_with_no_subscriber" 22 @class CheckCameraServicePowerSetOffAndOnWithNoSubscriber: check reponse for power operation like 23 set on/off when camera has no subscriber 27 @fn setUp: make sure camera is powered on 30 rospy.init_node(NAME, anonymous=
True, log_level=rospy.DEBUG)
32 output = os.popen(
"rosservice call /camera/driver/is_powered")
33 if output.read().find(
'True') == -1:
34 self.assertTrue(
False,
'Camera is not powered on.')
38 @fn test_set_camera_off_and_on_with_no_subscribers 39 check camera power can be set off and on when no subscribers exist 43 os.system(
"rosservice call /camera/driver/set_power false")
45 output = os.popen(
"rosservice call /camera/driver/is_powered")
46 self.assertNotEqual(-1, output.read().find(
'False'))
47 os.system(
"rosservice call /camera/driver/set_power true")
49 output = os.popen(
"rosservice call /camera/driver/is_powered")
50 self.assertNotEqual(-1, output.read().find(
'True'))
54 if __name__ ==
'__main__':
56 start_camera_info = param_dict[
'start_camera_info'].replace(
'*',
' ')
57 stop_camera_info = param_dict[
'stop_camera_info'].replace(
'*',
' ')
58 rostest.rosrun(PKG, NAME, CheckCameraServicePowerSetOffAndOnWithNoSubscriber, sys.argv)
def test_set_camera_off_and_on_with_no_subscribers(self)
def is_log_contains_keyword(log_file, keyword)
def get_camera_params_and_values(args)