Skip to content
Merged
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
42 changes: 42 additions & 0 deletions tutorials/iturtle_facedetect/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
cmake_minimum_required(VERSION 2.8.3)
project(iturtle_facedetect)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
message_generation
rospy
std_msgs
)

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
CATKIN_DEPENDS message_runtime rospy std_msgs
)

#############
## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

catkin_install_python(PROGRAMS
src/facedetect.py
src/facedetect_listener.py
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
install(FILES
launch/facedetect.launch
src/haarcascade_frontalface_alt.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

26 changes: 26 additions & 0 deletions tutorials/iturtle_facedetect/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# iturtle_facedetect

Simple face detection ROS project based on OpenCV.

## build

```
$ cd catkin_ws
$ mkdir -p src
$ git clone https://github.com/oroca/iTurtle.git
$ cp -r iTurtle/tutorials/iturtle_iturtle_facedetect src/
$ catkin_make
$ cakkin_make install
```

## launch

```
$ source install/setup.bash
$ roscore
```

facedetect/facedetect listener node
```
$ roslaunch iturtle_facedetect facedetect.launch
```
6 changes: 6 additions & 0 deletions tutorials/iturtle_facedetect/launch/facedetect.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<launch>
<node name="facedetect" pkg="iturtle_facedetect" type="facedetect.py" output="screen"/>
<node name="facedetect_listener" pkg="iturtle_facedetect" type="facedetect_listener.py" output="screen">
<param name="hello" value="hello.m4a" />
</node>
</launch>
68 changes: 68 additions & 0 deletions tutorials/iturtle_facedetect/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
<?xml version="1.0"?>
<package format="2">
<name>iturtle_facedetect</name>
<version>0.1.0</version>
<description>The facedetect package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="[email protected]">Jane Doe</maintainer> -->
<maintainer email="[email protected]">Changju Lee</maintainer>


<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>MIT</license>


<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/iturtle_facedetect</url> -->


<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="[email protected]">Jane Doe</author> -->


<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>message_generation</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>

<exec_depend>message_generation</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>

<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->

</export>
</package>
71 changes: 71 additions & 0 deletions tutorials/iturtle_facedetect/src/facedetect.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
#!/usr/bin/env python
# -*- encoding: UTF-8 -*-
import rospy
from std_msgs.msg import String
from picamera.array import PiRGBArray
from picamera import PiCamera
import time
import cv2
import os


def face_detect():
rospy.init_node('facedetect', anonymous=True)
rate = rospy.Rate(10) # 10hz

pub = rospy.Publisher('facedetect', String, queue_size=10)

# initialize the camera and grab a reference to the raw camera capture
camera = PiCamera()
camera.resolution = (640, 480)
camera.framerate = 32
rawCapture = PiRGBArray(camera, size=(640, 480))

# allow the camera to warmup
time.sleep(0.1)

model_path = os.path.join(os.path.dirname(__file__), 'haarcascade_frontalface_alt.xml')
face_cascade = cv2.CascadeClassifier(model_path)

# capture frames from the camera
t1 = rospy.get_time()
for frame in camera.capture_continuous(rawCapture, format="bgr", use_video_port=True):
t2 = rospy.get_time()
#print("captured: %d" % (t2-t1))
if rospy.is_shutdown():
break

# grab the raw NumPy array representing the image, then initialize the timestamp
# and occupied/unoccupied text
image = frame.array
gray = cv2.cvtColor(image,cv2.COLOR_BGR2GRAY)

scaleFactor = 1.3
minNeighbors = 5
flags = 0
minSize = (150,150)
maxSize = (0,0)
faces = face_cascade.detectMultiScale(gray, scaleFactor, minNeighbors, flags, minSize)
if faces is not None and len(faces) > 0:
t3 = rospy.get_time()
rospy.loginfo('face detected: %s, captured=%s, detected=%s, total=%s' % (str(faces), t2 - t1, t3 - t2, t3 - t1))
pub.publish(str(faces))

# for (x,y,w,h) in faces:
# cv2.rectangle(image,(x,y),(x+w,y+h),(255,0,0),2)
# # show the frame
# cv2.imshow("Frame", image)

# clear the stream in preparation for the next frame
rawCapture.truncate(0)

rate.sleep()
t1 = rospy.get_time()


if __name__ == '__main__':
try:
face_detect()
except rospy.ROSInterruptException:
pass

34 changes: 34 additions & 0 deletions tutorials/iturtle_facedetect/src/facedetect_listener.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
#!/usr/bin/env python
# -*- encoding: UTF-8 -*-
import os
import rospy
from std_msgs.msg import String

pub = None
hello = None

def facedetect_callback(data):
rospy.loginfo(rospy.get_caller_id() + ': face detect received: %s', data.data)
pub.publish(hello)


def listener():
global pub
global hello

# In ROS, nodes are uniquely named. If two nodes with the same
# name are launched, the previous one is kicked off. The
# anonymous=True flag means that rospy will choose a unique
# name for our 'listener' node so that multiple listeners can
# run simultaneously.
rospy.init_node('facedetect_listener', anonymous=True)
pub = rospy.Publisher('/play_sound_file', String, queue_size=10)
hello = rospy.get_param('~hello', 'hello.m4a')
print('param: hello=%s' % hello)

rospy.Subscriber('/facedetect', String, facedetect_callback)
# spin() simply keeps python from exiting until this node is stopped
rospy.spin()

if __name__ == '__main__':
listener()
Loading