Skip to content

Setup motion capture

Ajay Shankar edited this page Nov 21, 2020 · 2 revisions

Motion capture systems (such as Vicon, OptiTrack etc) that have ROS interfaces are supported by Freyja's state_manager. For typical setups, all you need to do is to pass a launch argument with the right topic name. A default ENU convention is assumed for the motion-capture data.

Launch argument

The default freyja_controller.launch file takes an argument vicon_topic which is the full topic name (e.g., "/vicon/FLH1/FLH1").

Pre-checks

  • Verify that topic updates locally on a terminal:

    • Check topic updates on (rostopic echo -c <topic>).
    • Ensure high rate using (rostopic hz <topic>).

    Usual rates are ~200Hz, but lower rates are ok assuming the filter length is not too large. Filters are "sample domain", so a 21-element filter would lag too much for a 50Hz topic.

  • Verify that /current_state updates correctly after launching Freyja with the correct arg.:

    • /current_state/state_vector[0] and /current_state/state_vector[1] are the North and East components. Use rqt_plot to visualise.
    • /current_state/state_vector[8] is Yaw, and has a left-handed chirality (should be 0 when facing North, +90 when East..).

    Note: within an indoor-space, "north" is something you can arbitrarily define - does not have to be true north, as long as east is to the right. For Vicon (with the vicon_bridge ROS interface), the default ENU convention would mean that Vicon's +Y == N, +X == E, +Z == -D, and yaw=0 when vehicle faces Vicon's +Y.

Debugging Issues & Common Mistakes

  • Vicon object's rotation is incorrect.
    When creating object, face it along Vicon's +Y. Alternatively, rotate the axes after creating. Adapt for other motion capture systems.
  • Streaming Vicon over wireless/wifi.
    The packet delays may be unreliable over TCP/IP and can cause oscillations. Avoid if possible, and run over wired ethernet instead. Check /current_state/state_vector[12] to see the inter-message interval ("dt") -- it should be steady (and equal to 1/freq.).