diff --git a/CMakeLists.txt b/CMakeLists.txt
index 5570974..0684df2 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -8,6 +8,15 @@ find_package(PkgConfig)
 pkg_check_modules(PC_LIBOPENNI REQUIRED libopenni)
 pkg_check_modules(PC_LIBUSB REQUIRED libusb-1.0)
 
+find_package(Log4cxx QUIET)
+if(NOT LOG4CXX_LIBRARIES)  
+    # backup plan, hope it is in the system path
+  find_library(LOG4CXX_LIBRARIES log4cxx)
+endif()
+if(NOT LOG4CXX_LIBRARIES)
+  message(ERROR "log4cxx required")
+endif()
+
 generate_dynamic_reconfigure_options(cfg/OpenNI.cfg)
 
 catkin_package(
@@ -44,6 +53,7 @@ target_link_libraries(openni_driver ${catkin_LIBRARIES}
                                     ${Boost_LIBRARIES} 
                                     ${PC_LIBOPENNI_LIBRARIES}
                                     ${PC_LIBUSB_LIBRARIES}
+                                    ${LOG4CXX_LIBRARIES}
 )
 
 # ROS nodelets library
diff --git a/package.xml b/package.xml
index f051b02..82add23 100644
--- a/package.xml
+++ b/package.xml
@@ -22,6 +22,7 @@
   <build_depend>camera_info_manager</build_depend>
   <build_depend>dynamic_reconfigure</build_depend>
   <build_depend>image_transport</build_depend>
+  <build_depend>log4cxx</build_depend>
   <build_depend>nodelet</build_depend>
   <build_depend>roscpp</build_depend>
   <build_depend>sensor_msgs</build_depend>
@@ -33,6 +34,7 @@
   <run_depend>camera_info_manager</run_depend>
   <run_depend>dynamic_reconfigure</run_depend>
   <run_depend>image_transport</run_depend>
+  <run_depend>log4cxx</run_depend>
   <run_depend>nodelet</run_depend>
   <run_depend>roscpp</run_depend>
   <run_depend>sensor_msgs</run_depend>
diff --git a/src/nodelets/driver.cpp b/src/nodelets/driver.cpp
index a0ef0ee..6b99a22 100644
--- a/src/nodelets/driver.cpp
+++ b/src/nodelets/driver.cpp
@@ -46,6 +46,8 @@
 #include <sensor_msgs/distortion_models.h>
 #include <boost/algorithm/string/replace.hpp>
 
+#include <log4cxx/logger.h>
+
 using namespace std;
 using namespace openni_wrapper;
 namespace openni_camera