Displays a sensor_msgs::Range message as a cone. More...
#include <range_display.h>
Public Member Functions | |
virtual void | createProperties () |
Called from setPropertyManager, gives the display a chance to create some properties immediately. | |
virtual void | fixedFrameChanged () |
Override to handle changes to fixed_frame_. This base class implementation does nothing. | |
float | getAlpha () |
int | getBuffer () |
const rviz::Color & | getColor () |
const std::string & | getTopic () |
virtual const char * | getType () const |
virtual void | onInitialize () |
Override this function to do subclass-specific initialization. | |
RangeDisplay () | |
virtual void | reset () |
Called to tell the display to clear its state. | |
void | setAlpha (float alpha) |
void | setBuffer (int buffer) |
void | setColor (const rviz::Color &color) |
void | setTopic (const std::string &topic) |
virtual void | update (float wall_dt, float ros_dt) |
Called periodically by the visualization panel. | |
virtual | ~RangeDisplay () |
Static Public Member Functions | |
static const char * | getDescription () |
static const char * | getTypeStatic () |
Protected Member Functions | |
void | clear () |
void | incomingMessage (const sensor_msgs::Range::ConstPtr &msg) |
virtual void | onDisable () |
Derived classes override this to do the actual work of disabling themselves. | |
virtual void | onEnable () |
Derived classes override this to do the actual work of enabling themselves. | |
void | processMessage (const sensor_msgs::Range::ConstPtr &msg) |
void | subscribe () |
void | unsubscribe () |
Protected Attributes | |
float | alpha_ |
rviz::FloatPropertyWPtr | alpha_property_ |
int | buffer_len_ |
rviz::IntPropertyWPtr | bufferLen_property_ |
rviz::Color | color_ |
rviz::ColorPropertyWPtr | color_property_ |
std::vector< Shape * > | cones_ |
Handles actually drawing the cone. | |
sensor_msgs::Range::ConstPtr | current_message_ |
uint32_t | messages_received_ |
Ogre::SceneNode * | scene_node_ |
message_filters::Subscriber < sensor_msgs::Range > | sub_ |
tf::MessageFilter < sensor_msgs::Range > * | tf_filter_ |
std::string | topic_ |
rviz::ROSTopicStringPropertyWPtr | topic_property_ |
Displays a sensor_msgs::Range message as a cone.
Definition at line 63 of file range_display.h.
Definition at line 17 of file range_display.cpp.
rviz::RangeDisplay::~RangeDisplay | ( | ) | [virtual] |
Definition at line 40 of file range_display.cpp.
void rviz::RangeDisplay::clear | ( | void | ) | [protected] |
Definition at line 51 of file range_display.cpp.
void rviz::RangeDisplay::createProperties | ( | ) | [virtual] |
Called from setPropertyManager, gives the display a chance to create some properties immediately.
When this function is called, the property_manager_ member is valid and will stay valid
Reimplemented from rviz::Display.
Definition at line 218 of file range_display.cpp.
void rviz::RangeDisplay::fixedFrameChanged | ( | ) | [virtual] |
Override to handle changes to fixed_frame_. This base class implementation does nothing.
Reimplemented from rviz::Display.
Definition at line 157 of file range_display.cpp.
float rviz::RangeDisplay::getAlpha | ( | ) | [inline] |
Definition at line 81 of file range_display.h.
int rviz::RangeDisplay::getBuffer | ( | ) | [inline] |
Definition at line 78 of file range_display.h.
const rviz::Color& rviz::RangeDisplay::getColor | ( | ) | [inline] |
Definition at line 75 of file range_display.h.
const char * rviz::RangeDisplay::getDescription | ( | ) | [static] |
Definition at line 237 of file range_display.cpp.
const std::string& rviz::RangeDisplay::getTopic | ( | ) | [inline] |
Definition at line 72 of file range_display.h.
virtual const char* rviz::RangeDisplay::getType | ( | ) | const [inline, virtual] |
Definition at line 90 of file range_display.h.
static const char* rviz::RangeDisplay::getTypeStatic | ( | ) | [inline, static] |
Definition at line 89 of file range_display.h.
void rviz::RangeDisplay::incomingMessage | ( | const sensor_msgs::Range::ConstPtr & | msg | ) | [protected] |
Definition at line 207 of file range_display.cpp.
void rviz::RangeDisplay::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Implements rviz::Display.
Definition at line 150 of file range_display.cpp.
void rviz::RangeDisplay::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Implements rviz::Display.
Definition at line 144 of file range_display.cpp.
void rviz::RangeDisplay::onInitialize | ( | ) | [virtual] |
Override this function to do subclass-specific initialization.
This is called after vis_manager_ and scene_manager_ are set.
Reimplemented from rviz::Display.
Definition at line 24 of file range_display.cpp.
void rviz::RangeDisplay::processMessage | ( | const sensor_msgs::Range::ConstPtr & | msg | ) | [protected] |
Definition at line 168 of file range_display.cpp.
void rviz::RangeDisplay::reset | ( | ) | [virtual] |
Called to tell the display to clear its state.
Reimplemented from rviz::Display.
Definition at line 212 of file range_display.cpp.
void rviz::RangeDisplay::setAlpha | ( | float | alpha | ) |
Definition at line 111 of file range_display.cpp.
void rviz::RangeDisplay::setBuffer | ( | int | buffer | ) |
Definition at line 82 of file range_display.cpp.
void rviz::RangeDisplay::setColor | ( | const rviz::Color & | color | ) |
Definition at line 72 of file range_display.cpp.
void rviz::RangeDisplay::setTopic | ( | const std::string & | topic | ) |
Definition at line 59 of file range_display.cpp.
void rviz::RangeDisplay::subscribe | ( | ) | [protected] |
Definition at line 121 of file range_display.cpp.
void rviz::RangeDisplay::unsubscribe | ( | ) | [protected] |
Definition at line 139 of file range_display.cpp.
void rviz::RangeDisplay::update | ( | float | wall_dt, |
float | ros_dt | ||
) | [virtual] |
Called periodically by the visualization panel.
dt | Wall-clock time, in seconds, since the last time the update list was run through. |
Reimplemented from rviz::Display.
Definition at line 163 of file range_display.cpp.
float rviz::RangeDisplay::alpha_ [protected] |
Definition at line 106 of file range_display.h.
rviz::FloatPropertyWPtr rviz::RangeDisplay::alpha_property_ [protected] |
Definition at line 120 of file range_display.h.
int rviz::RangeDisplay::buffer_len_ [protected] |
Definition at line 107 of file range_display.h.
rviz::IntPropertyWPtr rviz::RangeDisplay::bufferLen_property_ [protected] |
Definition at line 121 of file range_display.h.
rviz::Color rviz::RangeDisplay::color_ [protected] |
Definition at line 105 of file range_display.h.
rviz::ColorPropertyWPtr rviz::RangeDisplay::color_property_ [protected] |
Definition at line 118 of file range_display.h.
std::vector<Shape* > rviz::RangeDisplay::cones_ [protected] |
Handles actually drawing the cone.
Definition at line 112 of file range_display.h.
sensor_msgs::Range::ConstPtr rviz::RangeDisplay::current_message_ [protected] |
Definition at line 116 of file range_display.h.
uint32_t rviz::RangeDisplay::messages_received_ [protected] |
Definition at line 109 of file range_display.h.
Ogre::SceneNode* rviz::RangeDisplay::scene_node_ [protected] |
Definition at line 111 of file range_display.h.
message_filters::Subscriber<sensor_msgs::Range> rviz::RangeDisplay::sub_ [protected] |
Definition at line 114 of file range_display.h.
tf::MessageFilter<sensor_msgs::Range>* rviz::RangeDisplay::tf_filter_ [protected] |
Definition at line 115 of file range_display.h.
std::string rviz::RangeDisplay::topic_ [protected] |
Definition at line 104 of file range_display.h.
rviz::ROSTopicStringPropertyWPtr rviz::RangeDisplay::topic_property_ [protected] |
Definition at line 119 of file range_display.h.