ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Multiple rigid bodies crash optitrack node

asked 2015-09-09 03:18:05 -0500

vivek rk gravatar image

updated 2015-09-10 03:55:01 -0500

mgruhler gravatar image

I am running the optitrack mocap node found here. http://wiki.ros.org/mocap_optitrack

Everything is fine when i have 1 rigid body data streaming from my windows PC. If i enable more than one then the program shuts down immediately, without giving any error. This is what i see in the terminal

... logging to /home/vivekr/.ros/log/2ed18b8c-55ec-11e5-bb88-001fbc0efc2f/roslaunch-but-5283.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://but:52380/

SUMMARY
========

PARAMETERS
 * /mocap_node/rigid_bodies/1/child_frame_id: drone1
 * /mocap_node/rigid_bodies/1/parent_frame_id: world
 * /mocap_node/rigid_bodies/1/pose2d: Drone_1/ground_pose
 * /mocap_node/rigid_bodies/1/pose: Drone_1/pose
 * /mocap_node/rigid_bodies/2/frame_id: drone2
 * /mocap_node/rigid_bodies/2/parent_frame_id: world
 * /mocap_node/rigid_bodies/2/pose2d: Drone_2/ground_pose
 * /mocap_node/rigid_bodies/2/pose: Drone_2/pose
 * /mocap_node/rigid_bodies/3/child_frame_id: drone3
 * /mocap_node/rigid_bodies/3/parent_frame_id: world
 * /mocap_node/rigid_bodies/3/pose2d: Drone_3/ground_pose
 * /mocap_node/rigid_bodies/3/pose: Drone_3/pose
 * /mocap_node/rigid_bodies/4/child_frame_id: drone4
 * /mocap_node/rigid_bodies/4/parent_frame_id: world
 * /mocap_node/rigid_bodies/4/pose2d: Drone_4/ground_pose
 * /mocap_node/rigid_bodies/4/pose: Drone_4/pose
 * /mocap_node/rigid_bodies/5/child_frame_id: drone5
 * /mocap_node/rigid_bodies/5/parent_frame_id: world
 * /mocap_node/rigid_bodies/5/pose2d: Drone_5/ground_pose
 * /mocap_node/rigid_bodies/5/pose: Drone_5/pose
 * /rosdistro: jade
 * /rosversion: 1.11.13

NODES
  /
    mocap_node (mocap_optitrack/mocap_node)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[mocap_node-1]: started with pid [5301]
================================================================================REQUIRED process [mocap_node-1] has died!
process has died [pid 5301, exit code -11, cmd /home/vivekr/workspace/catkin/devel/lib/mocap_optitrack/mocap_node __name:=mocap_node __log:=/home/vivekr/.ros/log/2ed18b8c-55ec-11e5-bb88-001fbc0efc2f/mocap_node-1.log].
log file: /home/vivekr/.ros/log/2ed18b8c-55ec-11e5-bb88-001fbc0efc2f/mocap_node-1*.log
Initiating shutdown!
================================================================================
[mocap_node-1] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done

Can someone please help me out

Regards Vivek

edit retag flag offensive close merge delete

Comments

Well, we have it working with two rigid bodies. Have you tried this and not with 5 rigid bodies?

From the error output, it is basially not possible to extract any information, so it is hard to help you. Do you somehow have more information?

mgruhler gravatar image mgruhler  ( 2015-09-10 03:58:59 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-09-10 04:39:05 -0500

vivek rk gravatar image

I figured out what the problem was.

In the function parse(), the program does not add the counter for buffer exactly. To fix this error we need to add

seek(2);

after the line

//skip mean marker error

seek(sizeof(float));

This is in the for loop that keeps iterating for each rigid bodies. Since after the 1st rigid body the counter was not at the right place, the function

read_and_seek(model.rigidBodies[m].NumberOfMarkers);

would return a value like 24533 instead of 3.

So after the 1st rigid body the function

model.rigidBodies[m].marker = new Marker [model.rigidBodies[m].NumberOfMarkers];

would allocate more memory and the functions

size_t byte_count = model.rigidBodies[m].NumberOfMarkers * sizeof(Marker); memcpy(model.rigidBodies[m].marker, packet, byte_count);

So the value for bytecount was more than 60000 when it should have been 36 (since i have 3 markers), and this would lead the memcpy to acces data out of the buffer which caused the crash

So we correct this by adding the seek(2) which will get everything to the right indices

edit flag offensive delete link more

Comments

if this is actually a bug, could you open a PR to the original Repo? This would help fixing this for all users... Thanks

mgruhler gravatar image mgruhler  ( 2015-09-10 04:45:28 -0500 )edit

This is may be an obvious thing but I didn't understand how did you arrive at seek(2)? As in why 2?

aorait gravatar image aorait  ( 2016-02-08 11:31:19 -0500 )edit

@aorait looking at the code above and the sample from NatNet SDK for a long time i couldn't realize what was missing and where. So my next best option was to bruteforce it. So i started with seek(2), which will move it by 2 and it worked

vivek rk gravatar image vivek rk  ( 2016-02-09 07:36:33 -0500 )edit

@mig sorry i dont know how to use those advanced features of github

vivek rk gravatar image vivek rk  ( 2016-02-09 07:37:07 -0500 )edit

Hi! Same issue with multiple rigid bodies... Has anybody solved already this problem?

fapofa gravatar image fapofa  ( 2016-05-10 07:33:10 -0500 )edit

I've checked the NatNet SDK and find out that there is an extra data field in newer version of NatNet SDK. Use this branch will help resolve it.

GroundMelon gravatar image GroundMelon  ( 2016-05-19 04:47:45 -0500 )edit

@vivek rk I'm experiencing the same issue and it doesn't work even after making the mentioned changes, could you please help me out here ? I'm using motive 1.10.1 with ros indigo

kali gravatar image kali  ( 2016-12-10 14:01:25 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-09-09 03:18:05 -0500

Seen: 1,050 times

Last updated: Sep 10 '15