check_camera_service_power_set_off_and_on_with_no_subscriber.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 """
3 @file check_camera_service_power_set_off_and_on_with_no_subscriber.py
4 """
5 import os
6 import sys
7 import unittest
8 import time
9 import subprocess
10 import commands
11 import rospy
12 import rostest
13 from rs_general.rs_general import get_camera_params_and_values, \
14  is_log_contains_keyword, LOGFILE
15 
16 PKG = "realsense_camera"
17 NAME = "check_camera_service_power_set_off_and_on_with_no_subscriber"
18 
19 
21  """
22  @class CheckCameraServicePowerSetOffAndOnWithNoSubscriber: check reponse for power operation like
23  set on/off when camera has no subscriber
24  """
25  def setUp(self):
26  '''
27  @fn setUp: make sure camera is powered on
28  @param self
29  '''
30  rospy.init_node(NAME, anonymous=True, log_level=rospy.DEBUG)
31  time.sleep(10)
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.')
35 
37  """
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
40  @param self
41  @return
42  """
43  os.system("rosservice call /camera/driver/set_power false")
44  time.sleep(2)
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")
48  time.sleep(2)
49  output = os.popen("rosservice call /camera/driver/is_powered")
50  self.assertNotEqual(-1, output.read().find('True'))
51  self.assertTrue(is_log_contains_keyword(LOGFILE, stop_camera_info))
52  self.assertTrue(is_log_contains_keyword(LOGFILE, start_camera_info))
53 
54 if __name__ == '__main__':
55  param_dict = get_camera_params_and_values(sys.argv)
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 is_log_contains_keyword(log_file, keyword)
Definition: rs_general.py:60
def get_camera_params_and_values(args)
Definition: rs_general.py:38


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Mon Jun 10 2019 14:40:37