Public Member Functions | Protected Member Functions | Private Slots | Private Member Functions | Private Attributes
rviz::MeshDisplayCustom Class Reference

Uses a pose from topic + offset to render a bounding object with shape, size and color. More...

#include <mesh_display_custom.h>

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

List of all members.

Public Member Functions

 MeshDisplayCustom ()
virtual void onInitialize ()
virtual void reset ()
virtual void update (float wall_dt, float ros_dt)
virtual ~MeshDisplayCustom ()

Protected Member Functions

virtual void load (int index)
virtual void onDisable ()
virtual void onEnable ()
void processImage (int index, const sensor_msgs::Image &msg)
virtual void subscribe ()
virtual void unsubscribe ()

Private Slots

void updateDisplayImages ()
void updateMeshProperties ()

Private Member Functions

void addDecalToMaterial (int index, const Ogre::String &matName)
void clear ()
void clearStates (int num_quads)
shape_msgs::Mesh constructMesh (geometry_msgs::Pose mesh_origin, float width, float height, float border_size)
void constructQuads (const rviz_textured_quads::TexturedQuadArray::ConstPtr &images)
void createProjector (int index)
bool updateCamera (int index, bool update_image)
void updateImageMeshes (const rviz_textured_quads::TexturedQuadArray::ConstPtr &images)

Private Attributes

std::vector< std::vector< float > > border_colors_
std::vector< float > border_sizes_
std::vector< Ogre::Frustum * > decal_frustums_
RosTopicPropertydisplay_images_topic_property_
std::vector< std::vector
< Ogre::Frustum * > > 
filter_frustums_
std::vector< int > img_heights_
std::vector< int > img_widths_
bool initialized_
std::vector
< sensor_msgs::Image::ConstPtr > 
last_images_
std::vector< shape_msgs::Mesh > last_meshes_
std::vector< Ogre::ManualObject * > manual_objects_
std::vector< Ogre::MaterialPtr > mesh_materials_
boost::mutex mesh_mutex_
std::vector< Ogre::SceneNode * > mesh_nodes_
std::vector< geometry_msgs::Posemesh_poses_
ros::NodeHandle nh_
std::vector< float > physical_heights_
std::vector< float > physical_widths_
ros::Subscriber pose_sub_
std::vector< Ogre::SceneNode * > projector_nodes_
RenderPanelrender_panel_
std::vector< RenderPanel * > render_panel_list_
ros::Subscriber rviz_display_images_sub_
FloatPropertytext_bottom_offset_
ColorPropertytext_color_property_
FloatPropertytext_height_property_
std::vector
< rviz_textured_quads::TextNode * > 
text_nodes_
std::vector< ROSImageTexture * > textures_
float time_since_last_transform_

Detailed Description

Uses a pose from topic + offset to render a bounding object with shape, size and color.

Definition at line 109 of file mesh_display_custom.h.


Constructor & Destructor Documentation

Definition at line 82 of file mesh_display_custom.cpp.

Definition at line 102 of file mesh_display_custom.cpp.


Member Function Documentation

void rviz::MeshDisplayCustom::addDecalToMaterial ( int  index,
const Ogre::String &  matName 
) [private]

Definition at line 168 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::clear ( ) [private]

Definition at line 722 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::clearStates ( int  num_quads) [private]

Definition at line 254 of file mesh_display_custom.cpp.

shape_msgs::Mesh rviz::MeshDisplayCustom::constructMesh ( geometry_msgs::Pose  mesh_origin,
float  width,
float  height,
float  border_size 
) [private]

Definition at line 207 of file mesh_display_custom.cpp.

Definition at line 289 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::createProjector ( int  index) [private]

Definition at line 151 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::load ( int  index) [protected, virtual]

Definition at line 500 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::onDisable ( ) [protected, virtual]

Reimplemented from rviz::Display.

Definition at line 552 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::onEnable ( ) [protected, virtual]

Reimplemented from rviz::Display.

Definition at line 547 of file mesh_display_custom.cpp.

Reimplemented from rviz::Display.

Definition at line 146 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::processImage ( int  index,
const sensor_msgs::Image &  msg 
) [protected]

Definition at line 740 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::reset ( ) [virtual]

Reimplemented from rviz::Display.

Definition at line 734 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::subscribe ( ) [protected, virtual]

Definition at line 474 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::unsubscribe ( ) [protected, virtual]

Definition at line 495 of file mesh_display_custom.cpp.

void rviz::MeshDisplayCustom::update ( float  wall_dt,
float  ros_dt 
) [virtual]

Reimplemented from rviz::Display.

Definition at line 557 of file mesh_display_custom.cpp.

bool rviz::MeshDisplayCustom::updateCamera ( int  index,
bool  update_image 
) [private]

Definition at line 577 of file mesh_display_custom.cpp.

Definition at line 468 of file mesh_display_custom.cpp.

Definition at line 431 of file mesh_display_custom.cpp.

Definition at line 437 of file mesh_display_custom.cpp.


Member Data Documentation

std::vector<std::vector<float> > rviz::MeshDisplayCustom::border_colors_ [private]

Definition at line 161 of file mesh_display_custom.h.

std::vector<float> rviz::MeshDisplayCustom::border_sizes_ [private]

Definition at line 162 of file mesh_display_custom.h.

std::vector<Ogre::Frustum*> rviz::MeshDisplayCustom::decal_frustums_ [private]

Definition at line 177 of file mesh_display_custom.h.

Definition at line 152 of file mesh_display_custom.h.

std::vector<std::vector<Ogre::Frustum*> > rviz::MeshDisplayCustom::filter_frustums_ [private]

Definition at line 178 of file mesh_display_custom.h.

std::vector<int> rviz::MeshDisplayCustom::img_heights_ [private]

Definition at line 159 of file mesh_display_custom.h.

std::vector<int> rviz::MeshDisplayCustom::img_widths_ [private]

Definition at line 159 of file mesh_display_custom.h.

Reimplemented from rviz::Display.

Definition at line 184 of file mesh_display_custom.h.

std::vector<sensor_msgs::Image::ConstPtr> rviz::MeshDisplayCustom::last_images_ [private]

Definition at line 167 of file mesh_display_custom.h.

std::vector<shape_msgs::Mesh> rviz::MeshDisplayCustom::last_meshes_ [private]

Definition at line 157 of file mesh_display_custom.h.

std::vector<Ogre::ManualObject*> rviz::MeshDisplayCustom::manual_objects_ [private]

Definition at line 170 of file mesh_display_custom.h.

std::vector<Ogre::MaterialPtr> rviz::MeshDisplayCustom::mesh_materials_ [private]

Definition at line 171 of file mesh_display_custom.h.

boost::mutex rviz::MeshDisplayCustom::mesh_mutex_ [private]

Definition at line 186 of file mesh_display_custom.h.

std::vector<Ogre::SceneNode*> rviz::MeshDisplayCustom::mesh_nodes_ [private]

Definition at line 169 of file mesh_display_custom.h.

Definition at line 158 of file mesh_display_custom.h.

Definition at line 165 of file mesh_display_custom.h.

std::vector<float> rviz::MeshDisplayCustom::physical_heights_ [private]

Definition at line 160 of file mesh_display_custom.h.

std::vector<float> rviz::MeshDisplayCustom::physical_widths_ [private]

Definition at line 160 of file mesh_display_custom.h.

Definition at line 174 of file mesh_display_custom.h.

std::vector<Ogre::SceneNode*> rviz::MeshDisplayCustom::projector_nodes_ [private]

Definition at line 179 of file mesh_display_custom.h.

Definition at line 182 of file mesh_display_custom.h.

Definition at line 181 of file mesh_display_custom.h.

Definition at line 175 of file mesh_display_custom.h.

Definition at line 155 of file mesh_display_custom.h.

Definition at line 153 of file mesh_display_custom.h.

Definition at line 154 of file mesh_display_custom.h.

Definition at line 163 of file mesh_display_custom.h.

Definition at line 172 of file mesh_display_custom.h.

Definition at line 150 of file mesh_display_custom.h.


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


rviz_textured_quads
Author(s): Mohit Shridhar
autogenerated on Thu Jun 6 2019 19:50:52