Skip to content

Commit

Permalink
Merge pull request #4 from k-okada/use_param_for_camera_info_yaml
Browse files Browse the repository at this point in the history
use param to set camera_info
  • Loading branch information
longjie committed Jan 5, 2015
2 parents a5f8f25 + d16370d commit 9554cfd
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 3 deletions.
5 changes: 4 additions & 1 deletion launch/stereo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,9 @@
</node>
<node name="camera_transform" pkg="tf" type="static_transform_publisher" args="$(arg parent_transform) $(arg parent_frame) /ps4eye_frame 10"/>

<node pkg="ps4eye" type="camera_info_publisher.py" name="camera_info_publisher" />
<node pkg="ps4eye" type="camera_info_publisher.py" name="camera_info_publisher" >
<param name="left_file_name" value="$(find ps4eye)/camera_info/left.yaml" />
<param name="right_file_name" value="$(find ps4eye)/camera_info/right.yaml" />
</node>
<node name="stereo_image_proc" pkg="stereo_image_proc" type="stereo_image_proc" ns="stereo"/>
</launch>
6 changes: 4 additions & 2 deletions script/camera_info_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,13 @@ def callback(self, data):
self.right_cam_info.header = left_cam_info_org.header
publisher.publish()

def __init__(self, camera_name, left_file_name, right_file_name):
def __init__(self, camera_name):
self.left_cam_info_org = 0
self.right_cam_info_org = 0

# yamlファイルを読み込んでCameraInfoを返す
left_file_name = rospy.get_param('~left_file_name', rospack.get_path('ps4eye')+'/camera_info/left.yaml')
right_file_name = rospy.get_param('~right_file_name', rospack.get_path('ps4eye')+'/camera_info/right.yaml')
self.left_cam_info = parse_yaml(left_file_name)
self.right_cam_info = parse_yaml(right_file_name)
left_topic = "/" + camera_name + "/left/camera_info"
Expand Down Expand Up @@ -68,7 +70,7 @@ def parse_yaml(filename):
argv = rospy.myargv(sys.argv)
rospy.init_node("camera_info_publisher")
rospack = rospkg.RosPack()
publisher = CameraInfoPublisher('stereo', rospack.get_path('ps4eye')+'/camera_info/left.yaml',rospack.get_path('ps4eye')+'/camera_info/right.yaml')
publisher = CameraInfoPublisher('stereo')

while not rospy.is_shutdown():
rospy.sleep(rospy.Duration(.1))

0 comments on commit 9554cfd

Please sign in to comment.