32 #include <QApplication> 36 #if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0) 40 #include <boost/bind.hpp> 43 #include <OgreSceneManager.h> 44 #include <OgreSceneNode.h> 45 #include <OgreLight.h> 46 #include <OgreViewport.h> 47 #include <OgreMaterialManager.h> 48 #include <OgreMaterial.h> 49 #include <OgreRenderWindow.h> 50 #include <OgreSharedPtr.h> 51 #include <OgreCamera.h> 53 #include <boost/filesystem.hpp> 94 const QVariant default_value = QVariant(),
95 const QString& description = QString(),
97 const char *changed_slot = 0,
98 QObject* receiver = 0 )
102 return (column == 0 && role == Qt::DecorationRole)
121 : ogre_root_(
Ogre::Root::getSingletonPtr() )
123 , shutting_down_(false)
124 , render_panel_( render_panel )
125 , time_update_timer_(0.0
f)
126 , frame_update_timer_(0.0
f)
127 , render_requested_(1)
129 , window_manager_(wm)
143 rviz::RenderSystem::RenderSystem::get()->prepareOverlays(
scene_manager_);
169 "Frame into which all data is transformed before being displayed.",
174 "Background color for the 3D view.",
178 "RViz will try to render this many frames per second.",
182 "Light source attached to the current 3D view.",
279 void createColorMaterial(
const std::string& name,
const Ogre::ColourValue& color,
bool use_self_illumination)
281 Ogre::MaterialPtr mat = Ogre::MaterialManager::getSingleton().create( name,
ROS_PACKAGE_NAME );
282 mat->setAmbient(color * 0.5
f);
283 mat->setDiffuse(color);
284 if( use_self_illumination )
286 mat->setSelfIllumination(color);
288 mat->setLightingEnabled(
true);
289 mat->setReceiveShadows(
false);
313 float wall_dt = wall_diff.
toSec();
314 float ros_dt = ros_diff.
toSec();
394 typedef std::vector<std::string>
V_string;
405 std::stringstream ss;
406 ss <<
"No tf data. Actual error: " << error;
482 QApplication::setOverrideCursor(QCursor(Qt::WaitCursor));
486 QApplication::restoreOverrideCursor();
539 #if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0) 540 QWindow* window = vme.
panel->windowHandle();
543 double pixel_ratio = window->devicePixelRatio();
544 _vme.
x =
static_cast<int>(pixel_ratio * _vme.
x);
545 _vme.
y =
static_cast<int>(pixel_ratio * _vme.
y);
546 _vme.
last_x =
static_cast<int>(pixel_ratio * _vme.
last_x);
547 _vme.
last_y =
static_cast<int>(pixel_ratio * _vme.
last_y);
555 vme.
panel->setCursor( QCursor( Qt::ArrowCursor ) );
virtual void save(Config config) const
Save subproperties and the list of displays in this group to the given Config node.
virtual QColor getColor() const
RenderPanel * render_panel_
ros::WallTime last_update_wall_time_
void updateBackgroundColor()
void initialize()
Do initialization that wasn't done in constructor. Initializes tool manager, view manager...
ros::WallDuration wall_clock_elapsed_
OgreRenderQueueClearer * ogre_render_queue_clearer_
ViewController * getCurrent() const
Return the current ViewController in use for the main RenderWindow.
VisualizationManager(RenderPanel *render_panel, WindowManagerInterface *wm=0, boost::shared_ptr< tf::TransformListener > tf=boost::shared_ptr< tf::TransformListener >())
Constructor Creates managers and sets up global properties.
IntProperty * fps_property_
ros::NodeHandle update_nh_
ros::NodeHandle threaded_nh_
DisplayGroup * root_display_group_
boost::unordered_map< CollObjectHandle, Picked > M_Picked
VisualizationManagerPrivate * private_
void update()
Clear the internal cache.
void onUpdate()
Call update() on all managed objects.
void configChanged()
Emitted whenever the display configuration changes.
void setAutoRender(bool auto_render)
virtual int getInt() const
Return the internal property value as an integer.
Display * createDisplay(const QString &class_lookup_name, const QString &name, bool enabled)
Create and add a display to this panel, by class lookup name.
Ogre::Light * directional_light_
TfFrameProperty * fixed_frame_property_
Frame to transform fixed data to.
IconizedProperty(const QString &name=QString(), const QVariant default_value=QVariant(), const QString &description=QString(), Property *parent=0, const char *changed_slot=0, QObject *receiver=0)
void setSelection(const M_Picked &objs)
StatusList * global_status_
A single element of a property tree, with a name, value, description, and possibly children...
virtual QVariant getViewData(int column, int role) const
Return data appropriate for the given column (0 or 1) and role for this Property. ...
virtual void load(const Config &config)
Load subproperties and the list of displays in this group from the given Config node, which must be a map.
void preUpdate()
Emitted before updating all Displays.
virtual bool setValue(const QVariant &new_value)
Override from Property to resolve the frame name on the way in.
void setFixedFrame(const QString &frame)
Set the coordinate frame we should be transforming all fixed data into.
virtual QVariant getViewData(int column, int role) const
Return data appropriate for the given column (0 or 1) and role for this Property. ...
ros::CallbackQueue threaded_queue_
void unlockRender()
Unlock a mutex, allowing calls to Ogre::Root::renderOneFrame().
BoolProperty * default_light_enabled_property_
volatile bool shutting_down_
ViewManager * view_manager_
ros::Time getTime()
Get current time, depending on the sync mode.
void lockRender()
Lock a mutex to delay calls to Ogre::Root::renderOneFrame().
BitAllocator visibility_bit_allocator_
ros::CallbackQueueInterface * getUpdateQueue()
Return the CallbackQueue using the main GUI thread.
ToolManager * tool_manager_
Property specialized to provide max/min enforcement for integers.
tf::TransformListener * getTFClient() const
Convenience function: returns getFrameManager()->getTFClient().
void emitStatusUpdate(const QString &message)
Emits statusUpdate() signal with the given message.
Display * createDisplay(const QString &class_id)
void handleMouseEvent(const ViewportMouseEvent &event)
Handle a mouse event.
Configuration data storage class.
ros::CallbackQueueInterface * getThreadedQueue()
Return a CallbackQueue using a different thread than the main GUI one.
Ogre::ColourValue qtToOgre(const QColor &c)
virtual bool getBool() const
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
void createColorMaterial(const std::string &name, const Ogre::ColourValue &color, bool use_self_illumination)
double getWallClock()
Return the wall clock time, in seconds since 1970.
QTimer * update_timer_
Update timer. Display::update is called on each display whenever this timer fires.
Helper class for transforming data into Ogre's world frame (the fixed frame).
double getROSTimeElapsed()
Return the ROS time in seconds since the last reset.
void updateDefaultLightVisible()
void addDisplay(Display *display, bool enabled)
Add a display to be managed by this panel.
A Display object which stores other Displays as children.
void handleChar(QKeyEvent *event, RenderPanel *panel)
Handle a single key event for a given RenderPanel.
void statusUpdate(const QString &message)
Emitted during file-loading and initialization to indicate progress.
void setCallbackQueue(CallbackQueueInterface *queue)
Ogre::Camera * getCamera() const
void setRenderPanel(RenderPanel *render_panel)
Set the 3D view widget whose view will be controlled by ViewController instances from by this ViewMan...
boost::thread_group threaded_queue_threads_
Config mapMakeChild(const QString &key)
Create a child node stored with the given key, and return the child.
void queueRender()
Queues a render. Multiple calls before a render happens will only cause a single render.
ros::Time ros_time_begin_
virtual void removeAllDisplays()
Remove and destroy all child Displays, but preserve any non-Display children.
ros::Time last_update_ros_time_
Update stopwatch. Stores how long it's been since the last update.
double getROSTime()
Return the ROS time, in seconds.
void onToolChanged(Tool *)
tf::TransformListener * getTFClient()
Return the tf::TransformListener used to receive transform data.
virtual void reset()
Reset this and all child Displays.
virtual void update(float wall_dt, float ros_dt)
Call update() on all child Displays.
Property * global_options_
void update(float wall_dt, float ros_dt)
void setBackgroundColor(Ogre::ColourValue color)
void load(const Config &config)
Load the properties of each Display and most editable rviz data.
void setFixedFrame(const QString &fixed_frame)
Set the fixed frame in this display.
uint32_t render_requested_
std::vector< std::string > V_string
ros::WallTime wall_clock_begin_
void save(Config config) const
Save the properties of each Display and most editable rviz data.
Ogre::Root * ogre_root_
Ogre Root.
void setDragDropClass(const QString &drag_drop_class)
FrameManager * frame_manager_
virtual void setStatus(const QString &message)
void createColorMaterials()
void setFixedFrame(const std::string &frame)
Set the frame to consider "fixed", into which incoming data is transformed.
void setEnabled(bool enabled)
Enable or disable this Display.
void setStatus(Level level, const QString &name, const QString &text)
boost::mutex render_mutex_
void setName(const QString &name)
Overridden from Property to set associated widget title to the new name.
Property specialized to provide getter for booleans.
double getWallClockElapsed()
Return the wall clock time in seconds since the last reset.
void removeAllDisplays()
Remove and delete all displays.
bool frameHasProblems(const std::string &frame, ros::Time time, std::string &error)
Check to see if a frame exists in the tf::TransformListener.
DisplayFactory * display_factory_
virtual ~VisualizationManager()
Destructor Stops update timers and destroys all displays, tools, and managers.
void notifyConfigChanged()
Notify this VisualizationManager that something about its display configuration has changed...
ColorProperty * background_color_property_
void initialize(DisplayContext *context)
Main initialization, called after constructor, before load() or setEnabled().
PropertyTreeModel * display_property_tree_model_
Config mapGetChild(const QString &key) const
If the referenced Node is a Map and it has a child with the given key, return a reference to the chil...
void save(Config config) const
ROSCPP_DECL void spinOnce()
virtual void addDisplay(Display *child)
Add a child Display to the end of the list of Displays.
float frame_update_timer_
Ogre::SceneManager * scene_manager_
Ogre scene manager associated with this panel.
void startUpdate()
Start timers. Creates and starts the update and idle timers, both set to 30Hz (33ms).
ros::Duration ros_time_elapsed_
QPixmap loadPixmap(QString url, bool fill_cache)
void resetTime()
Resets the wall and ROS elapsed time to zero and calls resetDisplays().
QString getFixedFrame() const
Return the fixed frame name.
SelectionManager * selection_manager_
uint32_t default_visibility_bit_
void load(const Config &config)
uint32_t allocBit()
Return a uint32 with a single bit "on" (previously unused), or a 0 if all bits are already allocated...
void threadedQueueThreadFunc()