Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions 20150422/README-koyama-submit.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# homework20150422 Submission by KOYAMA

Mirror node is a node which shows the mirror image of the image from the camera.
If you launch "camera_mirror.launch", you will see two images-one from your camera, the other mirror of it.
15 changes: 15 additions & 0 deletions 20150422/launch/mirror_camera.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<launch>
<arg name="show_debug_image" default="true" />

<include file="$(find homework20150422)/launch/camera.launch" />

<node name="camera_mirror" pkg="homework20150422" type="mirror.py">
<remap from="image" to="camera/image_raw"/>
<remap from="debug_image" to="camera/debug_image" />
</node>

<node name="debug_image_viewer" pkg="image_view" type="image_view"
if="$(arg show_debug_image)">
<remap from="image" to="camera/debug_image" />
</node>
</launch>
20 changes: 14 additions & 6 deletions 20150422/scripts/face_detect_mono.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,15 @@

cascade_path = "/opt/ros/hydro/share/OpenCV/haarcascades/haarcascade_frontalface_alt2.xml"


#define class
class FaceDetectorMonoNode(object):
"""
This class has feature to subscribe "image" and detect people face,
then publishes those positions as geometry_msgs/Twist message.
"""

def __init__(self):
def __init__(self):#constructor
# make instance of object for image processing
try:
self.bridge = CvBridge()
Expand All @@ -33,10 +35,14 @@ def __init__(self):
rospy.logerr("Error: %s" % e)

# 4. subscribe "image" topic whose message type is sensor_msgs/Image
self.image_subscriber = rospy.Subscriber("image", Image, self.image_callback)
# this node subscribes "image" topic which is of type Image, and if the message is subscribed image_callback will invoked.
self.image_subscriber = rospy.Subscriber("image", Image, self.image_callback)#create subscriber object


# declare publishers
self.face_pose_publisher = rospy.Publisher("twist", Twist)
# this node is publishing to the "twist" topic using message type Twist.
self.face_pose_publisher = rospy.Publisher("twist", Twist)# create publisher objct
# this node is publishing to the "debug_image" topic using message type Image.
self.debug_image_publisher = rospy.Publisher("debug_image", Image)

# 5. define callback function for image topic
Expand Down Expand Up @@ -89,11 +95,13 @@ def image_callback(self, msg):
else:
rospy.loginfo("no face detected.")

if __name__ == '__main__':

#main function
if __name__ == '__main__':#他のプログラムで読み込む(importする)のでないとき、__name__='__main__'となる。つまり、実行されるとif=true
# 3. At first, we must set node name, and register to the master.
# In this case, node name is face_detector_mono
rospy.init_node("face_detector_mono")
face_detector = FaceDetectorMonoNode()
rospy.init_node("face_detector_mono")#set node of this program
face_detector = FaceDetectorMonoNode()#make instance of the class made above

# wait for message comming
rospy.spin()
57 changes: 57 additions & 0 deletions 20150422/scripts/mirror.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
#!/usr/bin/env python
# -*- coding: utf-8 -*-
# Author: Ryo KOYAMA <[email protected]>

# 1. import rospy to enable ROS feature of python
import rospy

# 2. import message files for python
# cf. you can find what contains in a message by executing `rosmsg show <msg>`
# e.g. rosmsg show sensor_msgs/Image
from sensor_msgs.msg import Image # This imports sensor_msgs/Image
from geometry_msgs.msg import Twist # This imports geometry_msgs/Twist

# Tips: This is special utility for converting between ROS Image message and OpenCV Image format.
from cv_bridge import CvBridge

import cv2 # this imports opencv python interface

class MIRROR(object):
"""
This class has feature to subscribe "image" and detect people face,
then publishes those positions as geometry_msgs/Twist message.
"""

def __init__(self):#constructor
# make instance of object for image processing
try:
self.bridge = CvBridge()
except Exception as e:
rospy.logerr("Error: %s" % e)

# 4. subscribe "image" topic whose message type is sensor_msgs/Image
self.image_subscriber = rospy.Subscriber("image", Image, self.image_callback)

# declare publishers
self.debug_image_publisher = rospy.Publisher("debug_image", Image)

# 5. define callback function for image topic
def image_callback(self, msg):
# 6. convert ROS sensor_msgs/Image to OpenCV format
img_mat = self.bridge.imgmsg_to_cv2(msg)

# 7. convert image to grey image
img_flip = cv2.flip(img_mat, 1)

# 12. publish debug image
pub_debug_img_msg = self.bridge.cv2_to_imgmsg(img_flip, encoding="bgr8")
self.debug_image_publisher.publish(pub_debug_img_msg)

if __name__ == '__main__':
# 3. At first, we must set node name, and register to the master.
# In this case, node name is face_detector_mono
rospy.init_node("monokuro_camera")
mirror = MIRROR()

# wait for message comming
rospy.spin()
Binary file added 20150624/gazebo-48156517.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added 20150624/rviz-48156517.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added 20150708/gazebo-48156517.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.