wrench_display.h
Go to the documentation of this file.
1 #ifndef WRENCHSTAMPED_DISPLAY_H
2 #define WRENCHSTAMPED_DISPLAY_H
3 
4 #ifndef Q_MOC_RUN
5 #include <boost/circular_buffer.hpp>
6 #endif
7 
8 #include <geometry_msgs/WrenchStamped.h>
10 
11 namespace Ogre
12 {
13 class SceneNode;
14 }
15 
16 namespace rviz
17 {
18 class ColorProperty;
19 class ROSTopicStringProperty;
20 class FloatProperty;
21 class IntProperty;
22 } // namespace rviz
23 
24 namespace rviz
25 {
26 class WrenchVisual;
27 
28 class WrenchStampedDisplay : public rviz::MessageFilterDisplay<geometry_msgs::WrenchStamped>
29 {
30  Q_OBJECT
31 public:
32  // Constructor. pluginlib::ClassLoader creates instances by calling
33  // the default constructor, so make sure you have one.
35  ~WrenchStampedDisplay() override;
36 
37 protected:
38  // Overrides of public virtual functions from the Display class.
39  void onInitialize() override;
40  void reset() override;
41 
42 private Q_SLOTS:
43  // Helper function to properties for all visuals.
44  void updateProperties();
45  void updateHistoryLength();
46 
47 private:
48  // Function to handle an incoming ROS message.
49  void processMessage(const geometry_msgs::WrenchStamped::ConstPtr& msg) override;
50 
51  // Storage for the list of visuals par each joint intem
52  // Storage for the list of visuals. It is a circular buffer where
53  // data gets popped from the front (oldest) and pushed to the back (newest)
54  boost::circular_buffer<boost::shared_ptr<WrenchVisual> > visuals_;
55 
56  // Property objects for user-editable properties.
57  rviz::ColorProperty *force_color_property_, *torque_color_property_;
58  rviz::FloatProperty *alpha_property_, *force_scale_property_, *torque_scale_property_,
62 };
63 } // namespace rviz
64 
65 #endif // WRENCHSTAMPED_DISPLAY_H
boost::circular_buffer< boost::shared_ptr< WrenchVisual > > visuals_
rviz::IntProperty * history_length_property_
Property specialized to enforce floating point max/min.
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:37
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
rviz::FloatProperty * width_property_
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
rviz::BoolProperty * hide_small_values_property_
rviz::ColorProperty * torque_color_property_


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