Go to the documentation of this file.
   31 #ifndef RVIZ_TF_DISPLAY_H 
   32 #define RVIZ_TF_DISPLAY_H 
   37 #include <OGRE/OgreQuaternion.h> 
   38 #include <OGRE/OgreVector3.h> 
   59 class QuaternionProperty;
 
   75   void update(
float wall_dt, 
float ros_dt) 
override;
 
   82   void reset() 
override;
 
   99   M_FrameInfo::iterator 
deleteFrame(M_FrameInfo::iterator it, 
bool delete_properties);
 
  199 #endif // RVIZ_TF_DISPLAY_H 
  
Ogre::SceneNode * names_node_
Property * tree_property_
std::map< std::string, bool > M_EnabledState
void load(const Config &config) override
void fixedFrameChanged() override
FloatProperty * frame_timeout_property_
QuaternionProperty * orientation_property_
void onDisable() override
Ogre::SceneNode * root_node_
std::map< std::string, FrameInfo * > M_FrameInfo
Displays a visual representation of the TF hierarchy.
boost::shared_ptr< FrameSelectionHandler > FrameSelectionHandlerPtr
Property * tree_category_
VectorProperty * rel_position_property_
hri::HRIListener hri_listener_
M_FrameInfo::iterator deleteFrame(M_FrameInfo::iterator it, bool delete_properties)
FloatProperty * scale_property_
uint32_t CollObjectHandle
StringProperty * parent_property_
Ogre::SceneNode * axes_node_
BoolProperty * show_skeletons_property_
float distance_to_parent_
BoolProperty * all_enabled_property_
M_EnabledState frame_config_enabled_state_
BoolProperty * show_axes_property_
VectorProperty * position_property_
bool changing_single_frame_enabled_state_
FloatProperty * alpha_property_
CollObjectHandle axes_coll_
FrameInfo * createFrame(const std::string &frame)
QuaternionProperty * rel_orientation_property_
void updateVisibilityFromFrame()
Ogre::SceneNode * name_node_
Ogre::SceneNode * arrows_node_
void updateshowSkeletons()
FrameSelectionHandlerPtr selection_handler_
BoolProperty * enabled_property_
BoolProperty * show_names_property_
BoolProperty * show_gazes_property_
void update(float wall_dt, float ros_dt) override
BoolProperty * show_faces_property_
void setEnabled(bool enabled)
ros::Time last_time_to_fixed_
void updateFrame(FrameInfo *frame)
void onInitialize() override
BoolProperty * show_arrows_property_
void updateVisibilityFromSelection()
Property * frames_category_
FloatProperty * update_rate_property_
Internal class needed only by HRITFDisplay.
std::vector< std::string > skeleton_components_
FrameInfo(TFDisplay *display)
Ogre::Quaternion arrow_orientation_
FrameInfo * getFrameInfo(const std::string &frame)
hri_rviz
Author(s): Lorenzo Ferrini, Séverin Lemaignan
autogenerated on Fri Oct 20 2023 02:53:21