Go to the documentation of this file.
30 #include <OgreSceneNode.h>
31 #include <OgreSceneManager.h>
55 new IntProperty(
"Buffer Length", 1,
"Number of prior measurements to display.",
this,
69 for (
size_t i = 0; i <
cones_.size(); i++)
85 for (
size_t i = 0; i <
cones_.size(); i++)
87 cones_[i]->setColor(oc.r, oc.g, oc.b, alpha);
97 for (
size_t i = 0; i <
cones_.size(); i++)
101 cones_.resize(buffer_length);
102 for (
size_t i = 0; i <
cones_.size(); i++)
107 Ogre::Vector3 position;
108 Ogre::Quaternion orientation;
109 geometry_msgs::Pose pose;
110 pose.orientation.w = 1;
111 Ogre::Vector3 scale(0, 0, 0);
113 cone->
setColor(color.redF(), color.greenF(), color.blueF(), 0);
121 Ogre::Vector3 position;
122 Ogre::Quaternion orientation;
123 geometry_msgs::Pose pose;
124 float displayed_range = 0.0;
125 if (msg->min_range <= msg->range && msg->range <= msg->max_range)
127 displayed_range = msg->range;
129 else if (msg->min_range == msg->max_range)
131 if (msg->range < 0 && !std::isfinite(msg->range))
133 displayed_range = msg->min_range;
138 displayed_range / 2 -
139 .008824 * displayed_range;
140 pose.orientation.z = 0.707;
141 pose.orientation.w = 0.707;
145 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(),
152 double cone_width = 2.0 * displayed_range * tan(msg->field_of_view / 2.0);
153 Ogre::Vector3 scale(cone_width, displayed_range, cone_width);
virtual QColor getColor() const
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
void setColor(float r, float g, float b, float a) override
Set the color of the object. Values are in the range [0, 1].
void processMessage(const sensor_msgs::Range::ConstPtr &msg) override
Overridden from MessageFilterDisplay.
Displays a sensor_msgs::Range message as a cone.
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
void reset() override
Overridden from Display.
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
Property specialized to enforce floating point max/min.
void onInitialize() override
Overridden from Display.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual float getFloat() const
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
ColorProperty * color_property_
void updateColorAndAlpha()
IntProperty * buffer_length_property_
FloatProperty * alpha_property_
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
uint32_t messages_received_
void onInitialize() override
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
void updateBufferLength()
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Transform a pose from a frame into the fixed frame.
virtual int getInt() const
Return the internal property value as an integer.
std::vector< Shape * > cones_
Handles actually drawing the cones.
void setScale(const Ogre::Vector3 &scale) override
Set the scale of the object. Always relative to the identity orientation of the object.
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
Ogre::ColourValue getOgreColor() const
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:10