Skip to content

Commit 764fd40

Browse files
committed
Expanded and documented PlantFlagTool.
Also updated docs with github links and did a little updating for the latest version of the RViz API.
1 parent c1f03cb commit 764fd40

13 files changed

+366
-37
lines changed

rviz_plugin_tutorials/CMakeLists.txt

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -19,18 +19,19 @@ add_definitions(-DQT_NO_KEYWORDS)
1919
## Qt's meta-object compiler.
2020
qt4_wrap_cpp(MOC_FILES
2121
src/drive_widget.h
22-
src/teleop_panel.h
2322
src/imu_display.h
23+
src/plant_flag_tool.h
24+
src/teleop_panel.h
2425
)
2526

2627
## Here we specify the list of source files, including the output of
2728
## the previous command which is stored in ``${MOC_FILES}``.
2829
set(SOURCE_FILES
2930
src/drive_widget.cpp
30-
src/teleop_panel.cpp
31-
src/plant_flag_tool.cpp
3231
src/imu_display.cpp
3332
src/imu_visual.cpp
33+
src/plant_flag_tool.cpp
34+
src/teleop_panel.cpp
3435
${MOC_FILES}
3536
)
3637

324 Bytes
Loading

rviz_plugin_tutorials/src/doc/building_and_exporting.rst

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,13 @@ The contents of plugin_description.xml then look like this:
4040
Displays direction and scale of accelerations from sensor_msgs/Imu messages.
4141
</description>
4242
</class>
43+
<class name="rviz_plugin_tutorials/PlantFlag"
44+
type="rviz_plugin_tutorials::PlantFlagTool"
45+
base_class_type="rviz::Tool">
46+
<description>
47+
Tool for planting flags on the ground plane in rviz.
48+
</description>
49+
</class>
4350
</library>
4451
4552
The first line says that the compiled library lives in
@@ -67,13 +74,14 @@ This specifies the name, type, base class, and description of the
6774
class. The *name* field must be a combination of the first two
6875
strings given to the ``PLUGINLIB_DECLARE_CLASS()`` macro in the source
6976
file. It must be the "package" name, a "/" slash, then the "display
70-
name" for the class.
77+
name" for the class. The "display name" is the name used for the
78+
class in the user interface.
7179

7280
The *type* entry must be the fully-qualified class name, including any
7381
namespace(s) it is inside.
7482

75-
The *base_class_type* is either ``rviz::Panel`` for a panel class, or
76-
``rviz::Display`` for a display class.
83+
The *base_class_type* is usually one of ``rviz::Panel``,
84+
``rviz::Display``, ``rviz::Tool``, or ``rviz::ViewController``.
7785

7886
The *description* subsection is a simple text description of the
7987
class, which is shown in the class-chooser dialog and in the Displays

rviz_plugin_tutorials/src/doc/conf.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,4 +22,4 @@
2222
# The name of the Pygments (syntax highlighting) style to use.
2323
pygments_style = 'sphinx'
2424

25-
extlinks = {'svndir': ('https://code.ros.org/svn/ros-pkg/stacks/visualization_tutorials/branches/visualization_tutorials-0.6/rviz_plugin_tutorials/%s', '')}
25+
extlinks = {'srcdir': ('https://github.com/ros-visualization/visualization_tutorials/tree/groovy-devel/rviz_plugin_tutorials/%s', '')}

rviz_plugin_tutorials/src/doc/display_plugin_tutorial.rst

Lines changed: 10 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -25,36 +25,36 @@ The Plugin Code
2525
---------------
2626

2727
The code for ImuDisplay is in these files:
28-
:svndir:`src/imu_display.h`,
29-
:svndir:`src/imu_display.cpp`,
30-
:svndir:`src/imu_visual.h`, and
31-
:svndir:`src/imu_visual.cpp`.
28+
:srcdir:`src/imu_display.h`,
29+
:srcdir:`src/imu_display.cpp`,
30+
:srcdir:`src/imu_visual.h`, and
31+
:srcdir:`src/imu_visual.cpp`.
3232

3333
imu_display.h
3434
^^^^^^^^^^^^^
3535

36-
The full text of imu_display.h is here: :svndir:`src/imu_display.h`
36+
The full text of imu_display.h is here: :srcdir:`src/imu_display.h`
3737

3838
.. tutorial-formatter:: ../imu_display.h
3939

4040
imu_display.cpp
4141
^^^^^^^^^^^^^^^
4242

43-
The full text of imu_display.cpp is here: :svndir:`src/imu_display.cpp`
43+
The full text of imu_display.cpp is here: :srcdir:`src/imu_display.cpp`
4444

4545
.. tutorial-formatter:: ../imu_display.cpp
4646

4747
imu_visual.h
4848
^^^^^^^^^^^^
4949

50-
The full text of imu_visual.h is here: :svndir:`src/imu_visual.h`
50+
The full text of imu_visual.h is here: :srcdir:`src/imu_visual.h`
5151

5252
.. tutorial-formatter:: ../imu_visual.h
5353

5454
imu_visual.cpp
5555
^^^^^^^^^^^^^^
5656

57-
The full text of imu_visual.cpp is here: :svndir:`src/imu_visual.cpp`
57+
The full text of imu_visual.cpp is here: :srcdir:`src/imu_visual.cpp`
5858

5959
.. tutorial-formatter:: ../imu_visual.cpp
6060

@@ -90,7 +90,7 @@ topic name of the display to a source of sensor_msgs/Imu messages.
9090

9191
If you don't happen to have an IMU or other source of sensor_msgs/Imu
9292
messages, you can test the plugin with a Python script like this:
93-
:svndir:`scripts/send_test_msgs.py`.
93+
:srcdir:`scripts/send_test_msgs.py`.
9494

9595
The script publishes on the "/test_imu" topic, so enter that.
9696

@@ -122,11 +122,7 @@ This ImuDisplay is not yet a terribly useful Display class. Extensions to make
122122

123123
To add a gravity compensation option, you might take steps like these:
124124

125-
- Add a new ``bool gravity_compensation_on_`` property to ImuDisplay to store whether the option is on or off.
126-
- Add getter and setter functions for it.
127-
- Add a new ``rviz::BoolPropertyWPtr`` to ImuDisplay to show the property in the property editor.
128-
- Add a new ``setGravityCompensation(bool)`` function to
129-
ImuVisual to tell the visual whether to subtract out gravity or not.
125+
- Add a new ``rviz::BoolProperty`` to ImuDisplay to store whether the option is on or off.
130126
- Compute the direction of gravity relative to the Imu frame
131127
orientation (as set in ImuVisual::setFrameOrientation()) and
132128
subtract it from the acceleration vector each time in
55.9 KB
Loading

rviz_plugin_tutorials/src/doc/index.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,3 +10,6 @@ containing two main classes: ImuDisplay and TeleopPanel.
1010
- :doc:`panel_plugin_tutorial` is an example of an rviz::Panel
1111
subclass which shows a simple control input for sending velocities
1212
to a mobile base.
13+
14+
- :doc:`tool_plugin_tutorial` is an example of an rviz::Tool
15+
subclass which lets you plant flag markers on the Z=0 plane.

rviz_plugin_tutorials/src/doc/panel_plugin_tutorial.rst

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -35,36 +35,36 @@ The Plugin Code
3535
---------------
3636

3737
The code for TeleopPanel is in these files:
38-
:svndir:`src/teleop_panel.h`,
39-
:svndir:`src/teleop_panel.cpp`,
40-
:svndir:`src/drive_widget.h`, and
41-
:svndir:`src/drive_widget.cpp`.
38+
:srcdir:`src/teleop_panel.h`,
39+
:srcdir:`src/teleop_panel.cpp`,
40+
:srcdir:`src/drive_widget.h`, and
41+
:srcdir:`src/drive_widget.cpp`.
4242

4343
teleop_panel.h
4444
^^^^^^^^^^^^^^
4545

46-
The full text of teleop_panel.h is here: :svndir:`src/teleop_panel.h`
46+
The full text of teleop_panel.h is here: :srcdir:`src/teleop_panel.h`
4747

4848
.. tutorial-formatter:: ../teleop_panel.h
4949

5050
teleop_panel.cpp
5151
^^^^^^^^^^^^^^^^
5252

53-
The full text of teleop_panel.cpp is here: :svndir:`src/teleop_panel.cpp`
53+
The full text of teleop_panel.cpp is here: :srcdir:`src/teleop_panel.cpp`
5454

5555
.. tutorial-formatter:: ../teleop_panel.cpp
5656

5757
drive_widget.h
5858
^^^^^^^^^^^^^^
5959

60-
The full text of drive_widget.h is here: :svndir:`src/drive_widget.h`
60+
The full text of drive_widget.h is here: :srcdir:`src/drive_widget.h`
6161

6262
.. tutorial-formatter:: ../drive_widget.h
6363

6464
drive_widget.cpp
6565
^^^^^^^^^^^^^^^^
6666

67-
The full text of drive_widget.cpp is here: :svndir:`src/drive_widget.cpp`
67+
The full text of drive_widget.cpp is here: :srcdir:`src/drive_widget.cpp`
6868

6969
.. tutorial-formatter:: ../drive_widget.cpp
7070

Lines changed: 88 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,88 @@
1+
PlantFlagTool
2+
=============
3+
4+
Overview
5+
--------
6+
7+
This tutorial shows how to write a new tool for RViz.
8+
9+
In RViz, a tool is a class that determines how mouse events interact
10+
with the visualizer. In this example we describe PlantFlagTool which
11+
lets you place "flag" markers in the 3D scene.
12+
13+
The source code for this tutorial is in the rviz_plugin_tutorials
14+
package. You can check out the source directly or (if you use Ubuntu)
15+
you can just apt-get install the pre-compiled Debian package like so::
16+
17+
sudo apt-get install ros-fuerte-visualization-tutorials
18+
19+
Here is an example of what the new PlantFlagTool can do:
20+
21+
.. image:: flags.png
22+
23+
The Plugin Code
24+
---------------
25+
26+
The code for PlantFlagTool is in these files:
27+
:srcdir:`src/plant_flag_tool.h`, and
28+
:srcdir:`src/plant_flag_tool.cpp`.
29+
30+
plant_flag_tool.h
31+
^^^^^^^^^^^^^^^^^
32+
33+
The full text of plant_flag_tool.h is here: :srcdir:`src/plant_flag_tool.h`
34+
35+
.. tutorial-formatter:: ../plant_flag_tool.h
36+
37+
plant_flag_tool.cpp
38+
^^^^^^^^^^^^^^^^^^^
39+
40+
The full text of plant_flag_tool.cpp is here: :srcdir:`src/plant_flag_tool.cpp`
41+
42+
.. tutorial-formatter:: ../plant_flag_tool.cpp
43+
44+
.. include:: building_and_exporting.rst
45+
46+
Trying It Out
47+
-------------
48+
49+
Once your RViz plugin is compiled and exported, simply run rviz normally::
50+
51+
rosrun rviz rviz
52+
53+
and rviz will use pluginlib to find all the plugins exported to it.
54+
55+
Add a PlantFlag tool by clicking on the "+" button in the toolbar and
56+
selecting "PlantFlag" from the list under your plugin package name
57+
(here it is "rviz_plugin_tutorials").
58+
59+
Once "PlantFlag" is in your toolbar, click it or press "l" (the
60+
shortcut key) to start planting flags. Open the "Tool Properties"
61+
panel to see the positions of the flags you have planted.
62+
63+
Currently the only way to remove the flags is to delete the PlantFlag
64+
tool, which you do by pressing the "-" (minus sign) button in the
65+
toolbar and selecting "PlantFlag".
66+
67+
Next Steps
68+
----------
69+
70+
PlantFlag as shown here is not terribly useful yet. Some extensions to make it more useful might be:
71+
72+
- Add the ability to delete, re-position, and re-name existing flags.
73+
- Publish ROS messages with the names and locations of the flags.
74+
75+
To modify existing flags, you might:
76+
77+
- Change processMouseEvent() to notice when the mouse is pointing near an existing flag.
78+
- When it is:
79+
80+
- make the flag highlight.
81+
- If the right button is pressed, show a context menu with delete and rename options.
82+
- If the left button is pressed, begin dragging the existing flag around.
83+
84+
Conclusion
85+
----------
86+
87+
There are many possibilities for new types of interaction with RViz.
88+
We look forward to seeing what you make.

rviz_plugin_tutorials/src/flag.h

Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
/*
2+
* Copyright (c) 2012, Willow Garage, Inc.
3+
* All rights reserved.
4+
*
5+
* Redistribution and use in source and binary forms, with or without
6+
* modification, are permitted provided that the following conditions are met:
7+
*
8+
* * Redistributions of source code must retain the above copyright
9+
* notice, this list of conditions and the following disclaimer.
10+
* * Redistributions in binary form must reproduce the above copyright
11+
* notice, this list of conditions and the following disclaimer in the
12+
* documentation and/or other materials provided with the distribution.
13+
* * Neither the name of the Willow Garage, Inc. nor the names of its
14+
* contributors may be used to endorse or promote products derived from
15+
* this software without specific prior written permission.
16+
*
17+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21+
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
* POSSIBILITY OF SUCH DAMAGE.
28+
*/
29+
#ifndef FLAG_H
30+
#define FLAG_H
31+
32+
namespace rviz_plugin_tutorials
33+
{
34+
35+
class Flag: public rviz::Property
36+
{
37+
Q_OBJECT
38+
public:
39+
Flag();
40+
};
41+
42+
}
43+
44+
#endif // FLAG_H

0 commit comments

Comments
 (0)