set_camera_info.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import rospy
00019 from sensor_msgs.msg import *
00020 from sensor_msgs.srv import *
00021 
00022 rospy.init_node('set_camera_info')
00023 rospy.wait_for_service('camera/set_camera_info')
00024 set_camera_info = rospy.ServiceProxy('camera/set_camera_info', SetCameraInfo)
00025 req = SetCameraInfoRequest()
00026 req.camera_info.header.stamp = rospy.Time.now()
00027 req.camera_info.header.frame_id = rospy.get_param('~frame_id')
00028 req.camera_info.height = rospy.get_param('~image_height')
00029 req.camera_info.width = rospy.get_param('~image_width')
00030 req.camera_info.distortion_model = "plumb_bob"
00031 req.camera_info.D = rospy.get_param('~distortion_coefficients/data')
00032 req.camera_info.K = rospy.get_param('~camera_matrix/data')
00033 req.camera_info.R = rospy.get_param('~rectification_matrix/data')
00034 req.camera_info.P = rospy.get_param('~projection_matrix/data')
00035 print req.camera_info
00036 try:
00037   resp1 = set_camera_info(req)
00038 except rospy.ServiceException, e:
00039   print "Service did not process request: %s"%str(e)


cob_camera_sensors
Author(s): Jan Fischer , Richard Bormann
autogenerated on Sat Jun 8 2019 21:02:02