Go to the documentation of this file.
   30 #ifndef RVIZ_HRI_HUMANS_H 
   31 #define RVIZ_HRI_HUMANS_H 
   33 #ifndef Q_MOC_RUN  // See: https://bugreports.qt-project.org/browse/QTBUG-22829 
   34 #include <OGRE/OgreMaterial.h> 
   35 #include <OGRE/OgreRenderTargetListener.h> 
   36 #include <OGRE/OgreSharedPtr.h> 
   38 #include <hri_msgs/IdsList.h> 
   39 #include <hri_msgs/NormalizedPointOfInterest2D.h> 
   70   void update(
float wall_dt, 
float ros_dt) 
override;
 
   71   void reset() 
override;
 
   86   void drawSkeleton(std::string 
id, 
int width, 
int height, std::vector<hri_msgs::NormalizedPointOfInterest2D>& skeleton);
 
   89   void processMessage(
const sensor_msgs::Image::ConstPtr& msg) 
override;
 
  
void processMessage(const sensor_msgs::Image::ConstPtr &msg) override
BoolProperty * show_faces_property_
RenderPanel * render_panel_
void onInitialize() override
void update(float wall_dt, float ros_dt) override
void drawSkeleton(std::string id, int width, int height, std::vector< hri_msgs::NormalizedPointOfInterest2D > &skeleton)
BoolProperty * normalize_property_
virtual void updateNormalizeOptions()
IntProperty * median_buffer_size_property_
void updateShowFacialLandmarks()
BoolProperty * show_bodies_property_
BoolProperty * show_facial_landmarks_property_
cv_bridge::CvImagePtr cvBridge_
void onDisable() override
bool show_facial_landmarks_
Ogre::Rectangle2D * screen_rect_
void updateShowSkeletons()
FloatProperty * min_property_
hri::HRIListener hri_listener
FloatProperty * max_property_
~HumansDisplay() override
BoolProperty * show_skeletons_property_
Ogre::MaterialPtr material_
Ogre::SceneNode * img_scene_node_
Ogre::SceneManager * img_scene_manager_
hri_rviz
Author(s): Lorenzo Ferrini, Séverin Lemaignan
autogenerated on Fri Oct 20 2023 02:53:21