Go to the documentation of this file.    1 #ifndef SCREW_DISPLAY_H 
    2 #define SCREW_DISPLAY_H 
    5 #include <boost/circular_buffer.hpp> 
   10 #include <geometry_msgs/AccelStamped.h> 
   11 #include <geometry_msgs/TwistStamped.h> 
   12 #include <geometry_msgs/WrenchStamped.h> 
   22 class ROSTopicStringProperty;
 
   31 template <
class MessageType>
 
   43   void reset() 
override;
 
   50                              const geometry_msgs::Vector3& 
linear,
 
   51                              const geometry_msgs::Vector3& 
angular);
 
   56   boost::circular_buffer<boost::shared_ptr<ScrewVisual> > 
visuals_;
 
   71   void processMessage(
const geometry_msgs::AccelStamped::ConstPtr& msg)
 override 
   82   void processMessage(
const geometry_msgs::TwistStamped::ConstPtr& msg)
 override 
   93   void processMessage(
const geometry_msgs::WrenchStamped::ConstPtr& msg)
 override 
  100 #endif // SCREW_DISPLAY_H 
 
rviz::FloatProperty * alpha_property_
rviz::ColorProperty * linear_color_property_
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
void onInitialize() override
Override this function to do subclass-specific initialization.
constexpr const char * linear()
rviz::BoolProperty * hide_small_values_property_
Property specialized to provide getter for booleans.
void processMessage(const geometry_msgs::AccelStamped::ConstPtr &msg) override
rviz::IntProperty * history_length_property_
rviz::FloatProperty * linear_scale_property_
rviz::FloatProperty * width_property_
Property specialized to enforce floating point max/min.
boost::circular_buffer< boost::shared_ptr< ScrewVisual > > visuals_
void processMessage(const geometry_msgs::WrenchStamped::ConstPtr &msg) override
rviz::ColorProperty * angular_color_property_
rviz::FloatProperty * angular_scale_property_
constexpr const char * angular()
void processMessage(const geometry_msgs::TwistStamped::ConstPtr &msg) override
~ScrewDisplay() override=default
void updateHistoryLength()
void reset() override
Called to tell the display to clear its state.
void processMessagePrivate(const std_msgs::Header &header, const geometry_msgs::Vector3 &linear, const geometry_msgs::Vector3 &angular)
Property specialized to provide max/min enforcement for integers.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall 
autogenerated on Sun May 4 2025 02:31:26