Classes | Public Types | Public Member Functions | Static Public Member Functions | Private Types | Private Slots | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
rviz::SelectionManager Class Reference

#include <selection_manager.h>

Inheritance diagram for rviz::SelectionManager:
Inheritance graph
[legend]

Classes

struct  Highlight
 

Public Types

enum  SelectType { Add, Remove, Replace }
 

Public Member Functions

void addObject (CollObjectHandle obj, SelectionHandler *handler)
 
void addSelection (const M_Picked &objs)
 
void clearHandlers ()
 
CollObjectHandle createHandle ()
 
void enableInteraction (bool enable)
 
void focusOnSelection ()
 
bool get3DPatch (Ogre::Viewport *viewport, const int x, const int y, const unsigned width, const unsigned height, const bool skip_missing, std::vector< Ogre::Vector3 > &result_points)
 Gets the 3D points in a box around a point in a view port. More...
 
bool get3DPoint (Ogre::Viewport *viewport, const int x, const int y, Ogre::Vector3 &result_point)
 
SelectionHandlergetHandler (CollObjectHandle obj)
 
bool getInteractionEnabled ()
 
bool getPatchDepthImage (Ogre::Viewport *viewport, const int x, const int y, const unsigned width, const unsigned height, std::vector< float > &depth_vector)
 Renders a depth image in a box around a point in a view port. More...
 
PropertyTreeModelgetPropertyModel ()
 
const M_PickedgetSelection ()
 
Ogre::Technique * handleSchemeNotFound (unsigned short scheme_index, const Ogre::String &scheme_name, Ogre::Material *original_material, unsigned short lod_index, const Ogre::Renderable *rend) override
 
void highlight (Ogre::Viewport *viewport, int x1, int y1, int x2, int y2)
 
void initialize ()
 
void pick (Ogre::Viewport *viewport, int x1, int y1, int x2, int y2, M_Picked &results, bool single_render_pass=false)
 
void removeHighlight ()
 
void removeObject (CollObjectHandle obj)
 
void removeSelection (const M_Picked &objs)
 
void renderQueueStarted (uint8_t queueGroupId, const std::string &invocation, bool &skipThisInvocation) override
 
void select (Ogre::Viewport *viewport, int x1, int y1, int x2, int y2, SelectType type)
 
 SelectionManager (VisualizationManager *manager)
 
void setDebugMode (bool debug)
 Enables or disables publishing of picking and depth rendering images. More...
 
void setSelection (const M_Picked &objs)
 
void setTextureSize (unsigned size)
 
void update ()
 
 ~SelectionManager () override
 

Static Public Member Functions

static Ogre::ColourValue handleToColor (CollObjectHandle handle)
 
static void setPickColor (const Ogre::ColourValue &color, Ogre::SceneNode *node)
 
static void setPickColor (const Ogre::ColourValue &color, Ogre::MovableObject *object)
 
static void setPickData (CollObjectHandle handle, const Ogre::ColourValue &color, Ogre::SceneNode *node)
 
static void setPickData (CollObjectHandle handle, const Ogre::ColourValue &color, Ogre::MovableObject *object)
 
static void setPickHandle (CollObjectHandle handle, Ogre::SceneNode *node)
 
static void setPickHandle (CollObjectHandle handle, Ogre::MovableObject *object)
 

Private Types

typedef boost::unordered_map< CollObjectHandle, SelectionHandler * > M_CollisionObjectToSelectionHandler
 
typedef std::map< std::string, ros::PublisherPublisherMap
 

Private Slots

void updateProperties ()
 Call updateProperties() on all SelectionHandlers in the current selection. More...
 

Private Member Functions

std::pair< Picked, bool > addSelectedObject (const Picked &obj)
 
void publishDebugImage (const Ogre::PixelBox &pixel_box, const std::string &label)
 
void removeSelectedObject (const Picked &obj)
 
bool render (Ogre::Viewport *viewport, Ogre::TexturePtr tex, int x1, int y1, int x2, int y2, Ogre::PixelBox &dst_box, std::string material_scheme, unsigned texture_width, unsigned textured_height)
 
void renderAndUnpack (Ogre::Viewport *viewport, uint32_t pass, int x1, int y1, int x2, int y2, V_CollObject &pixels)
 
void selectionAdded (const M_Picked &added)
 
void selectionRemoved (const M_Picked &removed)
 
void setDepthTextureSize (unsigned width, unsigned height)
 
void setHighlightRect (Ogre::Viewport *viewport, int x1, int y1, int x2, int y2)
 
void unpackColors (Ogre::PixelBox &box, V_CollObject &pixels)
 

Private Attributes

Ogre::Camera * camera_
 
bool debug_mode_
 
PublisherMap debug_publishers_
 
Ogre::PixelBox depth_pixel_box_
 
Ogre::TexturePtr depth_render_texture_
 
uint32_t depth_texture_height_
 
uint32_t depth_texture_width_
 
Ogre::Technique * fallback_black_cull_technique_
 
Ogre::Technique * fallback_black_technique_
 
Ogre::Technique * fallback_depth_cull_technique_
 
Ogre::Technique * fallback_depth_technique_
 
Ogre::Technique * fallback_pick_cull_technique_
 
Ogre::MaterialPtr fallback_pick_material_
 
Ogre::Technique * fallback_pick_technique_
 
boost::recursive_mutex global_mutex_
 
Highlight highlight_
 
bool highlight_enabled_
 
Ogre::SceneNode * highlight_node_
 
Ogre::Rectangle2D * highlight_rectangle_
 
bool interaction_enabled_
 
M_CollisionObjectToSelectionHandler objects_
 
Ogre::PixelBox pixel_boxes_ [s_num_render_textures_]
 
V_CollObject pixel_buffer_
 
PropertyTreeModelproperty_model_
 
Ogre::TexturePtr render_textures_ [s_num_render_textures_]
 
M_Picked selection_
 
uint32_t texture_size_
 
uint32_t uid_counter_
 
VisualizationManagervis_manager_
 

Static Private Attributes

static const uint32_t s_num_render_textures_ = 2
 

Detailed Description

Definition at line 81 of file selection_manager.h.

Member Typedef Documentation

◆ M_CollisionObjectToSelectionHandler

Definition at line 288 of file selection_manager.h.

◆ PublisherMap

typedef std::map<std::string, ros::Publisher> rviz::SelectionManager::PublisherMap
private

Definition at line 340 of file selection_manager.h.

Member Enumeration Documentation

◆ SelectType

Enumerator
Add 
Remove 
Replace 

Definition at line 87 of file selection_manager.h.

Constructor & Destructor Documentation

◆ SelectionManager()

rviz::SelectionManager::SelectionManager ( VisualizationManager manager)

Definition at line 77 of file selection_manager.cpp.

◆ ~SelectionManager()

rviz::SelectionManager::~SelectionManager ( )
override

Definition at line 96 of file selection_manager.cpp.

Member Function Documentation

◆ addObject()

void rviz::SelectionManager::addObject ( CollObjectHandle  obj,
SelectionHandler handler 
)

Definition at line 458 of file selection_manager.cpp.

◆ addSelectedObject()

std::pair< Picked, bool > rviz::SelectionManager::addSelectedObject ( const Picked obj)
private

Definition at line 1222 of file selection_manager.cpp.

◆ addSelection()

void rviz::SelectionManager::addSelection ( const M_Picked objs)

Definition at line 1193 of file selection_manager.cpp.

◆ clearHandlers()

void rviz::SelectionManager::clearHandlers ( )

Definition at line 415 of file selection_manager.cpp.

◆ createHandle()

CollObjectHandle rviz::SelectionManager::createHandle ( )

Definition at line 436 of file selection_manager.cpp.

◆ enableInteraction()

void rviz::SelectionManager::enableInteraction ( bool  enable)

Definition at line 422 of file selection_manager.cpp.

◆ focusOnSelection()

void rviz::SelectionManager::focusOnSelection ( )

Definition at line 1285 of file selection_manager.cpp.

◆ get3DPatch()

bool rviz::SelectionManager::get3DPatch ( Ogre::Viewport *  viewport,
const int  x,
const int  y,
const unsigned  width,
const unsigned  height,
const bool  skip_missing,
std::vector< Ogre::Vector3 > &  result_points 
)

Gets the 3D points in a box around a point in a view port.

Parameters
[in]viewportRendering area clicked on.
[in]xx coordinate of upper-left corner of box.
[in]yy coordinate of upper-left corner of box.
[in]widthThe width of the rendered box in pixels.
[in]heightThe height of the rendered box in pixels.
[in]skip_missingWhether to skip non-existing points or insert NaNs for them
[out]result_pointsThe vector of output points.
Returns
True if any valid point is rendered in the box. NaN points count, so if skip_missing is false, this will always return true if width and height are > 0.

Definition at line 249 of file selection_manager.cpp.

◆ get3DPoint()

bool rviz::SelectionManager::get3DPoint ( Ogre::Viewport *  viewport,
const int  x,
const int  y,
Ogre::Vector3 &  result_point 
)

Return true if the point at x, y in the viewport is showing an object, false otherwise. If it is showing an object, result will be changed to contain the 3D point corresponding to it.

Definition at line 178 of file selection_manager.cpp.

◆ getHandler()

SelectionHandler * rviz::SelectionManager::getHandler ( CollObjectHandle  obj)

Definition at line 1166 of file selection_manager.cpp.

◆ getInteractionEnabled()

bool rviz::SelectionManager::getInteractionEnabled ( )
inline

Definition at line 170 of file selection_manager.h.

◆ getPatchDepthImage()

bool rviz::SelectionManager::getPatchDepthImage ( Ogre::Viewport *  viewport,
const int  x,
const int  y,
const unsigned  width,
const unsigned  height,
std::vector< float > &  depth_vector 
)

Renders a depth image in a box around a point in a view port.

Parameters
[in]viewportRendering area clicked on.
[in]xx coordinate of upper-left corner of box.
[in]yy coordinate of upper-left corner of box.
[in]widthThe width of the rendered box in pixels.
[in]heightThe height of the rendered box in pixels.
[out]depth_vectorThe vector of depth values.
Returns
True if rendering operation to render depth data to the depth texture buffer succeeds. Failure likely indicates a pretty serious problem.

Definition at line 195 of file selection_manager.cpp.

◆ getPropertyModel()

PropertyTreeModel* rviz::SelectionManager::getPropertyModel ( )
inline

Definition at line 238 of file selection_manager.h.

◆ getSelection()

const M_Picked& rviz::SelectionManager::getSelection ( )
inline

Definition at line 129 of file selection_manager.h.

◆ handleSchemeNotFound()

Ogre::Technique * rviz::SelectionManager::handleSchemeNotFound ( unsigned short  scheme_index,
const Ogre::String &  scheme_name,
Ogre::Material *  original_material,
unsigned short  lod_index,
const Ogre::Renderable *  rend 
)
override

Definition at line 1039 of file selection_manager.cpp.

◆ handleToColor()

Ogre::ColourValue rviz::SelectionManager::handleToColor ( CollObjectHandle  handle)
static

Definition at line 1104 of file selection_manager.cpp.

◆ highlight()

void rviz::SelectionManager::highlight ( Ogre::Viewport *  viewport,
int  x1,
int  y1,
int  x2,
int  y2 
)

Definition at line 519 of file selection_manager.cpp.

◆ initialize()

void rviz::SelectionManager::initialize ( )

Definition at line 121 of file selection_manager.cpp.

◆ pick()

void rviz::SelectionManager::pick ( Ogre::Viewport *  viewport,
int  x1,
int  y1,
int  x2,
int  y2,
M_Picked results,
bool  single_render_pass = false 
)

Definition at line 863 of file selection_manager.cpp.

◆ publishDebugImage()

void rviz::SelectionManager::publishDebugImage ( const Ogre::PixelBox &  pixel_box,
const std::string &  label 
)
private

Definition at line 792 of file selection_manager.cpp.

◆ removeHighlight()

void rviz::SelectionManager::removeHighlight ( )

Definition at line 532 of file selection_manager.cpp.

◆ removeObject()

void rviz::SelectionManager::removeObject ( CollObjectHandle  obj)

Definition at line 479 of file selection_manager.cpp.

◆ removeSelectedObject()

void rviz::SelectionManager::removeSelectedObject ( const Picked obj)
private

Definition at line 1261 of file selection_manager.cpp.

◆ removeSelection()

void rviz::SelectionManager::removeSelection ( const M_Picked objs)

Definition at line 1179 of file selection_manager.cpp.

◆ render()

bool rviz::SelectionManager::render ( Ogre::Viewport *  viewport,
Ogre::TexturePtr  tex,
int  x1,
int  y1,
int  x2,
int  y2,
Ogre::PixelBox &  dst_box,
std::string  material_scheme,
unsigned  texture_width,
unsigned  textured_height 
)
private

Internal render function to render to a texture and read the pixels back out.

Definition at line 624 of file selection_manager.cpp.

◆ renderAndUnpack()

void rviz::SelectionManager::renderAndUnpack ( Ogre::Viewport *  viewport,
uint32_t  pass,
int  x1,
int  y1,
int  x2,
int  y2,
V_CollObject pixels 
)
private

Render to a texture for one of the picking passes and unpack the resulting pixels.

Definition at line 599 of file selection_manager.cpp.

◆ renderQueueStarted()

void rviz::SelectionManager::renderQueueStarted ( uint8_t  queueGroupId,
const std::string &  invocation,
bool &  skipThisInvocation 
)
override

Definition at line 851 of file selection_manager.cpp.

◆ select()

void rviz::SelectionManager::select ( Ogre::Viewport *  viewport,
int  x1,
int  y1,
int  x2,
int  y2,
SelectType  type 
)

Definition at line 539 of file selection_manager.cpp.

◆ selectionAdded()

void rviz::SelectionManager::selectionAdded ( const M_Picked added)
private

Definition at line 1340 of file selection_manager.cpp.

◆ selectionRemoved()

void rviz::SelectionManager::selectionRemoved ( const M_Picked removed)
private

Definition at line 1326 of file selection_manager.cpp.

◆ setDebugMode()

void rviz::SelectionManager::setDebugMode ( bool  debug)

Enables or disables publishing of picking and depth rendering images.

Definition at line 116 of file selection_manager.cpp.

◆ setDepthTextureSize()

void rviz::SelectionManager::setDepthTextureSize ( unsigned  width,
unsigned  height 
)
private

Definition at line 326 of file selection_manager.cpp.

◆ setHighlightRect()

void rviz::SelectionManager::setHighlightRect ( Ogre::Viewport *  viewport,
int  x1,
int  y1,
int  x2,
int  y2 
)
private

Definition at line 563 of file selection_manager.cpp.

◆ setPickColor() [1/2]

static void rviz::SelectionManager::setPickColor ( const Ogre::ColourValue &  color,
Ogre::SceneNode *  node 
)
inlinestatic

Definition at line 138 of file selection_manager.h.

◆ setPickColor() [2/2]

static void rviz::SelectionManager::setPickColor ( const Ogre::ColourValue &  color,
Ogre::MovableObject *  object 
)
inlinestatic

Definition at line 142 of file selection_manager.h.

◆ setPickData() [1/2]

void rviz::SelectionManager::setPickData ( CollObjectHandle  handle,
const Ogre::ColourValue &  color,
Ogre::SceneNode *  node 
)
static

Definition at line 1112 of file selection_manager.cpp.

◆ setPickData() [2/2]

void rviz::SelectionManager::setPickData ( CollObjectHandle  handle,
const Ogre::ColourValue &  color,
Ogre::MovableObject *  object 
)
static

Definition at line 1157 of file selection_manager.cpp.

◆ setPickHandle() [1/2]

static void rviz::SelectionManager::setPickHandle ( CollObjectHandle  handle,
Ogre::SceneNode *  node 
)
inlinestatic

Definition at line 146 of file selection_manager.h.

◆ setPickHandle() [2/2]

static void rviz::SelectionManager::setPickHandle ( CollObjectHandle  handle,
Ogre::MovableObject *  object 
)
inlinestatic

Definition at line 150 of file selection_manager.h.

◆ setSelection()

void rviz::SelectionManager::setSelection ( const M_Picked objs)

Definition at line 1212 of file selection_manager.cpp.

◆ setTextureSize()

void rviz::SelectionManager::setTextureSize ( unsigned  size)

Definition at line 374 of file selection_manager.cpp.

◆ unpackColors()

void rviz::SelectionManager::unpackColors ( Ogre::PixelBox &  box,
V_CollObject pixels 
)
private

Definition at line 578 of file selection_manager.cpp.

◆ update()

void rviz::SelectionManager::update ( )

Definition at line 500 of file selection_manager.cpp.

◆ updateProperties

void rviz::SelectionManager::updateProperties ( )
privateslot

Call updateProperties() on all SelectionHandlers in the current selection.

Definition at line 1355 of file selection_manager.cpp.

Member Data Documentation

◆ camera_

Ogre::Camera* rviz::SelectionManager::camera_
private

Definition at line 320 of file selection_manager.h.

◆ debug_mode_

bool rviz::SelectionManager::debug_mode_
private

Definition at line 326 of file selection_manager.h.

◆ debug_publishers_

PublisherMap rviz::SelectionManager::debug_publishers_
private

Definition at line 341 of file selection_manager.h.

◆ depth_pixel_box_

Ogre::PixelBox rviz::SelectionManager::depth_pixel_box_
private

Definition at line 314 of file selection_manager.h.

◆ depth_render_texture_

Ogre::TexturePtr rviz::SelectionManager::depth_render_texture_
private

Definition at line 312 of file selection_manager.h.

◆ depth_texture_height_

uint32_t rviz::SelectionManager::depth_texture_height_
private

Definition at line 313 of file selection_manager.h.

◆ depth_texture_width_

uint32_t rviz::SelectionManager::depth_texture_width_
private

Definition at line 313 of file selection_manager.h.

◆ fallback_black_cull_technique_

Ogre::Technique* rviz::SelectionManager::fallback_black_cull_technique_
private

Definition at line 333 of file selection_manager.h.

◆ fallback_black_technique_

Ogre::Technique* rviz::SelectionManager::fallback_black_technique_
private

Definition at line 330 of file selection_manager.h.

◆ fallback_depth_cull_technique_

Ogre::Technique* rviz::SelectionManager::fallback_depth_cull_technique_
private

Definition at line 334 of file selection_manager.h.

◆ fallback_depth_technique_

Ogre::Technique* rviz::SelectionManager::fallback_depth_technique_
private

Definition at line 331 of file selection_manager.h.

◆ fallback_pick_cull_technique_

Ogre::Technique* rviz::SelectionManager::fallback_pick_cull_technique_
private

Definition at line 332 of file selection_manager.h.

◆ fallback_pick_material_

Ogre::MaterialPtr rviz::SelectionManager::fallback_pick_material_
private

Definition at line 328 of file selection_manager.h.

◆ fallback_pick_technique_

Ogre::Technique* rviz::SelectionManager::fallback_pick_technique_
private

Definition at line 329 of file selection_manager.h.

◆ global_mutex_

boost::recursive_mutex rviz::SelectionManager::global_mutex_
private

Definition at line 286 of file selection_manager.h.

◆ highlight_

Highlight rviz::SelectionManager::highlight_
private

Definition at line 301 of file selection_manager.h.

◆ highlight_enabled_

bool rviz::SelectionManager::highlight_enabled_
private

Definition at line 291 of file selection_manager.h.

◆ highlight_node_

Ogre::SceneNode* rviz::SelectionManager::highlight_node_
private

Definition at line 319 of file selection_manager.h.

◆ highlight_rectangle_

Ogre::Rectangle2D* rviz::SelectionManager::highlight_rectangle_
private

Definition at line 318 of file selection_manager.h.

◆ interaction_enabled_

bool rviz::SelectionManager::interaction_enabled_
private

Definition at line 324 of file selection_manager.h.

◆ objects_

M_CollisionObjectToSelectionHandler rviz::SelectionManager::objects_
private

Definition at line 289 of file selection_manager.h.

◆ pixel_boxes_

Ogre::PixelBox rviz::SelectionManager::pixel_boxes_[s_num_render_textures_]
private

Definition at line 309 of file selection_manager.h.

◆ pixel_buffer_

V_CollObject rviz::SelectionManager::pixel_buffer_
private

Definition at line 322 of file selection_manager.h.

◆ property_model_

PropertyTreeModel* rviz::SelectionManager::property_model_
private

Definition at line 338 of file selection_manager.h.

◆ render_textures_

Ogre::TexturePtr rviz::SelectionManager::render_textures_[s_num_render_textures_]
private

Definition at line 308 of file selection_manager.h.

◆ s_num_render_textures_

const uint32_t rviz::SelectionManager::s_num_render_textures_ = 2
staticprivate

Definition at line 305 of file selection_manager.h.

◆ selection_

M_Picked rviz::SelectionManager::selection_
private

Definition at line 303 of file selection_manager.h.

◆ texture_size_

uint32_t rviz::SelectionManager::texture_size_
private

Definition at line 336 of file selection_manager.h.

◆ uid_counter_

uint32_t rviz::SelectionManager::uid_counter_
private

Definition at line 316 of file selection_manager.h.

◆ vis_manager_

VisualizationManager* rviz::SelectionManager::vis_manager_
private

Definition at line 284 of file selection_manager.h.


The documentation for this class was generated from the following files:


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:26