check_camera_service_power_force_off_and_on_with_subscriber.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 """
3 @file check_camera_service_power_force_off_and_on_with_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 BASEDIR = os.path.abspath(os.path.join(os.path.dirname(__file__)))
16 
17 PKG = "realsense_camera"
18 NAME = "check_camera_service_power_force_off_and_on_with_subscriber"
19 
20 
22  """
23  @class CheckCameraServicePowerForceOffAndOnWithSubscriber: check reponse for power operation like
24  force off and on when camera has subscriber
25  """
26  def setUp(self):
27  '''
28  @fn setUp: make sure camera is powered on
29  @param self
30  '''
31  rospy.init_node(NAME, anonymous=True, log_level=rospy.DEBUG)
32  time.sleep(6)
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.')
36 
38  """
39  @fn test_force_camera_off_and_on_with_subscriber
40  check camera power can be forced off and on when subscribers exist
41  @param self
42  @return
43  """
44  # add a subscriber to camera
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,
50  preexec_fn=os.setsid)
51  time.sleep(6)
52  cmd = "rosservice call /camera/driver/force_power false"
53  cmd_proc = subprocess.Popen(cmd, stderr=subprocess.STDOUT,
54  stdout=subprocess.PIPE, shell=True,
55  preexec_fn=os.setsid)
56  time.sleep(2)
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,
62  preexec_fn=os.setsid)
63  time.sleep(2)
64  output = os.popen("rosservice call /camera/driver/is_powered")
65  self.assertNotEqual(-1, output.read().find('True'))
66  self.assertTrue(is_log_contains_keyword(
67  LOGFILE, stop_camera_info))
68  self.assertTrue(is_log_contains_keyword(
69  LOGFILE, start_camera_info))
70  os.system('killall rviz')
71 
72 if __name__ == '__main__':
73  param_dict = get_camera_params_and_values(sys.argv)
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 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