|
| 1 | +ImuDisplay |
| 2 | +========== |
| 3 | + |
| 4 | +The RViz plugin API and library API are preliminary in Fuerte. We |
| 5 | +welcome feedback about how to make them more powerful and easier to |
| 6 | +program with. We expect the APIs to change (possibly significantly) |
| 7 | +between Fuerte and Groovy. |
| 8 | + |
| 9 | +Overview |
| 10 | +-------- |
| 11 | + |
| 12 | +This tutorial shows how to write a simple Display plugin for RViz. |
| 13 | + |
| 14 | +RViz does not currently have a way to display sensor_msgs/Imu messages |
| 15 | +directly. The code in this tutorial implements a subclass of |
| 16 | +rviz::Display to do so. |
| 17 | + |
| 18 | +The source code for this tutorial is in the rviz_plugin_tutorials |
| 19 | +package. You can check out the source directly or (if you use Ubuntu) |
| 20 | +you can just apt-get install the pre-compiled Debian package like so:: |
| 21 | + |
| 22 | + sudo apt-get install ros-fuerte-visualization-tutorials |
| 23 | + |
| 24 | +Here is what the new ImuDisplay output looks like, showing a sequence of |
| 25 | +sensor_msgs/Imu messages from the test script: |
| 26 | + |
| 27 | +.. image:: imu_arrows.png |
| 28 | + |
| 29 | +The Plugin Code |
| 30 | +--------------- |
| 31 | + |
| 32 | +The code for ImuDisplay is in these files: |
| 33 | +:svndir:`src/imu_display.h`, |
| 34 | +:svndir:`src/imu_display.cpp`, |
| 35 | +:svndir:`src/imu_visual.h`, and |
| 36 | +:svndir:`src/imu_visual.cpp`. |
| 37 | + |
| 38 | +imu_display.h |
| 39 | +^^^^^^^^^^^^^ |
| 40 | + |
| 41 | +The full text of imu_display.h is here: :svndir:`src/imu_display.h` |
| 42 | + |
| 43 | +.. tutorial-formatter:: ../imu_display.h |
| 44 | + |
| 45 | +imu_display.cpp |
| 46 | +^^^^^^^^^^^^^^^ |
| 47 | + |
| 48 | +The full text of imu_display.cpp is here: :svndir:`src/imu_display.cpp` |
| 49 | + |
| 50 | +.. tutorial-formatter:: ../imu_display.cpp |
| 51 | + |
| 52 | +imu_visual.h |
| 53 | +^^^^^^^^^^^^ |
| 54 | + |
| 55 | +The full text of imu_visual.h is here: :svndir:`src/imu_visual.h` |
| 56 | + |
| 57 | +.. tutorial-formatter:: ../imu_visual.h |
| 58 | + |
| 59 | +imu_visual.cpp |
| 60 | +^^^^^^^^^^^^^^ |
| 61 | + |
| 62 | +The full text of imu_visual.cpp is here: :svndir:`src/imu_visual.cpp` |
| 63 | + |
| 64 | +.. tutorial-formatter:: ../imu_visual.cpp |
| 65 | + |
| 66 | +Building the Plugin |
| 67 | +------------------- |
| 68 | + |
| 69 | +.. tutorial-formatter:: ../../CMakeLists.txt |
| 70 | + |
| 71 | +To build the plugin, just do the normal "rosmake" thing:: |
| 72 | + |
| 73 | + rosmake rviz_plugin_tutorials |
| 74 | + |
| 75 | +Exporting the Plugin |
| 76 | +-------------------- |
| 77 | + |
| 78 | +For the plugin to be found and understood by other ROS packages (in |
| 79 | +this case, rviz), it needs a "plugin_description.xml" file. This file |
| 80 | +can be named anything you like, as it is specified in the plugin |
| 81 | +package's "manifest.xml" file like so: |
| 82 | + |
| 83 | +.. code-block:: xml |
| 84 | +
|
| 85 | + <export> |
| 86 | + <rviz plugin="${prefix}/plugin_description.xml"/> |
| 87 | + </export> |
| 88 | +
|
| 89 | +The contents of plugin_description.xml then look like this: |
| 90 | + |
| 91 | +.. code-block:: xml |
| 92 | +
|
| 93 | + <library path="lib/librviz_plugin_tutorials"> |
| 94 | + <class name="rviz_plugin_tutorials/Teleop" |
| 95 | + type="rviz_plugin_tutorials::TeleopPanel" |
| 96 | + base_class_type="rviz::Panel"> |
| 97 | + <description> |
| 98 | + A panel widget allowing simple diff-drive style robot base control. |
| 99 | + </description> |
| 100 | + </class> |
| 101 | + <class name="rviz_plugin_tutorials/Imu" |
| 102 | + type="rviz_plugin_tutorials::ImuDisplay" |
| 103 | + base_class_type="rviz::Display"> |
| 104 | + <description> |
| 105 | + Displays direction and scale of accelerations from sensor_msgs/Imu messages. |
| 106 | + </description> |
| 107 | + </class> |
| 108 | + </library> |
| 109 | +
|
| 110 | +The first line says that the compiled library lives in |
| 111 | +lib/librviz_plugin_tutorials (the ".so" ending is appended by |
| 112 | +pluginlib according to the OS). This path is relative to the top |
| 113 | +directory of the package: |
| 114 | + |
| 115 | +.. code-block:: xml |
| 116 | +
|
| 117 | + <library path="lib/librviz_plugin_tutorials"> |
| 118 | +
|
| 119 | +The next section is a ``class`` entry describing the TeleopPanel: |
| 120 | + |
| 121 | +.. code-block:: xml |
| 122 | +
|
| 123 | + <class name="rviz_plugin_tutorials/Teleop" |
| 124 | + type="rviz_plugin_tutorials::TeleopPanel" |
| 125 | + base_class_type="rviz::Panel"> |
| 126 | + <description> |
| 127 | + A panel widget allowing simple diff-drive style robot base control. |
| 128 | + </description> |
| 129 | + </class> |
| 130 | +
|
| 131 | +This specifies the name, type, base class, and description of the |
| 132 | +class. The *name* field must be a combination of the first two |
| 133 | +strings given to the ``PLUGINLIB_DECLARE_CLASS()`` macro in the source |
| 134 | +file. It must be the "package" name, a "/" slash, then the "display |
| 135 | +name" for the class. |
| 136 | + |
| 137 | +The *type* entry must be the fully-qualified class name, including any |
| 138 | +namespace(s) it is inside. |
| 139 | + |
| 140 | +The *base_class_type* is either ``rviz::Panel`` for a panel class, or |
| 141 | +``rviz::Display`` for a display class. |
| 142 | + |
| 143 | +The *description* subsection is a simple text description of the |
| 144 | +class, which is shown in the class-chooser dialog and in the Displays |
| 145 | +panel help area. This section can contain HTML, including hyperlinks, |
| 146 | +but the markup must be escaped to avoid being interpreted as XML |
| 147 | +markup. For example a link tag might look like: ``<a |
| 148 | +href="my-web-page.html">``. |
| 149 | + |
| 150 | +Trying It Out |
| 151 | +------------- |
| 152 | + |
| 153 | +Once your RViz plugin is compiled and exported, simply run rviz normally:: |
| 154 | + |
| 155 | + rosrun rviz rviz |
| 156 | + |
| 157 | +and rviz will use pluginlib to find all the plugins exported to it. |
| 158 | + |
| 159 | +Add an ImuDisplay by clicking the "Add" button at the bottom of the |
| 160 | +"Displays" panel (or by typing Control-N), then scrolling down through |
| 161 | +the available displays until you see "Imu" under your plugin package |
| 162 | +name (here it is "rviz_plugin_tutorials"). |
| 163 | + |
| 164 | +.. image:: imu_plugin.png |
| 165 | + |
| 166 | +If "Imu" is not in your list of Display Types, look through RViz's |
| 167 | +console output for error messages relating to plugin loading. Some common |
| 168 | +problems are: |
| 169 | + |
| 170 | +- not having a plugin_description.xml file, |
| 171 | +- not exporting it in the manifest.xml file, or |
| 172 | +- not properly referencing the library file (like |
| 173 | + librviz_plugin_tutorials.so) from plugin_description.xml. |
| 174 | + |
| 175 | +Once you've added the Imu display to RViz, you just need to set the |
| 176 | +topic name of the display to a source of sensor_msgs/Imu messages. |
| 177 | + |
| 178 | +If you don't happen to have an IMU or other source of sensor_msgs/Imu |
| 179 | +messages, you can test the plugin with a Python script like this: |
| 180 | +:svndir:`scripts/send_test_msgs.py`. |
| 181 | + |
| 182 | +The script publishes on the "/test_imu" topic, so enter that. |
| 183 | + |
| 184 | +The script publishes both Imu messages and a moving TF frame |
| 185 | +("/base_link" relative to "/map"), so make sure your "Fixed Frame" is |
| 186 | +set to "/map". |
| 187 | + |
| 188 | +Finally, adjust the "History Length" parameter of the Imu display to |
| 189 | +10 and you should see something like the picture at the top of this |
| 190 | +page. |
| 191 | + |
| 192 | +Note: If you use this to visualize messages from an *actual* IMU, the |
| 193 | +arrows are going to be huge compared to most robots: |
| 194 | + |
| 195 | +.. image:: real_imu.png |
| 196 | + |
| 197 | +(Note the PR2 robot at the base of the purple arrow.) This is because |
| 198 | +the Imu acceleration units are meters per second squared, and gravity |
| 199 | +is 9.8 m/s^2, and we haven't applied any scaling or gravity |
| 200 | +compensation to the acceleration vectors. |
| 201 | + |
| 202 | +Next Steps |
| 203 | +---------- |
| 204 | + |
| 205 | +This ImuDisplay is not yet a terribly useful Display class. Extensions to make it more useful might be: |
| 206 | + |
| 207 | +- Add a gravity-compensation option to the acceleration vector. |
| 208 | +- Visualize more of the data in the Imu messages. |
| 209 | + |
| 210 | +To add a gravity compensation option, you might take steps like these: |
| 211 | + |
| 212 | +- Add a new ``bool gravity_compensation_on_`` property to ImuDisplay to store whether the option is on or off. |
| 213 | +- Add getter and setter functions for it. |
| 214 | +- Add a new ``rviz::BoolPropertyWPtr`` to ImuDisplay to show the property in the property editor. |
| 215 | +- Add a new ``setGravityCompensation(bool)`` function to |
| 216 | + ImuVisual to tell the visual whether to subtract out gravity or not. |
| 217 | +- Compute the direction of gravity relative to the Imu frame |
| 218 | + orientation (as set in ImuVisual::setFrameOrientation()) and |
| 219 | + subtract it from the acceleration vector each time in |
| 220 | + ImuVisual::setMessage(). |
| 221 | + |
| 222 | +Since ImuVisual takes complete Imu messages as input, adding |
| 223 | +visualizations of more of the Imu data only needs modifications to |
| 224 | +ImuVisual. Imu data displays might look like: |
| 225 | + |
| 226 | +- orientation: An rviz::Axes object at the Imu reference frame, turned to show the orientation. |
| 227 | +- angular_velocity: Maybe a line to show the axis of rotation and a 3D arrow curving around it to show the speed of rotation? |
| 228 | +- orientation_covariance: Maybe this is an ellipse at the end of each of the X, Y, and Z axes showing the orientation? |
| 229 | +- linear_acceleration_covariance: Maybe this is an ellipsoid at the end of the acceleration arrow? |
| 230 | + |
| 231 | +As all this might be visually cluttered, it may make sense to include boolean options to enable or disable some of them. |
0 commit comments