check_camera_service_power_force_off_and_on_with_subscriber.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 """
00003 @file check_camera_service_power_force_off_and_on_with_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 BASEDIR = os.path.abspath(os.path.join(os.path.dirname(__file__)))
00016 
00017 PKG = "realsense_camera"
00018 NAME = "check_camera_service_power_force_off_and_on_with_subscriber"
00019 
00020 
00021 class CheckCameraServicePowerForceOffAndOnWithSubscriber(unittest.TestCase):
00022     """
00023     @class CheckCameraServicePowerForceOffAndOnWithSubscriber: check reponse for power operation like
00024     force off and on when camera has subscriber
00025     """
00026     def setUp(self):
00027         '''
00028         @fn setUp: make sure camera is powered on
00029         @param self
00030         '''
00031         rospy.init_node(NAME, anonymous=True, log_level=rospy.DEBUG)
00032         time.sleep(6)
00033         output = os.popen("rosservice call /camera/driver/is_powered")
00034         if output.read().find('True') == -1:
00035             self.assertTrue(False, 'Camera is not powered on.')
00036 
00037     def test_force_camera_off_and_on_with_subscriber(self):
00038         """
00039         @fn test_force_camera_off_and_on_with_subscriber
00040          check camera power can be forced off and on when subscribers exist
00041         @param self
00042         @return
00043         """
00044         # add a subscriber to camera
00045         (ret, output) = commands.getstatusoutput(
00046             BASEDIR + '/libs/roscd_path.bash realsense_camera')
00047         cmd = "cd " + output + "; rosrun rviz rviz -d rviz/realsenseRvizConfiguration1.rviz"
00048         subprocess.Popen(cmd, stderr=subprocess.STDOUT,
00049                          stdout=subprocess.PIPE, shell=True,
00050                          preexec_fn=os.setsid)
00051         time.sleep(6)
00052         cmd = "rosservice call /camera/driver/force_power false"
00053         cmd_proc = subprocess.Popen(cmd, stderr=subprocess.STDOUT,
00054                                     stdout=subprocess.PIPE, shell=True,
00055                                     preexec_fn=os.setsid)
00056         time.sleep(2)
00057         output = os.popen("rosservice call /camera/driver/is_powered")
00058         self.assertNotEqual(-1, output.read().find('False'))
00059         cmd = "rosservice call /camera/driver/force_power true"
00060         subprocess.Popen(cmd, stderr=subprocess.STDOUT,
00061                          stdout=subprocess.PIPE, shell=True,
00062                          preexec_fn=os.setsid)
00063         time.sleep(2)
00064         output = os.popen("rosservice call /camera/driver/is_powered")
00065         self.assertNotEqual(-1, output.read().find('True'))
00066         self.assertTrue(is_log_contains_keyword(
00067                             LOGFILE, stop_camera_info))
00068         self.assertTrue(is_log_contains_keyword(
00069                             LOGFILE, start_camera_info))
00070         os.system('killall rviz')
00071 
00072 if __name__ == '__main__':
00073     param_dict = get_camera_params_and_values(sys.argv)
00074     start_camera_info = param_dict['start_camera_info'].replace('*', ' ')
00075     stop_camera_info = param_dict['stop_camera_info'].replace('*', ' ')
00076     rostest.rosrun(PKG, NAME, CheckCameraServicePowerForceOffAndOnWithSubscriber, sys.argv)


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