ROBOTIS-GIT / dynamixel-workbench

ROS packages for Dynamixel controllers, msgs, single_manager, toolbox, tutorials
http://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_workbench/
Apache License 2.0
106 stars 174 forks source link

dynamixel_workbench_controllers node fills RAM memory and crashes #225

Closed jcgarciaca closed 5 years ago

jcgarciaca commented 5 years ago

I am using dynamixel_controller with moveit. If I drag the marker and press Plan and execute button it works well. However, after a couple of times (planing and executing trajectories) the dynamixel_workbench_controllers node fills RAM memory and then crashes.

routiful commented 5 years ago

Due to lack information, I couldn't help you. Please fill the issue form to describe development environment and copy and paste error messages.

jcgarciaca commented 5 years ago

I just changed sample_duration value and the issue seems to be solved. I'll try and if issue appears again then re-open with detailed information.

routiful commented 5 years ago

Good :) But next time, please fill the issue form.

jcgarciaca commented 5 years ago

I've tested continuously and got error again. Here the issue form:

  1. How to setup? U2D2

  2. Which Dynamixel have you used? and how many? (Please describe below format to all connected Dynamixels) 2 Motors

    • Model Name: XM430-W210R (both)
    • ID: 1 and 2
    • Baud Rate of Dynamixels: 57600
    • Protocol Version: 2.0
  3. Write down the commands you used in order

    $ roscore
    $ roslaunch dynamixel_workbench_controllers dynamixel_controllers.launch
    $ roslaunch open_manipulator_controller open_manipulator_moveit.launch sample_duration:=0.050
    $ roslaunch dynamixel_workbench_moveit_bridge moveit_bridge.launch robot_name:=open_manipulator
  4. Copy and Paste your error message on terminal

    terminate called after throwing an instance of 'std::bad_alloc'
    what():  std::bad_alloc
    ================================================================================REQUIRED process [dynamixel_workbench_controllers-2] has died!
    process has died [pid 2498, exit code -6, cmd /home/millerup/robotic_arm/catkin_ws/devel/lib/dynamixel_workbench_controllers/dynamixel_workbench_controllers /dev/ttyUSB0 57600 __name:=dynamixel_workbench_controllers __log:=/home/millerup/.ros/log/ba43078a-2a5b-11e9-96ed-40a8f0a985e8/dynamixel_workbench_controllers-2.log].
    log file: /home/millerup/.ros/log/ba43078a-2a5b-11e9-96ed-40a8f0a985e8/dynamixel_workbench_controllers-2*.log
    Initiating shutdown!
    ================================================================================
    [dynamixel_workbench_controllers-2] killing on exit
    [dynamixel_workbench_controllers-2] escalating to SIGTERM
  5. Please, describe detailedly what difficulty you are in

I run the commands described in point 3 (I added some code to delete joint information about not dynamixel motors as here). If move the marker then press Plan and Execute button, motors move properly. If I repeat the process (plan and execute a trajectory) it works, but after a couple of times (not a fixed number -sometimes just 9 or 10 times, sometimes it requires a lot, around 20 minutes test-), the controller stops working. If I check the active processes, this controller uses ~1MiB of RAM memory when working well. When the controller failed I checked processes again and I note this node increases the memory usage until it fills RAM memory and crashes.

If I run the commands again, but don't plan and execute any trajectory (motors keep torque enabled), then the controller never fail.

routiful commented 5 years ago

open_manipulator_moveit launch file would load moveit_config for openmanipulator. Did you try to make your moveit_config including 2 joints?

jcgarciaca commented 5 years ago

I did not change open_manipulator. I just added some code in moveit_bridge to publish a trajectory message with only two joints as follow:

for(int i = 0; i < jnt_tra.points.size(); i++){
    // for joint 2 and 3 (index 1 and 2)
    trajectory_msgs::JointTrajectoryPoint point_dxl;
    for(int index = 1; index <= 2; index++){
      point_dxl.positions.push_back(jnt_tra.points[i].positions[index]);
      point_dxl.velocities.push_back(jnt_tra.points[i].velocities[index]);
      point_dxl.accelerations.push_back(jnt_tra.points[i].accelerations[index]);      
    }
    point_dxl.time_from_start = jnt_tra.points[i].time_from_start;
    dynamixel_jnt_tra.points.push_back(point_dxl);
}
dynamixel_workbench_pub_.publish(dynamixel_jnt_tra);

As I mentioned previously, it worked. But eventually the controller node (starts to increase RAM memory usage and then) crashes with message I posted.

Just for reference, I created my custom robot_moveit package with three joints (1 pololu joint and 2 dynamixel joints) and got same behaviour, it is the three joints move properly but eventually dynamixel controller fails.

routiful commented 5 years ago

trajectoryMsgCallback have represented some debug msgs when you had clicked Plan&Execute button.

https://github.com/ROBOTIS-GIT/dynamixel-workbench/blob/bf60cf8f17e8385f623cbe72236938b5950d3b56/dynamixel_workbench_controllers/src/dynamixel_workbench_controllers.cpp#L627

Can you show me which msgs are showed when it fails?

jcgarciaca commented 5 years ago

@routiful Thank you for your help. Finally I solved the issue. It was because eventually a trajectory with ~300 points was generated, and since uint8_t cnt capacity is 8bits, then while loop in trajectoryMsgCallback never finished.

routiful commented 5 years ago

Good :) I will fix it next release.