Skip to content
Snippets Groups Projects
Commit 94e5eff5 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Added a new parameter to create the serial device name (device_name).

parent 7ddd8246
No related branches found
No related tags found
No related merge requests found
......@@ -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{
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment