Index: /trunk/saliency_detection/CMakeLists.txt
===================================================================
--- /trunk/saliency_detection/CMakeLists.txt	(revision 10)
+++ /trunk/saliency_detection/CMakeLists.txt	(revision 10)
@@ -0,0 +1,40 @@
+cmake_minimum_required(VERSION 2.4.6)
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+
+# Set the build type.  Options are:
+#  Coverage       : w/ debug symbols, w/o optimization, w/ code-coverage
+#  Debug          : w/ debug symbols, w/o optimization
+#  Release        : w/o debug symbols, w/ optimization
+#  RelWithDebInfo : w/ debug symbols, w/ optimization
+#  MinSizeRel     : w/o debug symbols, w/ optimization, stripped binaries
+#set(ROS_BUILD_TYPE RelWithDebInfo)
+
+rosbuild_init()
+
+#set the default path for built executables to the "bin" directory
+set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set the default path for built libraries to the "lib" directory
+set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+
+#uncomment if you have defined messages
+#rosbuild_genmsg()
+#uncomment if you have defined services
+#rosbuild_gensrv()
+
+#common commands for building c++ executables and libraries
+#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
+#target_link_libraries(${PROJECT_NAME} another_library)
+#rosbuild_add_boost_directories()
+#rosbuild_link_boost(${PROJECT_NAME} thread)
+#rosbuild_add_executable(example examples/example.cpp)
+#target_link_libraries(example ${PROJECT_NAME})
+
+rosbuild_add_library(cvgabor src/cvgabor.cpp)
+
+rosbuild_add_executable(saliencyDetectionHou src/saliencyDetectionHou.cpp)
+rosbuild_add_executable(saliencyDetectionRudinac src/saliencyDetectionRudinac.cpp)
+rosbuild_add_executable(saliencyDetectionItti src/saliencyDetectionItti.cpp)
+
+target_link_libraries(saliencyDetectionItti cvgabor)
+
+
Index: /trunk/saliency_detection/Makefile
===================================================================
--- /trunk/saliency_detection/Makefile	(revision 10)
+++ /trunk/saliency_detection/Makefile	(revision 10)
@@ -0,0 +1,1 @@
+include $(shell rospack find mk)/cmake.mk
Index: /trunk/saliency_detection/include/saliency_detection/cvgabor.h
===================================================================
--- /trunk/saliency_detection/include/saliency_detection/cvgabor.h	(revision 10)
+++ /trunk/saliency_detection/include/saliency_detection/cvgabor.h	(revision 10)
@@ -0,0 +1,81 @@
+/***************************************************************************
+ *   Copyright (C) 2006 by Mian Zhou   *
+ *   M.Zhou@reading.ac.uk   *
+ *                                                                         *
+ *   This program is free software; you can redistribute it and/or modify  *
+ *   it under the terms of the GNU General Public License as published by  *
+ *   the Free Software Foundation; either version 2 of the License, or     *
+ *   (at your option) any later version.                                   *
+ *                                                                         *
+ *   This program is distributed in the hope that it will be useful,       *
+ *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
+ *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
+ *   GNU General Public License for more details.                          *
+ *                                                                         *
+ *   You should have received a copy of the GNU General Public License     *
+ *   along with this program; if not, write to the                         *
+ *   Free Software Foundation, Inc.,                                       *
+ *   59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.             *
+ ***************************************************************************/
+#ifndef CVGABOR_H
+#define CVGABOR_H
+
+#include <iostream>
+
+
+#include <cv.h>
+#include <highgui.h>
+using namespace std;
+
+#define PI 3.14159265
+#define FALSE 0
+#define TRUE 1
+#define CV_GABOR_REAL 1
+#define CV_GABOR_IMAG 2
+#define CV_GABOR_MAG  3
+#define CV_GABOR_PHASE 4
+
+/**
+@author Mian Zhou
+*/
+class CvGabor{
+public:
+    CvGabor();
+
+    ~CvGabor();
+
+     CvGabor(int iMu, int iNu);
+     CvGabor(int iMu, int iNu, float dSigma);
+     CvGabor(int iMu, int iNu, float dSigma, float dF);
+     CvGabor(float dPhi, int iNu);
+     CvGabor(float dPhi, int iNu, float dSigma);
+     CvGabor(float dPhi, int iNu, float dSigma, float dF);
+    bool IsInit();
+    long mask_width();
+    IplImage* get_image(int Type);
+    bool IsKernelCreate();
+    long get_mask_width();
+    void Init(int iMu, int iNu, double dSigma, double dF);
+    void Init(double dPhi, int iNu, double dSigma, double dF);
+    void output_file(const char *filename, int Type);
+    CvMat* get_matrix(int Type);
+    void show(int Type);
+    void conv_img(IplImage *src, IplImage *dst, int Type);
+
+protected:
+    float Sigma;
+    float F;
+    float Kmax;
+    float K;
+    float Phi;
+    bool bInitialised;
+    bool bKernel;
+    long Width;
+    CvMat *Imag;
+    CvMat *Real;
+private:
+    void creat_kernel();
+
+};
+
+#endif
Index: /trunk/saliency_detection/include/saliency_detection/saliencyDetectionHou.h
===================================================================
--- /trunk/saliency_detection/include/saliency_detection/saliencyDetectionHou.h	(revision 10)
+++ /trunk/saliency_detection/include/saliency_detection/saliencyDetectionHou.h	(revision 10)
@@ -0,0 +1,55 @@
+//===================================================================================
+// Name        : saliencyDetectionHou.h
+// Author      : Oytun Akman, oytunakman@gmail.com
+// Version     : 1.0
+// Copyright   : Copyright (c) 2010 LGPL
+// Description : C++ implementation of "Saliency Detection: A Spectral Residual 
+//				 Approach" by Xiaodi Hou and Liqing Zhang (CVPR 2007).												  
+//===================================================================================
+
+#ifndef _SALIENCYMAPHOU_H_INCLUDED_
+#define _SALIENCYMAPHOU_H_INCLUDED_
+
+// ROS
+#include <ros/ros.h>
+#include "image_transport/image_transport.h"
+#include <cv_bridge/cv_bridge.h>
+#include <sensor_msgs/image_encodings.h>
+#include <sensor_msgs/fill_image.h>
+#include <geometry_msgs/Point.h>
+
+// OpenCV
+#include "cv.h"
+#include "opencv2/highgui/highgui.hpp"
+
+using namespace cv;
+using namespace std;
+namespace enc = sensor_msgs::image_encodings;
+
+class saliencyMapHou
+{
+protected:
+    	ros::NodeHandle nh_;
+    	ros::Publisher point_pub_;
+    	image_transport::ImageTransport it_;
+    	image_transport::Subscriber 	image_sub_;
+    	image_transport::Publisher		saliencymap_pub_;
+
+public:
+    	saliencyMapHou() : nh_("~"), it_(nh_)
+    	{
+    		image_sub_ = it_.subscribe("/rgbimage_in", 1, &saliencyMapHou::imageCB, this);
+    		saliencymap_pub_= it_.advertise("/saliency/image", 1);
+    		point_pub_ = nh_.advertise<geometry_msgs::Point>("/saliency/salientpoint", 1);
+    	}
+
+
+    	~saliencyMapHou()
+    	{
+    		nh_.shutdown();
+    	}
+
+    	void imageCB(const sensor_msgs::ImageConstPtr& msg_ptr);
+    	void calculateSaliencyMap(const Mat* src, Mat* dst);
+};
+#endif
Index: /trunk/saliency_detection/include/saliency_detection/saliencyDetectionItti.h
===================================================================
--- /trunk/saliency_detection/include/saliency_detection/saliencyDetectionItti.h	(revision 10)
+++ /trunk/saliency_detection/include/saliency_detection/saliencyDetectionItti.h	(revision 10)
@@ -0,0 +1,88 @@
+//===================================================================================
+// Name        : saliencyDetectionItti.h
+// Author      : Oytun Akman, oytunakman@gmail.com
+// Version     : 1.0
+// Copyright   : Copyright (c) 2010 LGPL
+// Description : C++ implementation of "A Model of Saliency-Based Visual Attention
+//				 for Rapid Scene Analysis" by Laurent Itti, Christof Koch and Ernst
+//				 Niebur (PAMI 1998).												  
+//===================================================================================
+
+#ifndef _SALIENCYMAPITTI_H_INCLUDED_
+#define _SALIENCYMAPITTI_H_INCLUDED_
+// ROS
+#include <ros/ros.h>
+#include "image_transport/image_transport.h"
+#include <cv_bridge/cv_bridge.h>
+#include <sensor_msgs/image_encodings.h>
+#include <sensor_msgs/fill_image.h>
+#include <geometry_msgs/Point.h>
+
+// OpenCV
+#include "cv.h"
+#include "opencv2/highgui/highgui.hpp"
+
+using namespace cv;
+using namespace std;
+namespace enc = sensor_msgs::image_encodings;
+
+class saliencyMapItti
+{
+protected:
+    	ros::NodeHandle nh_;
+    	ros::Publisher point_pub_;
+    	image_transport::ImageTransport it_;
+    	image_transport::Subscriber 	image_sub_;
+    	image_transport::Publisher		saliencymap_pub_;
+
+public:
+    	saliencyMapItti() : nh_("~"), it_(nh_)
+    	{
+    		image_sub_ = it_.subscribe("/rgbimage_in", 1, &saliencyMapItti::imageCB, this);
+    		saliencymap_pub_= it_.advertise("/saliency/image", 1);
+    		point_pub_ = nh_.advertise<geometry_msgs::Point>("/saliency/salientpoint", 1);
+    	}
+
+
+    	~saliencyMapItti()
+    	{
+    		nh_.shutdown();
+    	}
+
+    	void imageCB(const sensor_msgs::ImageConstPtr& msg_ptr);
+    	void calculateSaliencyMap(const Mat* src, Mat* dst, int scaleBase);
+    	void combineFeatureMaps(int scale);
+
+    	Mat conspicuityMap_I;
+    	Mat conspicuityMap_C;
+    	Mat conspicuityMap_O;
+    	Mat S;
+
+private:
+    	Mat r,g,b,R,G,B,Y,I;
+    	vector<Mat> gaussianPyramid_I;
+    	vector<Mat> gaussianPyramid_R;
+    	vector<Mat> gaussianPyramid_G;
+    	vector<Mat> gaussianPyramid_B;
+    	vector<Mat> gaussianPyramid_Y;
+
+    	void createChannels(const Mat* src);
+    	void createScaleSpace(const Mat* src, vector<Mat>* dst, int scale);
+
+    	void normalize_rgb();
+    	void create_RGBY();
+    	void createIntensityFeatureMaps();
+    	void createColorFeatureMaps();
+    	void createOrientationFeatureMaps(int orientation);
+    	void mapNormalization(Mat* src);
+    	void clearBuffers();
+
+    	vector<Mat> featureMaps_I;
+    	vector<Mat> featureMaps_RG;
+    	vector<Mat> featureMaps_BY;
+    	vector<Mat> featureMaps_0;
+    	vector<Mat> featureMaps_45;
+    	vector<Mat> featureMaps_90;
+    	vector<Mat> featureMaps_135;
+};
+#endif
Index: /trunk/saliency_detection/include/saliency_detection/saliencyDetectionRudinac.h
===================================================================
--- /trunk/saliency_detection/include/saliency_detection/saliencyDetectionRudinac.h	(revision 10)
+++ /trunk/saliency_detection/include/saliency_detection/saliencyDetectionRudinac.h	(revision 10)
@@ -0,0 +1,61 @@
+//===================================================================================
+// Name        : saliencyDetectionRudinac.h
+// Author      : Joris van de Weem, joris.vdweem@gmail.com
+// Version     : 1.0
+// Copyright   : Copyright (c) 2010 LGPL
+// Description : C++ implementation of "Maja Rudinac, Pieter P. Jonker. 
+// 				"Saliency Detection and Object Localization in Indoor Environments". 
+//				ICPR'2010. pp.404~407											  
+//===================================================================================
+
+#ifndef _SALIENCYMAPRUDINAC_H_INCLUDED_
+#define _SALIENCYMAPRUDINAC_H_INCLUDED_
+
+// ROS
+#include <ros/ros.h>
+#include "image_transport/image_transport.h"
+#include <cv_bridge/cv_bridge.h>
+#include <sensor_msgs/image_encodings.h>
+#include <sensor_msgs/fill_image.h>
+#include <geometry_msgs/Point.h>
+
+// OpenCV
+#include "cv.h"
+#include "opencv2/highgui/highgui.hpp"
+
+using namespace cv;
+using namespace std;
+namespace enc = sensor_msgs::image_encodings;
+
+class saliencyMapRudinac
+{
+protected:
+    	ros::NodeHandle nh_;
+    	ros::Publisher point_pub_;
+    	image_transport::ImageTransport it_;
+    	image_transport::Subscriber 	image_sub_;
+    	image_transport::Publisher		saliencymap_pub_;
+
+
+public:
+    	saliencyMapRudinac() : nh_("~"), it_(nh_)
+    	{
+    		image_sub_ = it_.subscribe("/rgbimage_in", 1, &saliencyMapRudinac::imageCB, this);
+    		saliencymap_pub_= it_.advertise("/saliency/image", 1);
+    		point_pub_ = nh_.advertise<geometry_msgs::Point>("/saliency/salientpoint", 1);
+    	}
+
+    	~saliencyMapRudinac()
+    	{
+    		nh_.shutdown();
+    	}
+
+    	void imageCB(const sensor_msgs::ImageConstPtr& msg_ptr);
+    	void calculateSaliencyMap(const Mat* src, Mat* dst);
+
+private:
+    	Mat r,g,b,RG,BY,I;
+    	void createChannels(const Mat* src);
+    	void createSaliencyMap(const Mat src, Mat* dst);
+};
+#endif
Index: /trunk/saliency_detection/launch/saliency_detection.launch
===================================================================
--- /trunk/saliency_detection/launch/saliency_detection.launch	(revision 10)
+++ /trunk/saliency_detection/launch/saliency_detection.launch	(revision 10)
@@ -0,0 +1,14 @@
+<launch>
+	<arg name="kinect" value="false" />
+	<arg name="algorithm" value="Itti" /> <!-- Options: Rudinac / Itti / Hou / Achanta -->
+
+	<!-- Select camera stream -->
+   	<arg if="$(arg kinect)"  name="imagestream" value="/camera/rgb/image_color" type="str" />
+   	<arg unless="$(arg kinect)" name="imagestream" value="/image_raw" type="str" />
+      
+	<node name="saliencymap$(arg algorithm)" pkg="saliency_detection" type="saliencyDetection$(arg algorithm)" output="screen">  
+		<remap from="/rgbimage_in" to="$(arg imagestream)" />
+      	<remap from="/saliency/image" to="/saliency/image" />
+	</node>
+</launch>
+
Index: /trunk/saliency_detection/mainpage.dox
===================================================================
--- /trunk/saliency_detection/mainpage.dox	(revision 10)
+++ /trunk/saliency_detection/mainpage.dox	(revision 10)
@@ -0,0 +1,26 @@
+/**
+\mainpage
+\htmlinclude manifest.html
+
+\b saliencymaps is ... 
+
+<!-- 
+Provide an overview of your package.
+-->
+
+
+\section codeapi Code API
+
+<!--
+Provide links to specific auto-generated API documentation within your
+package that is of particular interest to a reader. Doxygen will
+document pretty much every part of your code, so do your best here to
+point the reader to the actual API.
+
+If your codebase is fairly large or has different sets of APIs, you
+should use the doxygen 'group' tag to keep these APIs together. For
+example, the roscpp documentation has 'libros' group.
+-->
+
+
+*/
Index: /trunk/saliency_detection/manifest.xml
===================================================================
--- /trunk/saliency_detection/manifest.xml	(revision 10)
+++ /trunk/saliency_detection/manifest.xml	(revision 10)
@@ -0,0 +1,16 @@
+<package>
+  <description brief="saliency_detection">
+	Create saliency maps using one of the following algorithms:
+	Hou
+	Itti
+	Rudinac
+  </description>
+  <author>Joris van de Weem</author>
+  <license>GPL</license>
+  <review status="unreviewed" notes=""/>
+  <url>http://ros.org/wiki/saliency_detection</url>
+  <depend package="sensor_msgs"/>
+  <depend package="cv_bridge"/>
+  <depend package="roscpp"/>
+  <depend package="image_transport"/>
+</package>
Index: /trunk/saliency_detection/src/cvgabor.cpp
===================================================================
--- /trunk/saliency_detection/src/cvgabor.cpp	(revision 10)
+++ /trunk/saliency_detection/src/cvgabor.cpp	(revision 10)
@@ -0,0 +1,651 @@
+/***************************************************************************
+ *   Copyright (C) 2006 by Mian Zhou   *
+ *   M.Zhou@reading.ac.uk   *
+ *                                                                         *
+ *   This program is free software; you can redistribute it and/or modify  *
+ *   it under the terms of the GNU General Public License as published by  *
+ *   the Free Software Foundation; either version 2 of the License, or     *
+ *   (at your option) any later version.                                   *
+ *                                                                         *
+ *   This program is distributed in the hope that it will be useful,       *
+ *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
+ *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
+ *   GNU General Public License for more details.                          *
+ *                                                                         *
+ *   You should have received a copy of the GNU General Public License     *
+ *   along with this program; if not, write to the                         *
+ *   Free Software Foundation, Inc.,                                       *
+ *   59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.             *
+ ***************************************************************************/
+#include <saliency_detection/cvgabor.h>
+
+#undef DEBUG
+//#define DEBUG
+CvGabor::CvGabor()
+{
+}
+
+
+CvGabor::~CvGabor()
+{
+cvReleaseMat( &Real );
+cvReleaseMat( &Imag );
+}
+
+
+/*!
+    \fn CvGabor::CvGabor(int iMu, int iNu)
+Construct a gabor
+
+Parameters:
+    	iMu		The orientation iMu*PI/8,
+    	iNu 		The scale,
+
+Returns:
+	None,
+
+Create a gabor with a orientation iMu*PI/8, and with a scale iNu. The sigma (Sigma) and the spatial frequence (F) are set to 2*PI and sqrt(2) defaultly. It calls Init() to generate parameters and kernels.
+ */
+ CvGabor::CvGabor(int iMu, int iNu)
+{
+    //Initilise the parameters 
+    
+    Sigma = 2*PI;
+    F = sqrt(2.0);
+    Init(iMu, iNu, Sigma, F);
+    
+}
+
+/*!
+    \fn CvGabor::CvGabor(int iMu, int iNu, double dSigma)
+Construct a gabor
+
+Parameters:
+    	iMu		The orientation iMu*PI/8,
+    	iNu 		The scale,
+	dSigma 		The sigma value of Gabor,
+
+Returns:
+	None
+
+Create a gabor with a orientation iMu*PI/8, a scale iNu, and a sigma value dSigma. The spatial frequence (F) is set to sqrt(2) defaultly. It calls Init() to generate parameters and kernels.
+ */
+CvGabor::CvGabor(int iMu, int iNu, float dSigma)
+{ 
+    F = sqrt(2.0);
+    Init(iMu, iNu, dSigma, F);
+}
+
+
+/*!
+    \fn CvGabor::CvGabor(int iMu, int iNu, double dSigma, double dF)
+Construct a gabor
+
+Parameters:
+    	iMu		The orientation iMu*PI/8
+    	iNu 		The scale
+	dSigma 		The sigma value of Gabor
+	dF		The spatial frequency 
+
+Returns:
+	None
+
+Create a gabor with a orientation iMu*PI/8, a scale iNu, a sigma value dSigma, and a spatial frequence dF. It calls Init() to generate parameters and kernels.
+ */
+ CvGabor::CvGabor(int iMu, int iNu, float dSigma, float dF)
+{
+
+    Init(iMu, iNu, dSigma, dF);
+    
+}
+
+
+/*!
+    \fn CvGabor::CvGabor(double dPhi, int iNu)
+Construct a gabor
+
+Parameters:
+    	dPhi		The orientation in arc
+    	iNu 		The scale
+
+Returns:
+	None
+
+Create a gabor with a orientation dPhi, and with a scale iNu. The sigma (Sigma) and the spatial frequence (F) are set to 2*PI and sqrt(2) defaultly. It calls Init() to generate parameters and kernels.
+ */
+ CvGabor::CvGabor(float dPhi, int iNu)
+{
+
+    Sigma = 2*PI;
+    F = sqrt(2.0);
+    Init(dPhi, iNu, Sigma, F);
+}
+
+
+/*!
+    \fn CvGabor::CvGabor(double dPhi, int iNu, double dSigma)
+Construct a gabor
+
+Parameters:
+    	dPhi		The orientation in arc
+    	iNu 		The scale
+	dSigma		The sigma value of Gabor
+
+Returns:
+	None
+    
+Create a gabor with a orientation dPhi, a scale iNu, and a sigma value dSigma. The spatial frequence (F) is set to sqrt(2) defaultly. It calls Init() to generate parameters and kernels.
+ */
+ CvGabor::CvGabor(float dPhi, int iNu, float dSigma)
+{
+
+    F = sqrt(2.0);
+    Init(dPhi, iNu, dSigma, F);
+}
+
+
+/*!
+    \fn CvGabor::CvGabor(double dPhi, int iNu, double dSigma, double dF)
+Construct a gabor
+
+Parameters:
+    	dPhi		The orientation in arc
+    	iNu 		The scale
+	dSigma 		The sigma value of Gabor
+	dF		The spatial frequency 
+
+Returns:
+	None
+
+Create a gabor with a orientation dPhi, a scale iNu, a sigma value dSigma, and a spatial frequence dF. It calls Init() to generate parameters and kernels.
+ */
+ CvGabor::CvGabor(float dPhi, int iNu, float dSigma, float dF)
+{
+
+   Init(dPhi, iNu, dSigma,dF);
+}
+
+/*!
+    \fn CvGabor::IsInit()
+Determine the gabor is initilised or not
+
+Parameters:
+	None
+
+Returns:
+	a boolean value, TRUE is initilised or FALSE is non-initilised.
+
+Determine whether the gabor has been initlized - variables F, K, Kmax, Phi, Sigma are filled.
+ */
+bool CvGabor::IsInit()
+{
+
+    return bInitialised;
+}
+
+/*!
+    \fn CvGabor::mask_width()
+Give out the width of the mask
+
+Parameters:
+	None
+
+Returns:
+	The long type show the width.
+
+Return the width of mask (should be NxN) by the value of Sigma and iNu.
+ */
+long CvGabor::mask_width()
+{
+
+    long lWidth;
+    if (IsInit() == FALSE)  {
+       perror ("Error: The Object has not been initilised in mask_width()!\n");
+       return 0;
+    }
+    else {
+       //determine the width of Mask
+      float dModSigma = Sigma/K;
+      float dWidth = cvRound(dModSigma*6 + 1);
+      //test whether dWidth is an odd.
+      if (fmod(dWidth, (float)2.0)==0.0) dWidth++;
+      lWidth = (long)dWidth;
+
+      return lWidth;
+    }
+}
+
+
+/*!
+    \fn CvGabor::creat_kernel()
+Create gabor kernel
+
+Parameters:
+	None
+
+Returns:
+	None
+
+Create 2 gabor kernels - REAL and IMAG, with an orientation and a scale 
+ */
+void CvGabor::creat_kernel()
+{
+    
+    if (IsInit() == FALSE) {perror("Error: The Object has not been initilised in creat_kernel()!\n");}
+    else {
+      CvMat *mReal, *mImag;
+      mReal = cvCreateMat( Width, Width, CV_32FC1);
+      mImag = cvCreateMat( Width, Width, CV_32FC1);
+      
+      /**************************** Gabor Function ****************************/ 
+      int x, y;
+      float dReal;
+      float dImag;
+      float dTemp1, dTemp2, dTemp3;
+
+      for (int i = 0; i < Width; i++)
+      {
+          for (int j = 0; j < Width; j++)
+          {
+              x = i-(Width-1)/2;
+              y = j-(Width-1)/2;
+              dTemp1 = (pow(K,2)/pow(Sigma,2))*exp(-(pow((float)x,2)+pow((float)y,2))*pow(K,2)/(2*pow(Sigma,2)));
+              dTemp2 = cos(K*cos(Phi)*x + K*sin(Phi)*y) - exp(-(pow(Sigma,2)/2));
+              dTemp3 = sin(K*cos(Phi)*x + K*sin(Phi)*y);
+              dReal = dTemp1*dTemp2;
+              dImag = dTemp1*dTemp3; 
+              //gan_mat_set_el(pmReal, i, j, dReal);
+	      cvmSet( (CvMat*)mReal, i, j, dReal );
+              //gan_mat_set_el(pmImag, i, j, dImag);
+              cvmSet( (CvMat*)mImag, i, j, dImag );
+
+          } 
+       }
+       /**************************** Gabor Function ****************************/
+       bKernel = TRUE;
+       cvCopy(mReal, Real, NULL);
+       cvCopy(mImag, Imag, NULL);
+       #ifdef DEBUG
+       printf("A %d x %d Gabor kernel with %f PI in arc is created.\n", Width, Width, Phi/PI);
+       #endif
+       cvReleaseMat( &mReal );
+       cvReleaseMat( &mImag );
+     }
+}
+
+
+/*!
+    \fn CvGabor::get_image(int Type)
+Get the speific type of image of Gabor
+
+Parameters:
+	Type		The Type of gabor kernel, e.g. REAL, IMAG, MAG, PHASE   
+
+Returns:
+	Pointer to image structure, or NULL on failure	
+
+Return an Image (gandalf image class) with a specific Type   "REAL"	"IMAG" "MAG" "PHASE"  
+ */
+IplImage* CvGabor::get_image(int Type)
+{
+
+    if(IsKernelCreate() == FALSE)
+    { 
+      perror("Error: the Gabor kernel has not been created in get_image()!\n");
+      return NULL;
+    }
+    else
+    {  
+    IplImage* pImage;
+    IplImage *newimage;
+    newimage = cvCreateImage(cvSize(Width,Width), IPL_DEPTH_8U, 1 );
+    //printf("Width is %d.\n",(int)Width);
+    //printf("Sigma is %f.\n", Sigma);
+    //printf("F is %f.\n", F);
+    //printf("Phi is %f.\n", Phi);
+    
+    //pImage = gan_image_alloc_gl_d(Width, Width);
+    pImage = cvCreateImage( cvSize(Width,Width), IPL_DEPTH_32F, 1 );
+    
+    
+    CvMat* kernel = cvCreateMat(Width, Width, CV_32FC1);
+    double ve;
+    CvScalar S;
+    switch(Type)
+    {
+        case 1:  //Real
+
+           cvCopy( (CvMat*)Real, (CvMat*)kernel, NULL );
+            //pImage = cvGetImage( (CvMat*)kernel, pImageGL );
+           for (int i = 0; i < kernel->rows; i++)
+    	   {
+              for (int j = 0; j < kernel->cols; j++)
+              {
+                   ve = cvGetReal2D((CvMat*)kernel, i, j);
+                   cvSetReal2D( (IplImage*)pImage, j, i, ve );
+              }
+           }
+           break;
+        case 2:  //Imag
+           cvCopy( (CvMat*)Imag, (CvMat*)kernel, NULL );
+           //pImage = cvGetImage( (CvMat*)kernel, pImageGL );
+           for (int i = 0; i < kernel->rows; i++)
+    	   {
+              for (int j = 0; j < kernel->cols; j++)
+              {
+                   ve = cvGetReal2D((CvMat*)kernel, i, j);
+                   cvSetReal2D( (IplImage*)pImage, j, i, ve );
+              }
+           }
+           break; 
+        case 3:  //Magnitude
+           ///@todo  
+           break;
+        case 4:  //Phase
+          ///@todo
+           break;
+    }
+   
+    cvNormalize((IplImage*)pImage, (IplImage*)pImage, 0, 255, CV_MINMAX, NULL );
+
+
+    cvConvertScaleAbs( (IplImage*)pImage, (IplImage*)newimage, 1, 0 );
+
+    cvReleaseMat(&kernel);
+
+    cvReleaseImage(&pImage);
+
+    return newimage;
+    }
+}
+
+
+/*!
+    \fn CvGabor::IsKernelCreate()
+Determine the gabor kernel is created or not
+
+Parameters:
+	None
+
+Returns:
+	a boolean value, TRUE is created or FALSE is non-created.
+
+Determine whether a gabor kernel is created.
+ */
+bool CvGabor::IsKernelCreate()
+{
+
+    return bKernel;
+}
+
+
+/*!
+    \fn CvGabor::get_mask_width()
+Reads the width of Mask
+
+Parameters:
+    None
+
+Returns:
+    Pointer to long type width of mask.
+ */
+long CvGabor::get_mask_width()
+{
+  return Width;
+}
+
+
+/*!
+    \fn CvGabor::Init(int iMu, int iNu, double dSigma, double dF)
+Initilize the.gabor
+
+Parameters:
+    	iMu 	The orientations which is iMu*PI.8
+    	iNu 	The scale can be from -5 to infinit
+    	dSigma 	The Sigma value of gabor, Normally set to 2*PI
+    	dF 	The spatial frequence , normally is sqrt(2)
+
+Returns:
+
+Initilize the.gabor with the orientation iMu, the scale iNu, the sigma dSigma, the frequency dF, it will call the function creat_kernel(); So a gabor is created.
+ */
+void CvGabor::Init(int iMu, int iNu, double dSigma, double dF)
+{
+  //Initilise the parameters 
+    bInitialised = FALSE;
+    bKernel = FALSE;
+
+    Sigma = dSigma;
+    F = dF;
+    
+    Kmax = PI/2;
+    
+    // Absolute value of K
+    K = Kmax / pow(F, (float)iNu);
+    Phi = PI*iMu/8;
+    bInitialised = TRUE;
+    Width = mask_width();
+    Real = cvCreateMat( Width, Width, CV_32FC1);
+    Imag = cvCreateMat( Width, Width, CV_32FC1);
+    creat_kernel();
+}
+
+
+/*!
+    \fn CvGabor::Init(double dPhi, int iNu, double dSigma, double dF)
+Initilize the.gabor
+
+Parameters:
+    	dPhi 	The orientations 
+    	iNu 	The scale can be from -5 to infinit
+    	dSigma 	The Sigma value of gabor, Normally set to 2*PI
+    	dF 	The spatial frequence , normally is sqrt(2)
+
+Returns:
+	None
+
+Initilize the.gabor with the orientation dPhi, the scale iNu, the sigma dSigma, the frequency dF, it will call the function creat_kernel(); So a gabor is created.filename 	The name of the image file
+    	file_format 	The format of the file, e.g. GAN_PNG_FORMAT
+    	image 	The image structure to be written to the file
+    	octrlstr 	Format-dependent control structure
+
+ */
+void CvGabor::Init(double dPhi, int iNu, double dSigma, double dF)
+{
+
+    bInitialised = FALSE;
+    bKernel = FALSE;
+    Sigma = dSigma;
+    F = dF;
+    
+    Kmax = PI/2;
+    
+    // Absolute value of K
+    K = Kmax / pow(F, (float)iNu);
+    Phi = dPhi;
+    bInitialised = TRUE;
+    Width = mask_width();
+    Real = cvCreateMat( Width, Width, CV_32FC1);
+    Imag = cvCreateMat( Width, Width, CV_32FC1);
+    creat_kernel();
+}
+
+
+
+/*!
+    \fn CvGabor::get_matrix(int Type)
+Get a matrix by the type of kernel
+
+Parameters:
+    	Type		The type of kernel, e.g. REAL, IMAG, MAG, PHASE
+
+Returns:
+    	Pointer to matrix structure, or NULL on failure.
+
+Return the gabor kernel.
+ */
+CvMat* CvGabor::get_matrix(int Type)
+{
+    if (!IsKernelCreate()) {perror("Error: the gabor kernel has not been created!\n"); return NULL;}
+    switch (Type)
+    {
+      case CV_GABOR_REAL:
+        return Real;
+        break;
+      case CV_GABOR_IMAG:
+        return Imag;
+        break;
+      case CV_GABOR_MAG:
+        return NULL;
+        break;
+      case CV_GABOR_PHASE:
+        return NULL;
+        break;
+    }
+}
+
+
+
+
+/*!
+    \fn CvGabor::output_file(const char *filename, Gan_ImageFileFormat file_format, int Type)
+Writes a gabor kernel as an image file.
+
+Parameters:
+    	filename 	The name of the image file
+    	file_format 	The format of the file, e.g. GAN_PNG_FORMAT
+    	Type		The Type of gabor kernel, e.g. REAL, IMAG, MAG, PHASE   
+Returns:
+	None
+
+Writes an image from the provided image structure into the given file and the type of gabor kernel.
+ */
+void CvGabor::output_file(const char *filename, int Type)
+{
+  IplImage *pImage;
+  pImage = get_image(Type);
+  if(pImage != NULL)
+  {
+    if( cvSaveImage(filename, pImage )) printf("%s has been written successfully!\n", filename);
+    else printf("Error: writting %s has failed!\n", filename);
+  }
+  else 
+    perror("Error: the image is empty in output_file()!\n"); 
+
+  cvReleaseImage(&pImage);
+}
+
+
+
+
+
+
+/*!
+    \fn CvGabor::show(int Type)
+ */
+void CvGabor::show(int Type)
+{
+    if(!IsInit()) {
+        perror("Error: the gabor kernel has not been created!\n");
+    }
+    else {
+    IplImage *pImage;
+    pImage = get_image(Type);
+    cvNamedWindow("Testing",1);
+    cvShowImage("Testing",pImage);
+    cvWaitKey(0);
+    cvDestroyWindow("Testing");
+    cvReleaseImage(&pImage);
+    }
+
+}
+
+
+
+
+/*!
+    \fn CvGabor::conv_img(IplImage *src, IplImage *dst, int Type)
+ */
+void CvGabor::conv_img(IplImage *src, IplImage *dst, int Type)
+{
+    double ve, re,im;
+
+    CvMat *mat = cvCreateMat(src->width, src->height, CV_32FC1);
+    for (int i = 0; i < src->width; i++)
+    {
+       for (int j = 0; j < src->height; j++)
+       {
+              ve = cvGetReal2D((IplImage*)src, j, i);
+              cvSetReal2D( (CvMat*)mat, i, j, ve );
+       }
+    }
+
+    CvMat *rmat = cvCreateMat(src->width, src->height, CV_32FC1);
+    CvMat *imat = cvCreateMat(src->width, src->height, CV_32FC1);
+
+    CvMat *kernel = cvCreateMat( Width, Width, CV_32FC1 );
+
+    switch (Type)
+    {
+      case CV_GABOR_REAL:
+        cvCopy( (CvMat*)Real, (CvMat*)kernel, NULL );
+        cvFilter2D( (CvMat*)mat, (CvMat*)mat, (CvMat*)kernel, cvPoint( (Width-1)/2, (Width-1)/2));
+        break;
+      case CV_GABOR_IMAG:
+        cvCopy( (CvMat*)Imag, (CvMat*)kernel, NULL );
+        cvFilter2D( (CvMat*)mat, (CvMat*)mat, (CvMat*)kernel, cvPoint( (Width-1)/2, (Width-1)/2));
+        break;
+      case CV_GABOR_MAG:
+        /* Real Response */
+        cvCopy( (CvMat*)Real, (CvMat*)kernel, NULL );
+        cvFilter2D( (CvMat*)mat, (CvMat*)rmat, (CvMat*)kernel, cvPoint( (Width-1)/2, (Width-1)/2));
+        /* Imag Response */
+        cvCopy( (CvMat*)Imag, (CvMat*)kernel, NULL );
+        cvFilter2D( (CvMat*)mat, (CvMat*)imat, (CvMat*)kernel, cvPoint( (Width-1)/2, (Width-1)/2));
+        /* Magnitude response is the square root of the sum of the square of real response and imaginary response */
+        for (int i = 0; i < mat->rows; i++)
+        {
+           for (int j = 0; j < mat->cols; j++)
+           {
+               re = cvGetReal2D((CvMat*)rmat, i, j);
+               im = cvGetReal2D((CvMat*)imat, i, j);
+               ve = sqrt(re*re + im*im);
+               cvSetReal2D( (CvMat*)mat, i, j, ve );
+           }
+        }       
+        break;
+      case CV_GABOR_PHASE:
+        break;
+    }
+    
+    if (dst->depth == IPL_DEPTH_8U)
+    {
+    	cvNormalize((CvMat*)mat, (CvMat*)mat, 0, 255, CV_MINMAX);
+    	for (int i = 0; i < mat->rows; i++)
+    	{
+            for (int j = 0; j < mat->cols; j++)
+            {
+                ve = cvGetReal2D((CvMat*)mat, i, j);
+                ve = cvRound(ve);
+                cvSetReal2D( (IplImage*)dst, j, i, ve );
+            }
+        }
+     }
+
+     if (dst->depth == IPL_DEPTH_32F)
+     {
+         for (int i = 0; i < mat->rows; i++)
+    	 {
+            for (int j = 0; j < mat->cols; j++)
+            {
+                ve = cvGetReal2D((CvMat*)mat, i, j);
+                cvSetReal2D( (IplImage*)dst, j, i, ve );
+            }
+         }
+     }       
+
+    cvReleaseMat(&kernel);
+    cvReleaseMat(&imat);   
+    cvReleaseMat(&rmat);
+    cvReleaseMat(&mat);
+}
Index: /trunk/saliency_detection/src/saliencyDetectionHou.cpp
===================================================================
--- /trunk/saliency_detection/src/saliencyDetectionHou.cpp	(revision 10)
+++ /trunk/saliency_detection/src/saliencyDetectionHou.cpp	(revision 10)
@@ -0,0 +1,122 @@
+//===================================================================================
+// Name        : saliencyDetectionHou.cpp
+// Author      : Oytun Akman, oytunakman@gmail.com
+// Editor	   : Joris van de Weem, joris.vdweem@gmail.com (Conversion to ROS)
+// Version     : 1.2
+// Copyright   : Copyright (c) 2010 LGPL
+// Description : C++ implementation of "Saliency Detection: A Spectral Residual 
+//				 Approach" by Xiaodi Hou and Liqing Zhang (CVPR 2007).												  
+//===================================================================================
+// v1.1: Changed Gaussianblur of logamplitude to averaging blur and gaussian kernel of saliency map to sigma = 8, kernelsize = 5
+//      for better consistency with the paper. (Joris)
+// v1.2: Ported to Robot Operating System (ROS) (Joris)
+
+#include <saliency_detection/saliencyDetectionHou.h>
+
+
+void saliencyMapHou::imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
+{
+	cv_bridge::CvImagePtr cv_ptr;
+	sensor_msgs::Image salmap_;
+	geometry_msgs::Point salientpoint_;
+
+	Mat image_, saliencymap_;
+	Point pt_salient;
+	double maxVal;
+
+	try
+	{
+		cv_ptr = cv_bridge::toCvCopy(msg_ptr, enc::BGR8);
+	}
+	catch (cv_bridge::Exception& e)
+	{
+		ROS_ERROR("cv_bridge exception: %s", e.what());
+	}
+	cv_ptr->image.copyTo(image_);
+
+	saliencymap_.create(image_.size(),CV_8UC1);
+	saliencyMapHou::calculateSaliencyMap(&image_, &saliencymap_);
+
+	//-- Return most salient point --//
+	cv::minMaxLoc(saliencymap_,NULL,&maxVal,NULL,&pt_salient);
+	salientpoint_.x = pt_salient.x;
+	salientpoint_.y = pt_salient.y;
+
+
+	//	CONVERT FROM CV::MAT TO ROSIMAGE FOR PUBLISHING
+	saliencymap_.convertTo(saliencymap_, CV_8UC1,255);
+	fillImage(salmap_, "mono8",saliencymap_.rows, saliencymap_.cols, saliencymap_.step, const_cast<uint8_t*>(saliencymap_.data));
+
+	saliencymap_pub_.publish(salmap_);
+	point_pub_.publish(salientpoint_);
+
+	return;
+}
+
+
+void saliencyMapHou::calculateSaliencyMap(const Mat* src, Mat* dst)
+{
+	Mat grayTemp, grayDown;
+	vector<Mat> mv;	
+	//Size imageSize(160,120);
+	Size imageSize(64,64);
+	Mat realImage(imageSize,CV_64F);
+	Mat imaginaryImage(imageSize,CV_64F); imaginaryImage.setTo(0);
+	Mat combinedImage(imageSize,CV_64FC2);
+	Mat imageDFT;	
+	Mat logAmplitude;
+	Mat angle(imageSize,CV_64F);
+	Mat magnitude(imageSize,CV_64F);
+	Mat logAmplitude_blur;
+	
+	cvtColor(*src, grayTemp, CV_BGR2GRAY);
+	resize(grayTemp, grayDown, imageSize, 0, 0, INTER_LINEAR);
+	for(int j=0; j<grayDown.rows;j++)
+       	for(int i=0; i<grayDown.cols; i++)
+       		realImage.at<double>(j,i) = grayDown.at<uchar>(j,i);
+			
+	mv.push_back(realImage);
+	mv.push_back(imaginaryImage);	
+	merge(mv,combinedImage);	
+	dft( combinedImage, imageDFT);
+	split(imageDFT, mv);	
+
+	//-- Get magnitude and phase of frequency spectrum --//
+	cartToPolar(mv.at(0), mv.at(1), magnitude, angle, false);
+	log(magnitude,logAmplitude);	
+	//-- Blur log amplitude with averaging filter --//
+	blur(logAmplitude, logAmplitude_blur, Size(3,3), Point(-1,-1), BORDER_DEFAULT);
+	
+	exp(logAmplitude - logAmplitude_blur,magnitude);
+	//-- Back to cartesian frequency domain --//
+	polarToCart(magnitude, angle, mv.at(0), mv.at(1), false);
+	merge(mv, imageDFT);
+	dft( imageDFT, combinedImage, CV_DXT_INVERSE); 
+	split(combinedImage, mv);
+
+	cartToPolar(mv.at(0), mv.at(1), magnitude, angle, false);
+	GaussianBlur(magnitude, magnitude, Size(5,5), 8, 0, BORDER_DEFAULT);
+	magnitude = magnitude.mul(magnitude);
+
+	double minVal,maxVal;
+	minMaxLoc(magnitude, &minVal, &maxVal);
+	magnitude = magnitude / maxVal;
+
+	Mat tempFloat(imageSize,CV_32F);
+	for(int j=0; j<magnitude.rows;j++)
+       	for(int i=0; i<magnitude.cols; i++)
+       		tempFloat.at<float>(j,i) = magnitude.at<double>(j,i);
+
+	resize(tempFloat, *dst, dst->size(), 0, 0, INTER_LINEAR);
+}
+
+int main(int argc, char **argv)
+{
+	ros::init(argc, argv, "saliencymap");
+
+	saliencyMapHou salmapHou;
+
+	ros::spin();
+
+	return 0;
+}
Index: /trunk/saliency_detection/src/saliencyDetectionItti.cpp
===================================================================
--- /trunk/saliency_detection/src/saliencyDetectionItti.cpp	(revision 10)
+++ /trunk/saliency_detection/src/saliencyDetectionItti.cpp	(revision 10)
@@ -0,0 +1,350 @@
+//===================================================================================
+// Name        : saliencyDetectionItti.cpp
+// Author      : Oytun Akman, oytunakman@gmail.com
+// Editor	   : Joris van de Weem, joris.vdweem@gmail.com (Conversion to ROS)
+// Version     : 1.1
+// Copyright   : Copyright (c) 2010 LGPL
+// Description : C++ implementation of "A Model of Saliency-Based Visual Attention
+//				 for Rapid Scene Analysis" by Laurent Itti, Christof Koch and Ernst
+//				 Niebur (PAMI 1998).												  
+//===================================================================================
+// v1.1: Ported to Robot Operating System (ROS) (Joris)
+
+#include <saliency_detection/saliencyDetectionItti.h>
+#include <saliency_detection/cvgabor.h>
+
+void saliencyMapItti::imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
+{
+	cv_bridge::CvImagePtr cv_ptr;
+	sensor_msgs::Image salmap_;
+	geometry_msgs::Point salientpoint_;
+
+	Mat image_, saliencymap_;
+	Point pt_salient;
+	double maxVal;
+
+	try
+	{
+		cv_ptr = cv_bridge::toCvCopy(msg_ptr, enc::BGR8);
+	}
+	catch (cv_bridge::Exception& e)
+	{
+		ROS_ERROR("cv_bridge exception: %s", e.what());
+	}
+	cv_ptr->image.copyTo(image_);
+
+
+	saliencymap_.create(image_.size(),CV_8UC1);
+	saliencyMapItti::calculateSaliencyMap(&image_, &saliencymap_,1);
+
+	//-- Return most salient point --//
+	cv::minMaxLoc(saliencymap_,NULL,&maxVal,NULL,&pt_salient);
+	salientpoint_.x = pt_salient.x;
+	salientpoint_.y = pt_salient.y;
+
+
+	//	CONVERT FROM CV::MAT TO ROSIMAGE FOR PUBLISHING
+	saliencymap_.convertTo(saliencymap_, CV_8UC1,255);
+	fillImage(salmap_, "mono8",saliencymap_.rows, saliencymap_.cols, saliencymap_.step, const_cast<uint8_t*>(saliencymap_.data));
+
+	saliencymap_pub_.publish(salmap_);
+	point_pub_.publish(salientpoint_);
+
+	return;
+}
+
+void saliencyMapItti::calculateSaliencyMap(const Mat* src, Mat* dst, int scaleBase)
+{
+	createChannels(src);
+
+	createIntensityFeatureMaps();
+	createColorFeatureMaps();
+	createOrientationFeatureMaps(0);
+	createOrientationFeatureMaps(2);
+	createOrientationFeatureMaps(4);
+	createOrientationFeatureMaps(6);
+
+	combineFeatureMaps(scaleBase);
+
+	resize(S, *dst, src->size(), 0, 0, INTER_LINEAR);
+
+	clearBuffers();
+}
+
+void saliencyMapItti::createChannels(const Mat* src)
+{
+	b.create(src->size(),CV_32F);
+	g.create(src->size(),CV_32F);
+	r.create(src->size(),CV_32F);
+	I.create(src->size(),CV_32F);
+	vector<Mat> planes;	
+	split(*src, planes);
+
+	for(int j=0; j<r.rows;j++)
+       	for(int i=0; i<r.cols; i++)
+       	{
+			b.at<float>(j,i) = planes[0].at<uchar>(j,i);
+			g.at<float>(j,i) = planes[1].at<uchar>(j,i);
+			r.at<float>(j,i) = planes[2].at<uchar>(j,i);
+       	}
+	
+	I = r+g+b; 
+	I = I/3;
+
+	normalize_rgb();
+	create_RGBY();
+	createScaleSpace(&I, &gaussianPyramid_I, 8);	
+	createScaleSpace(&R, &gaussianPyramid_R, 8);	
+	createScaleSpace(&G, &gaussianPyramid_G, 8);	
+	createScaleSpace(&B, &gaussianPyramid_B, 8);	
+	createScaleSpace(&Y, &gaussianPyramid_Y, 8);	
+}
+
+/*r,g and b channels are normalized by I in order to decouple hue from intensity
+  Because hue variations are not perceivable at very low luminance normalization is only applied at the locations
+  where I is larger than max(I)/10 (other locations yield zero r,g,b)*/
+void saliencyMapItti::normalize_rgb()
+{
+	double minVal,maxVal;	
+	minMaxLoc(I, &minVal, &maxVal);
+	Mat mask_I;
+	threshold(I, mask_I, maxVal/10, 1.0, THRESH_BINARY);
+
+	r = r/I;
+	g = g/I;
+	b = b/I;
+	r = r.mul(mask_I);
+	g = g.mul(mask_I);
+	b = b.mul(mask_I);
+}
+
+void saliencyMapItti::create_RGBY()
+{
+	Mat gb = g+b; 
+	Mat rb = r+b; 
+	Mat rg = r+g; 
+	Mat rg_ = r-g;
+
+	R = r-gb/2;
+	G = g-rb/2;
+	B = b-rg/2;
+	Y = rg/2 - abs(rg_/2) - b;
+
+	Mat mask;
+	threshold(R, mask, 0.0, 1.0, THRESH_BINARY);
+	R = R.mul(mask);
+	threshold(G, mask, 0.0, 1.0, THRESH_BINARY);
+	G = G.mul(mask);
+	threshold(B, mask, 0.0, 1.0, THRESH_BINARY);
+	B = B.mul(mask);
+	threshold(Y, mask, 0.0, 1.0, THRESH_BINARY);
+	Y = Y.mul(mask);
+}
+
+void saliencyMapItti::createScaleSpace(const Mat* src, vector<Mat>* dst, int scale)
+{
+	buildPyramid( *src, *dst, scale);
+}
+
+void saliencyMapItti::createIntensityFeatureMaps()
+{
+	int fineScaleNumber = 3;
+	int scaleDiff = 2;
+	int c[3] = {2,3,4};
+	int delta[2] = {3,4};
+
+	for (int scaleIndex = 0; scaleIndex < fineScaleNumber; scaleIndex++)
+	{		
+		Mat fineScaleImage = gaussianPyramid_I.at(c[scaleIndex]);
+		Size fineScaleImageSize = fineScaleImage.size();
+
+		for(int scaleDiffIndex = 0; scaleDiffIndex<scaleDiff; scaleDiffIndex++)
+		{
+			int s = c[scaleIndex] + delta[scaleDiffIndex];
+			Mat coarseScaleImage = gaussianPyramid_I.at(s);
+			Mat coarseScaleImageUp;
+			resize(coarseScaleImage, coarseScaleImageUp, fineScaleImageSize, 0, 0, INTER_LINEAR);
+			Mat I_cs = abs(fineScaleImage -  coarseScaleImageUp);			
+			featureMaps_I.push_back(I_cs);		
+		}
+	}
+}
+
+void saliencyMapItti::createColorFeatureMaps()
+{
+	int fineScaleNumber = 3;
+	int scaleDiff = 2;
+	int c[3] = {2,3,4};
+	int delta[2] = {3,4};
+
+	for (int scaleIndex = 0; scaleIndex < fineScaleNumber; scaleIndex++)
+	{		
+		Mat fineScaleImageR = gaussianPyramid_R.at(c[scaleIndex]);
+		Mat fineScaleImageG = gaussianPyramid_G.at(c[scaleIndex]);
+		Mat fineScaleImageB = gaussianPyramid_B.at(c[scaleIndex]);
+		Mat fineScaleImageY = gaussianPyramid_Y.at(c[scaleIndex]);
+		Size fineScaleImageSize = fineScaleImageR.size();
+
+		Mat RGc = fineScaleImageR - fineScaleImageG;
+		Mat BYc = fineScaleImageB - fineScaleImageY;
+
+		for(int scaleDiffIndex = 0; scaleDiffIndex<scaleDiff; scaleDiffIndex++)
+		{
+			int s = c[scaleIndex] + delta[scaleDiffIndex];
+			Mat coarseScaleImageR = gaussianPyramid_R.at(s);
+			Mat coarseScaleImageG = gaussianPyramid_G.at(s);
+			Mat coarseScaleImageB = gaussianPyramid_B.at(s);
+			Mat coarseScaleImageY = gaussianPyramid_Y.at(s);
+
+			Mat GRs = coarseScaleImageG - coarseScaleImageR;
+			Mat YBs = coarseScaleImageY - coarseScaleImageB;
+			Mat coarseScaleImageUpGRs, coarseScaleImageUpYBs;
+			resize(GRs, coarseScaleImageUpGRs, fineScaleImageSize, 0, 0, INTER_LINEAR);
+			resize(YBs, coarseScaleImageUpYBs, fineScaleImageSize, 0, 0, INTER_LINEAR);			
+			Mat RG_cs = abs( RGc - coarseScaleImageUpGRs);
+			Mat BY_cs = abs( BYc - coarseScaleImageUpYBs);
+			
+			featureMaps_RG.push_back(RG_cs);
+			featureMaps_BY.push_back(BY_cs);		
+		}
+	}
+}
+
+void saliencyMapItti::createOrientationFeatureMaps(int orientation)
+{
+	int fineScaleNumber = 3;
+	int scaleDiff = 2;
+	int c[3] = {2,3,4};
+	int delta[2] = {3,4};
+	CvGabor *gabor = new CvGabor(orientation,0);	
+	IplImage* gbr_fineScaleImage, *gbr_coarseScaleImage;
+
+	for (int scaleIndex = 0; scaleIndex < fineScaleNumber; scaleIndex++)
+	{		
+		Mat fineScaleImage = gaussianPyramid_I.at(c[scaleIndex]);
+		Size fineScaleImageSize = fineScaleImage.size();
+
+		IplImage src_fineScaleImage = IplImage(fineScaleImage);
+		gbr_fineScaleImage = cvCreateImage(fineScaleImage.size(),IPL_DEPTH_8U, 1);				
+		gabor->conv_img(&src_fineScaleImage,gbr_fineScaleImage,CV_GABOR_REAL);		
+		Mat src_responseImg(gbr_fineScaleImage);		
+
+		for(int scaleDiffIndex = 0; scaleDiffIndex<scaleDiff; scaleDiffIndex++)
+		{
+			int s = c[scaleIndex] + delta[scaleDiffIndex];
+			Mat coarseScaleImage = gaussianPyramid_I.at(s);
+			IplImage src_coarseScaleImage = IplImage(coarseScaleImage);
+			gbr_coarseScaleImage = cvCreateImage(coarseScaleImage.size(),IPL_DEPTH_8U, 1);			
+			gabor->conv_img(&src_coarseScaleImage,gbr_coarseScaleImage,CV_GABOR_REAL);			
+			Mat coarse_responseImg(gbr_coarseScaleImage);
+
+			Mat coarseScaleImageUp;
+			resize(coarse_responseImg, coarseScaleImageUp, fineScaleImageSize, 0, 0, INTER_LINEAR);			
+
+			Mat temp = abs(src_responseImg -  coarseScaleImageUp);
+			Mat O_cs(temp.size(),CV_32F);
+
+			for(int j=0; j<temp.rows;j++)
+       			for(int i=0; i<temp.cols; i++)
+       				O_cs.at<float>(j,i) = temp.at<uchar>(j,i);
+
+			if(orientation == 0)			
+				featureMaps_0.push_back(O_cs);
+			if(orientation == 2)			
+				featureMaps_45.push_back(O_cs);
+			if(orientation == 4)			
+				featureMaps_90.push_back(O_cs);
+			if(orientation == 6)			
+				featureMaps_135.push_back(O_cs);
+
+			cvReleaseImage(&gbr_coarseScaleImage);		
+		}
+		cvReleaseImage(&gbr_fineScaleImage);		
+	}
+}
+
+void saliencyMapItti::combineFeatureMaps(int scale)
+{
+	Size scaleImageSize = gaussianPyramid_I.at(scale).size();
+	conspicuityMap_I.create(scaleImageSize,CV_32F); conspicuityMap_I.setTo(0);
+	conspicuityMap_C.create(scaleImageSize,CV_32F); conspicuityMap_C.setTo(0);
+	conspicuityMap_O.create(scaleImageSize,CV_32F);	conspicuityMap_O.setTo(0);
+	Mat ori_0(scaleImageSize,CV_32F); ori_0.setTo(0);
+	Mat ori_45(scaleImageSize,CV_32F); ori_45.setTo(0);
+	Mat ori_90(scaleImageSize,CV_32F); ori_90.setTo(0);
+	Mat ori_135(scaleImageSize,CV_32F); ori_135.setTo(0);
+
+	Mat featureMap, featureMap_scaled, RG, BY, RG_scaled, BY_scaled;
+
+	for (int index=0; index<3*2; index++)
+	{
+		resize(featureMaps_I.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
+		mapNormalization(&featureMap_scaled);
+		conspicuityMap_I = conspicuityMap_I + featureMap_scaled;
+
+		resize(featureMaps_RG.at(index), RG_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
+		resize(featureMaps_BY.at(index), BY_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
+		mapNormalization(&RG_scaled);
+		mapNormalization(&BY_scaled);
+		conspicuityMap_C = conspicuityMap_C + (RG_scaled + BY_scaled);
+			
+		resize(featureMaps_0.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
+		mapNormalization(&featureMap_scaled);
+		ori_0 = ori_0 + featureMap_scaled;
+		resize(featureMaps_45.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
+		mapNormalization(&featureMap_scaled);
+		ori_45 = ori_45 + featureMap_scaled;	
+		resize(featureMaps_90.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
+		mapNormalization(&featureMap_scaled);
+		ori_90 = ori_90 + featureMap_scaled;
+		resize(featureMaps_135.at(index), featureMap_scaled, scaleImageSize, 0, 0, INTER_LINEAR);
+		mapNormalization(&featureMap_scaled);
+		ori_135 = ori_135 + featureMap_scaled;	
+	}
+
+	mapNormalization(&ori_0);	
+	mapNormalization(&ori_45);
+	mapNormalization(&ori_90);
+	mapNormalization(&ori_135);
+	conspicuityMap_O = ori_0 + ori_45 + ori_90 + ori_135;
+
+	mapNormalization(&conspicuityMap_I);
+	mapNormalization(&conspicuityMap_C);
+	mapNormalization(&conspicuityMap_O);
+
+	S = conspicuityMap_I + conspicuityMap_C + conspicuityMap_O;
+	S = S/3;
+}
+void saliencyMapItti::mapNormalization(Mat* src)
+{
+	double minVal,maxVal;	
+	minMaxLoc(*src, &minVal, &maxVal);
+	*src = *src / (float) maxVal;
+}
+
+void saliencyMapItti::clearBuffers()
+{
+	gaussianPyramid_I.clear();
+	gaussianPyramid_R.clear();
+	gaussianPyramid_G.clear();
+	gaussianPyramid_B.clear();
+	gaussianPyramid_Y.clear();
+	featureMaps_I.clear();
+	featureMaps_RG.clear();
+	featureMaps_BY.clear();	
+	featureMaps_0.clear();
+	featureMaps_45.clear();
+	featureMaps_90.clear();
+	featureMaps_135.clear();
+}
+
+int main(int argc, char **argv)
+{
+	ros::init(argc, argv, "saliencymap");
+
+	saliencyMapItti salmapItti;
+
+	ros::spin();
+
+	return 0;
+}
Index: /trunk/saliency_detection/src/saliencyDetectionRudinac.cpp
===================================================================
--- /trunk/saliency_detection/src/saliencyDetectionRudinac.cpp	(revision 10)
+++ /trunk/saliency_detection/src/saliencyDetectionRudinac.cpp	(revision 10)
@@ -0,0 +1,193 @@
+//===================================================================================
+// Name        : saliencyDetectionRudinac.cpp
+// Author      : Joris van de Weem, joris.vdweem@gmail.com
+// Version     : 1.1
+// Copyright   : Copyright (c) 2011 LGPL
+// Description : C++ implementation of "Maja Rudinac, Pieter P. Jonker. 
+// 				"Saliency Detection and Object Localization in Indoor Environments". 
+//				ICPR'2010. pp.404~407											  
+//===================================================================================
+// v1.1: Ported to Robot Operating System (ROS)
+
+#include <saliency_detection/saliencyDetectionRudinac.h>
+
+void saliencyMapRudinac::imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
+{
+	cv_bridge::CvImagePtr cv_ptr;
+	sensor_msgs::Image salmap_;
+	geometry_msgs::Point salientpoint_;
+
+	Mat image_, saliencymap_;
+	Point pt_salient;
+	double maxVal;
+
+	try
+	{
+		cv_ptr = cv_bridge::toCvCopy(msg_ptr, enc::BGR8);
+	}
+	catch (cv_bridge::Exception& e)
+	{
+		ROS_ERROR("cv_bridge exception: %s", e.what());
+	}
+	cv_ptr->image.copyTo(image_);
+
+
+	saliencymap_.create(image_.size(),CV_8UC1);
+	saliencyMapRudinac::calculateSaliencyMap(&image_, &saliencymap_);
+
+	//-- Return most salient point --//
+	cv::minMaxLoc(saliencymap_,NULL,&maxVal,NULL,&pt_salient);
+	salientpoint_.x = pt_salient.x;
+	salientpoint_.y = pt_salient.y;
+
+
+	//	CONVERT FROM CV::MAT TO ROSIMAGE FOR PUBLISHING
+	saliencymap_.convertTo(saliencymap_, CV_8UC1,255);
+	fillImage(salmap_, "mono8",saliencymap_.rows, saliencymap_.cols, saliencymap_.step, const_cast<uint8_t*>(saliencymap_.data));
+
+	saliencymap_pub_.publish(salmap_);
+	point_pub_.publish(salientpoint_);
+
+	return;
+}
+
+
+void saliencyMapRudinac::calculateSaliencyMap(const Mat* src, Mat* dst)
+{
+	Size imageSize(128,128);
+	Mat srcDown(imageSize,CV_64F);
+	Mat magnitudeI(imageSize,CV_64F);
+	Mat magnitudeRG(imageSize,CV_64F);
+	Mat magnitudeBY(imageSize,CV_64F);
+	Mat magnitude(imageSize,CV_64F);
+	
+	resize(*src, srcDown, imageSize, 0, 0, INTER_LINEAR);
+	
+	createChannels(&srcDown);
+	createSaliencyMap(I,&magnitudeI);
+	createSaliencyMap(RG,&magnitudeRG);
+	createSaliencyMap(BY,&magnitudeBY);
+	
+	magnitude= (magnitudeI + magnitudeRG + magnitudeBY);
+	GaussianBlur(magnitude, magnitude, Size(5,5), 0, 0, BORDER_DEFAULT);
+
+	//-- Scale to domain [0,1] --//
+	double minVal,maxVal;
+	minMaxLoc(magnitude, &minVal, &maxVal);
+	magnitude = magnitude / maxVal;
+
+	resize(magnitude, *dst, dst->size(), 0, 0, INTER_LINEAR);
+}
+
+
+void saliencyMapRudinac::createChannels(const Mat* src)
+{
+	
+	b.create(src->size(),CV_32F);
+	g.create(src->size(),CV_32F);
+	r.create(src->size(),CV_32F);
+	I.create(src->size(),CV_32F);
+	vector<Mat> planes;	
+	split(*src, planes);
+	Mat rgmax(src->size(),CV_32F);
+	Mat rgbmax(src->size(),CV_32F);
+	Mat mask(src->size(),CV_32F);
+
+	for(int j=0; j<r.rows;j++)
+       	for(int i=0; i<r.cols; i++)
+       	{
+			b.at<float>(j,i) = planes[0].at<uchar>(j,i);
+			g.at<float>(j,i) = planes[1].at<uchar>(j,i);
+			r.at<float>(j,i) = planes[2].at<uchar>(j,i);
+       	}
+	
+	I = r+g+b;
+	//threshold(I, I, 255, 255, THRESH_TRUNC); // Saturation as in Matlab?
+	I = I/3;
+		
+	rgmax = max(r,g);
+	rgbmax = max(rgmax,b);
+	
+	//-- Prevent that the lowest value is zero, because you cannot divide by zero.
+	for(int j=0; j<r.rows;j++)
+       	for(int i=0; i<r.cols; i++)
+       	{
+			if (rgbmax.at<float>(j,i) == 0) rgbmax.at<float>(j,i) = 1;
+       	}
+
+
+	RG = abs(r-g)/rgbmax;
+	BY = abs(b - min(r,g))/rgbmax;
+
+	rgbmax = rgbmax/255;
+	//-- If max(r,g,b)<0.1 all components should be zero to stop large fluctuations of the color opponency values at low luminance --//
+	threshold(rgbmax,mask,.1,1,THRESH_BINARY);
+	RG = RG.mul(mask);
+	BY = BY.mul(mask);
+	I = I.mul(mask);
+}
+
+
+
+void saliencyMapRudinac::createSaliencyMap(const Mat src, Mat* dst)
+{
+	vector<Mat> mv;	
+	
+	Mat realImage(src.size(),CV_64F);
+	Mat imaginaryImage(src.size(),CV_64F); imaginaryImage.setTo(0);
+	Mat combinedImage(src.size(),CV_64FC2);
+	Mat image_DFT;	
+	Mat logAmplitude;
+	Mat angle(src.size(),CV_64F);
+	Mat Magnitude(src.size(),CV_64F);
+	Mat logAmplitude_blur;
+	
+	for(int j=0; j<src.rows;j++){
+       	for(int i=0; i<src.cols; i++){
+       		realImage.at<double>(j,i) = src.at<float>(j,i);
+       	}
+	}
+
+			
+	mv.push_back(realImage);
+	mv.push_back(imaginaryImage);	
+	merge(mv,combinedImage);	
+	
+	dft( combinedImage, image_DFT);
+	split(image_DFT, mv);	
+
+	//-- Get magnitude and phase of frequency spectrum --//
+	cartToPolar(mv.at(0), mv.at(1), Magnitude, angle, false);
+	log(Magnitude,logAmplitude);	
+		
+	//-- Blur log amplitude with averaging filter --//
+	blur(logAmplitude, logAmplitude_blur, Size(3,3), Point(-1,-1), BORDER_DEFAULT);
+	exp(logAmplitude - logAmplitude_blur,Magnitude);
+	
+	polarToCart(Magnitude, angle,mv.at(0), mv.at(1),false);
+	merge(mv,image_DFT);
+	dft(image_DFT,combinedImage,CV_DXT_INVERSE);
+
+	split(combinedImage,mv);
+	cartToPolar(mv.at(0), mv.at(1), Magnitude, angle, false);
+	Magnitude = Magnitude.mul(Magnitude);
+
+	Mat tempFloat(src.size(),CV_32F);
+	for(int j=0; j<Magnitude.rows;j++)
+       	for(int i=0; i<Magnitude.cols; i++)
+       		tempFloat.at<float>(j,i) = Magnitude.at<double>(j,i);
+	
+	*dst = tempFloat;
+}
+
+
+int main(int argc, char **argv)
+{
+	ros::init(argc, argv, "saliencymap");
+
+	saliencyMapRudinac salmapRudinac;
+
+	ros::spin();
+
+	return 0;
+}
Index: /trunk/saliency_detection/stack.xml
===================================================================
--- /trunk/saliency_detection/stack.xml	(revision 10)
+++ /trunk/saliency_detection/stack.xml	(revision 10)
@@ -0,0 +1,7 @@
+<stack>
+  <description brief="saliency_detection">Create saliency maps</description>
+  <author>Joris van de Weem</author>
+  <license>GPL</license>
+  <review status="unreviewed" notes=""/>
+  <url>http://ros.org/wiki/saliency_detection</url>
+</stack>
