diff --git a/src/firewire_camera_driver_nodelet.cpp b/src/firewire_camera_driver_nodelet.cpp
index 1e0adac5f487d59c3b6560f7c827698803db9315..93221ed316be45ff99d8a4dec0deef7f0c6399ef 100755
--- a/src/firewire_camera_driver_nodelet.cpp
+++ b/src/firewire_camera_driver_nodelet.cpp
@@ -1,8 +1,10 @@
 #include "firewire_camera_driver_nodelet.h"
 #include <pluginlib/class_list_macros.h>
 
-FirewireCameraDriverNode::FirewireCameraDriverNode(ros::NodeHandle &nh) : iri_base_driver::IriBaseNodeDriver<FirewireCameraDriver>(nh), camera_manager(ros::NodeHandle(this->public_node_handle_)),
-                                                                          it(new image_transport::ImageTransport(this->public_node_handle_)),Image_msg_(new sensor_msgs::Image)
+FirewireCameraDriverNode::FirewireCameraDriverNode(ros::NodeHandle &nh) : iri_base_driver::IriBaseNodeDriver<FirewireCameraDriver>(nh), 
+                                                                          camera_manager(ros::NodeHandle(this->public_node_handle_)),
+                                                                          it(new image_transport::ImageTransport(this->public_node_handle_)),
+                                                                          Image_msg_(new sensor_msgs::Image)
 {
   std::string cal_file;
 
@@ -201,17 +203,16 @@ FirewireCameraDriverNode::~FirewireCameraDriverNode()
 FirewireCameraNodelet::FirewireCameraNodelet()
 {
   this->dev=NULL;
-  // initialize the thread
-  this->thread_server=CThreadServer::instance();
-  this->spin_thread_id="firewire_camera_driver_nodelet_spin";
-  this->thread_server->create_thread(this->spin_thread_id);
-  this->thread_server->attach_thread(this->spin_thread_id,this->spin_thread,this);
 }
 
 void FirewireCameraNodelet::onInit()
 {
-  ros::NodeHandle priv_nh(getPrivateNodeHandle());
-  this->dev=new FirewireCameraDriverNode(priv_nh);
+  this->dev=new FirewireCameraDriverNode(getPrivateNodeHandle());
+  // initialize the thread
+  this->thread_server=CThreadServer::instance();
+  this->spin_thread_id=getName() + "_camera_driver_nodelet_spin";
+  this->thread_server->create_thread(this->spin_thread_id);
+  this->thread_server->attach_thread(this->spin_thread_id,this->spin_thread,this);
   // start the spin thread
   this->thread_server->start_thread(this->spin_thread_id);
 }