Accumulates and displays the pose from a geometry_msgs::PoseStamped message. More...
#include <pose_display.h>
Public Types | |
enum | Shape { Arrow, Axes } |
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 () |
float | getAxesLength () |
float | getAxesRadius () |
const Color & | getColor () |
float | getHeadLength () |
float | getHeadRadius () |
float | getShaftLength () |
float | getShaftRadius () |
int | getShape () |
const std::string & | getTopic () |
virtual void | onInitialize () |
Override this function to do subclass-specific initialization. | |
PoseDisplay () | |
virtual void | reset () |
Called to tell the display to clear its state. | |
void | setAlpha (float a) |
void | setAxesLength (float l) |
void | setAxesRadius (float r) |
void | setColor (const Color &color) |
void | setHeadLength (float l) |
void | setHeadRadius (float r) |
void | setShaftLength (float l) |
void | setShaftRadius (float r) |
void | setShape (int shape) |
void | setTopic (const std::string &topic) |
virtual void | update (float wall_dt, float ros_dt) |
Called periodically by the visualization panel. | |
virtual | ~PoseDisplay () |
Protected Member Functions | |
void | clear () |
void | createShapeProperties () |
void | incomingMessage (const geometry_msgs::PoseStamped::ConstPtr &message) |
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 | setVisibility () |
void | subscribe () |
void | unsubscribe () |
Protected Attributes | |
float | alpha_ |
FloatPropertyWPtr | alpha_property_ |
rviz::Arrow * | arrow_ |
rviz::Axes * | axes_ |
float | axes_length_ |
FloatPropertyWPtr | axes_length_property_ |
float | axes_radius_ |
FloatPropertyWPtr | axes_radius_property_ |
CollObjectHandle | coll_ |
PoseDisplaySelectionHandlerPtr | coll_handler_ |
Color | color_ |
ColorPropertyWPtr | color_property_ |
Shape | current_shape_ |
float | head_length_ |
FloatPropertyWPtr | head_length_property_ |
float | head_radius_ |
FloatPropertyWPtr | head_radius_property_ |
geometry_msgs::PoseStampedConstPtr | latest_message_ |
uint32_t | messages_received_ |
Ogre::SceneNode * | scene_node_ |
float | shaft_length_ |
FloatPropertyWPtr | shaft_length_property_ |
float | shaft_radius_ |
FloatPropertyWPtr | shaft_radius_property_ |
CategoryPropertyWPtr | shape_category_ |
EnumPropertyWPtr | shape_property_ |
message_filters::Subscriber < geometry_msgs::PoseStamped > | sub_ |
tf::MessageFilter < geometry_msgs::PoseStamped > * | tf_filter_ |
std::string | topic_ |
ROSTopicStringPropertyWPtr | topic_property_ |
Accumulates and displays the pose from a geometry_msgs::PoseStamped message.
Definition at line 69 of file pose_display.h.
Definition at line 72 of file pose_display.h.
Definition at line 93 of file pose_display.cpp.
rviz::PoseDisplay::~PoseDisplay | ( | ) | [virtual] |
Definition at line 136 of file pose_display.cpp.
void rviz::PoseDisplay::clear | ( | void | ) | [protected] |
Definition at line 150 of file pose_display.cpp.
void rviz::PoseDisplay::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 358 of file pose_display.cpp.
void rviz::PoseDisplay::createShapeProperties | ( | ) | [protected] |
Definition at line 308 of file pose_display.cpp.
void rviz::PoseDisplay::fixedFrameChanged | ( | ) | [virtual] |
Override to handle changes to fixed_frame_. This base class implementation does nothing.
Reimplemented from rviz::Display.
Definition at line 376 of file pose_display.cpp.
float rviz::PoseDisplay::getAlpha | ( | ) | [inline] |
Definition at line 93 of file pose_display.h.
float rviz::PoseDisplay::getAxesLength | ( | ) | [inline] |
Definition at line 109 of file pose_display.h.
float rviz::PoseDisplay::getAxesRadius | ( | ) | [inline] |
Definition at line 107 of file pose_display.h.
const Color& rviz::PoseDisplay::getColor | ( | ) | [inline] |
Definition at line 87 of file pose_display.h.
float rviz::PoseDisplay::getHeadLength | ( | ) | [inline] |
Definition at line 99 of file pose_display.h.
float rviz::PoseDisplay::getHeadRadius | ( | ) | [inline] |
Definition at line 97 of file pose_display.h.
float rviz::PoseDisplay::getShaftLength | ( | ) | [inline] |
Definition at line 103 of file pose_display.h.
float rviz::PoseDisplay::getShaftRadius | ( | ) | [inline] |
Definition at line 101 of file pose_display.h.
int rviz::PoseDisplay::getShape | ( | ) | [inline] |
Definition at line 90 of file pose_display.h.
const std::string& rviz::PoseDisplay::getTopic | ( | ) | [inline] |
Definition at line 84 of file pose_display.h.
void rviz::PoseDisplay::incomingMessage | ( | const geometry_msgs::PoseStamped::ConstPtr & | message | ) | [protected] |
Definition at line 386 of file pose_display.cpp.
void rviz::PoseDisplay::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Implements rviz::Display.
Definition at line 301 of file pose_display.cpp.
void rviz::PoseDisplay::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Implements rviz::Display.
Definition at line 294 of file pose_display.cpp.
void rviz::PoseDisplay::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 106 of file pose_display.cpp.
void rviz::PoseDisplay::reset | ( | ) | [virtual] |
Called to tell the display to clear its state.
Reimplemented from rviz::Display.
Definition at line 419 of file pose_display.cpp.
void rviz::PoseDisplay::setAlpha | ( | float | a | ) |
Definition at line 183 of file pose_display.cpp.
void rviz::PoseDisplay::setAxesLength | ( | float | l | ) |
Definition at line 230 of file pose_display.cpp.
void rviz::PoseDisplay::setAxesRadius | ( | float | r | ) |
Definition at line 223 of file pose_display.cpp.
void rviz::PoseDisplay::setColor | ( | const Color & | color | ) |
Definition at line 171 of file pose_display.cpp.
void rviz::PoseDisplay::setHeadLength | ( | float | l | ) |
Definition at line 202 of file pose_display.cpp.
void rviz::PoseDisplay::setHeadRadius | ( | float | r | ) |
Definition at line 195 of file pose_display.cpp.
void rviz::PoseDisplay::setShaftLength | ( | float | l | ) |
Definition at line 216 of file pose_display.cpp.
void rviz::PoseDisplay::setShaftRadius | ( | float | r | ) |
Definition at line 209 of file pose_display.cpp.
void rviz::PoseDisplay::setShape | ( | int | shape | ) |
Definition at line 237 of file pose_display.cpp.
void rviz::PoseDisplay::setTopic | ( | const std::string & | topic | ) |
Definition at line 160 of file pose_display.cpp.
void rviz::PoseDisplay::setVisibility | ( | ) | [protected] |
Definition at line 250 of file pose_display.cpp.
void rviz::PoseDisplay::subscribe | ( | ) | [protected] |
Definition at line 271 of file pose_display.cpp.
void rviz::PoseDisplay::unsubscribe | ( | ) | [protected] |
Definition at line 289 of file pose_display.cpp.
void rviz::PoseDisplay::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 382 of file pose_display.cpp.
float rviz::PoseDisplay::alpha_ [protected] |
Definition at line 133 of file pose_display.h.
FloatPropertyWPtr rviz::PoseDisplay::alpha_property_ [protected] |
Definition at line 164 of file pose_display.h.
rviz::Arrow* rviz::PoseDisplay::arrow_ [protected] |
Definition at line 146 of file pose_display.h.
rviz::Axes* rviz::PoseDisplay::axes_ [protected] |
Definition at line 147 of file pose_display.h.
float rviz::PoseDisplay::axes_length_ [protected] |
Definition at line 143 of file pose_display.h.
FloatPropertyWPtr rviz::PoseDisplay::axes_length_property_ [protected] |
Definition at line 171 of file pose_display.h.
float rviz::PoseDisplay::axes_radius_ [protected] |
Definition at line 144 of file pose_display.h.
FloatPropertyWPtr rviz::PoseDisplay::axes_radius_property_ [protected] |
Definition at line 172 of file pose_display.h.
CollObjectHandle rviz::PoseDisplay::coll_ [protected] |
Definition at line 148 of file pose_display.h.
Definition at line 149 of file pose_display.h.
Color rviz::PoseDisplay::color_ [protected] |
Definition at line 132 of file pose_display.h.
ColorPropertyWPtr rviz::PoseDisplay::color_property_ [protected] |
Definition at line 163 of file pose_display.h.
Shape rviz::PoseDisplay::current_shape_ [protected] |
Definition at line 134 of file pose_display.h.
float rviz::PoseDisplay::head_length_ [protected] |
Definition at line 138 of file pose_display.h.
FloatPropertyWPtr rviz::PoseDisplay::head_length_property_ [protected] |
Definition at line 167 of file pose_display.h.
float rviz::PoseDisplay::head_radius_ [protected] |
Definition at line 137 of file pose_display.h.
FloatPropertyWPtr rviz::PoseDisplay::head_radius_property_ [protected] |
Definition at line 166 of file pose_display.h.
geometry_msgs::PoseStampedConstPtr rviz::PoseDisplay::latest_message_ [protected] |
Definition at line 157 of file pose_display.h.
uint32_t rviz::PoseDisplay::messages_received_ [protected] |
Definition at line 151 of file pose_display.h.
Ogre::SceneNode* rviz::PoseDisplay::scene_node_ [protected] |
Definition at line 153 of file pose_display.h.
float rviz::PoseDisplay::shaft_length_ [protected] |
Definition at line 140 of file pose_display.h.
FloatPropertyWPtr rviz::PoseDisplay::shaft_length_property_ [protected] |
Definition at line 169 of file pose_display.h.
float rviz::PoseDisplay::shaft_radius_ [protected] |
Definition at line 139 of file pose_display.h.
FloatPropertyWPtr rviz::PoseDisplay::shaft_radius_property_ [protected] |
Definition at line 168 of file pose_display.h.
CategoryPropertyWPtr rviz::PoseDisplay::shape_category_ [protected] |
Definition at line 161 of file pose_display.h.
EnumPropertyWPtr rviz::PoseDisplay::shape_property_ [protected] |
Definition at line 160 of file pose_display.h.
message_filters::Subscriber<geometry_msgs::PoseStamped> rviz::PoseDisplay::sub_ [protected] |
Definition at line 155 of file pose_display.h.
tf::MessageFilter<geometry_msgs::PoseStamped>* rviz::PoseDisplay::tf_filter_ [protected] |
Definition at line 156 of file pose_display.h.
std::string rviz::PoseDisplay::topic_ [protected] |
Definition at line 131 of file pose_display.h.
ROSTopicStringPropertyWPtr rviz::PoseDisplay::topic_property_ [protected] |
Definition at line 159 of file pose_display.h.