check_camera_service_power_set_off_and_on_with_no_subscriber.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 """
00003 @file check_camera_service_power_set_off_and_on_with_no_subscriber.py
00004 """
00005 import os
00006 import sys
00007 import unittest
00008 import time
00009 import subprocess
00010 import commands
00011 import rospy
00012 import rostest
00013 from rs_general.rs_general import get_camera_params_and_values, \
00014      is_log_contains_keyword, LOGFILE
00015 
00016 PKG = "realsense_camera"
00017 NAME = "check_camera_service_power_set_off_and_on_with_no_subscriber"
00018 
00019 
00020 class CheckCameraServicePowerSetOffAndOnWithNoSubscriber(unittest.TestCase):
00021     """
00022     @class CheckCameraServicePowerSetOffAndOnWithNoSubscriber: check reponse for power operation like
00023     set on/off when camera has no subscriber
00024     """
00025     def setUp(self):
00026         '''
00027         @fn setUp: make sure camera is powered on
00028         @param self
00029         '''
00030         rospy.init_node(NAME, anonymous=True, log_level=rospy.DEBUG)
00031         time.sleep(10)
00032         output = os.popen("rosservice call /camera/driver/is_powered")
00033         if output.read().find('True') == -1:
00034             self.assertTrue(False, 'Camera is not powered on.')
00035 
00036     def test_set_camera_off_and_on_with_no_subscribers(self):
00037         """
00038         @fn test_set_camera_off_and_on_with_no_subscribers
00039          check camera power can be set off and on when no subscribers exist
00040         @param self
00041         @return
00042         """
00043         os.system("rosservice call /camera/driver/set_power false")
00044         time.sleep(2)
00045         output = os.popen("rosservice call /camera/driver/is_powered")
00046         self.assertNotEqual(-1, output.read().find('False'))
00047         os.system("rosservice call /camera/driver/set_power true")
00048         time.sleep(2)
00049         output = os.popen("rosservice call /camera/driver/is_powered")
00050         self.assertNotEqual(-1, output.read().find('True'))
00051         self.assertTrue(is_log_contains_keyword(LOGFILE, stop_camera_info))
00052         self.assertTrue(is_log_contains_keyword(LOGFILE, start_camera_info))
00053 
00054 if __name__ == '__main__':
00055     param_dict = get_camera_params_and_values(sys.argv)
00056     start_camera_info = param_dict['start_camera_info'].replace('*', ' ')
00057     stop_camera_info = param_dict['stop_camera_info'].replace('*', ' ')
00058     rostest.rosrun(PKG, NAME, CheckCameraServicePowerSetOffAndOnWithNoSubscriber, sys.argv)


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Thu Jun 6 2019 21:15:58