Go to the documentation of this file. 1 #ifndef EFFORT_DISPLAY_H
2 #define EFFORT_DISPLAY_H
5 #include <boost/circular_buffer.hpp>
8 #include <sensor_msgs/JointState.h>
21 class CategoryProperty;
85 void reset()
override;
113 void processMessage(
const sensor_msgs::JointState::ConstPtr& msg)
override;
117 boost::circular_buffer<boost::shared_ptr<EffortVisual> >
visuals_;
133 #endif // EFFORT_DISPLAY_H
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
boost::shared_ptr< urdf::Model > robot_model_
std::string robot_description_
rviz::IntProperty * history_length_property_
Property specialized to provide getter for booleans.
std::set< JointInfo * > S_JointInfo
JointInfo(const std::string &name, rviz::Property *parent_category)
Property specialized to enforce floating point max/min.
rviz::BoolProperty * all_enabled_property_
A single element of a property tree, with a name, value, description, and possibly children.
boost::circular_buffer< boost::shared_ptr< EffortVisual > > visuals_
std::vector< std::string > V_string
~EffortDisplay() override
void setMaxEffort(double m)
rviz::FloatProperty * max_effort_property_
rviz::FloatProperty * scale_property_
void reset() override
Called to tell the display to clear its state.
Property specialized for string values.
void updateColorAndAlpha()
rviz::StringProperty * robot_description_property_
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
void load(const Config &config) override
Load the settings for this display from the given Config node, which must be a map.
rviz::StringProperty * tf_prefix_property_
rviz::Property * joints_category_
rviz::FloatProperty * alpha_property_
void processMessage(const sensor_msgs::JointState::ConstPtr &msg) override
JointInfo * createJoint(const std::string &joint)
void onInitialize() override
Override this function to do subclass-specific initialization.
std::map< std::string, JointInfo * > M_JointInfo
JointInfo * getJointInfo(const std::string &joint)
rviz::FloatProperty * width_property_
rviz::FloatProperty * effort_property_
rviz::Property * category_
void updateHistoryLength()
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
void updateRobotDescription()
Property specialized to provide max/min enforcement for integers.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09