#include <PathVisual.h>
Public Member Functions | |
PathVisual (Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node) | |
void | setFrameOrientation (const Ogre::Quaternion &orientation) |
void | setFramePosition (const Ogre::Vector3 &position) |
void | setMessage (const nav_msgs::Path::ConstPtr &msg) |
void | setOrientColor (Ogre::ColourValue color) |
void | setOrientDeltaS (double deltaS) |
void | setOrientScale (float scale) |
void | setPathColor (Ogre::ColourValue color) |
void | setPathScale (float scale) |
void | setShape (rviz::Shape::Type shape_type) |
virtual | ~PathVisual () |
Private Attributes | |
Ogre::ColourValue | colorOrient_ |
Ogre::ColourValue | colorPath_ |
double | deltaSOrient_ |
Ogre::SceneNode * | frame_node_ |
std::vector< boost::shared_ptr< rviz::Arrow > > | pathPtsTheta_ |
std::vector< boost::shared_ptr< rviz::Shape > > | pathPtsXY_ |
float | scaleOrient_ |
float | scalePath_ |
Ogre::SceneManager * | scene_manager_ |
rviz::Shape::Type | shape_type_ |
Definition at line 55 of file PathVisual.h.
tuw_nav_rviz::PathVisual::PathVisual | ( | Ogre::SceneManager * | scene_manager, |
Ogre::SceneNode * | parent_node | ||
) |
Definition at line 42 of file PathVisual.cpp.
|
virtual |
Definition at line 63 of file PathVisual.cpp.
void tuw_nav_rviz::PathVisual::setFrameOrientation | ( | const Ogre::Quaternion & | orientation | ) |
Definition at line 136 of file PathVisual.cpp.
void tuw_nav_rviz::PathVisual::setFramePosition | ( | const Ogre::Vector3 & | position | ) |
Definition at line 131 of file PathVisual.cpp.
void tuw_nav_rviz::PathVisual::setMessage | ( | const nav_msgs::Path::ConstPtr & | msg | ) |
Definition at line 68 of file PathVisual.cpp.
void tuw_nav_rviz::PathVisual::setOrientColor | ( | Ogre::ColourValue | color | ) |
Definition at line 147 of file PathVisual.cpp.
void tuw_nav_rviz::PathVisual::setOrientDeltaS | ( | double | deltaS | ) |
Definition at line 178 of file PathVisual.cpp.
void tuw_nav_rviz::PathVisual::setOrientScale | ( | float | scale | ) |
Definition at line 173 of file PathVisual.cpp.
void tuw_nav_rviz::PathVisual::setPathColor | ( | Ogre::ColourValue | color | ) |
Definition at line 141 of file PathVisual.cpp.
void tuw_nav_rviz::PathVisual::setPathScale | ( | float | scale | ) |
Definition at line 167 of file PathVisual.cpp.
void tuw_nav_rviz::PathVisual::setShape | ( | rviz::Shape::Type | shape_type | ) |
Definition at line 153 of file PathVisual.cpp.
|
private |
Definition at line 107 of file PathVisual.h.
|
private |
Definition at line 106 of file PathVisual.h.
|
private |
Definition at line 116 of file PathVisual.h.
|
private |
Definition at line 99 of file PathVisual.h.
|
private |
Definition at line 95 of file PathVisual.h.
|
private |
Definition at line 94 of file PathVisual.h.
|
private |
Definition at line 114 of file PathVisual.h.
|
private |
Definition at line 113 of file PathVisual.h.
|
private |
Definition at line 103 of file PathVisual.h.
|
private |
Definition at line 110 of file PathVisual.h.