diff --git a/src/dynamixel_robot_gazebo.cpp b/src/dynamixel_robot_gazebo.cpp
index 436f4502cdcab18f9d2b94a47516e1b8c02d2048..ebf54b376ee1672ebf3240a14c7b2e65fe3c9558 100644
--- a/src/dynamixel_robot_gazebo.cpp
+++ b/src/dynamixel_robot_gazebo.cpp
@@ -112,7 +112,7 @@ namespace dynamixel_robot_gazebo
   bool DynamixelRobotGazebo::init(hardware_interface::EffortJointInterface* hw,ros::NodeHandle& root_nh,ros::NodeHandle& controller_nh)
   {
     unsigned int n_joints;
-    std::string device_name;
+    std::string device_name,name;
     int return_delay=0,return_level=2,protocol=2,baudrate=1000000;
     struct stat buffer;
 
@@ -149,7 +149,8 @@ namespace dynamixel_robot_gazebo
     // initialize dynamixel slave server
     ROS_INFO("Dynamixel gazebo plugin: Load dynamixel slave parameters");
     ros::NodeHandle dynamixel_nh(this->controller_nh,std::string("dynamixel_bus"));
-    device_name="/tmp"+root_nh.getNamespace()+"_gazebo";
+    dynamixel_nh.getParam("device_name",name);
+    device_name="/tmp/"+name+"_gazebo";
     // wait until the serial device exists
     unsigned int timeout=20;
     do{