Tool for publishing a goal within a mesh. More...
#include <MeshGoalTool.hpp>
Public Member Functions | |
MeshGoalTool () | |
Constructor. More... | |
virtual void | onInitialize () |
Callback that is executed when tool is initialized. More... | |
![]() | |
virtual void | activate () |
virtual void | deactivate () |
MeshPoseTool () | |
virtual int | processMouseEvent (rviz::ViewportMouseEvent &event) |
virtual | ~MeshPoseTool () |
![]() | |
bool | accessAllKeys () |
virtual QString | getClassId () const |
const QCursor & | getCursor () |
QString | getDescription () const |
const QIcon & | getIcon () |
QString | getName () const |
virtual Property * | getPropertyContainer () const |
char | getShortcutKey () |
void | initialize (DisplayContext *context) |
virtual void | load (const Config &config) |
virtual int | processKeyEvent (QKeyEvent *event, RenderPanel *panel) |
virtual void | save (Config config) const |
virtual void | setClassId (const QString &class_id) |
void | setCursor (const QCursor &cursor) |
void | setDescription (const QString &description) |
void | setIcon (const QIcon &icon) |
void | setName (const QString &name) |
void | setStatus (const QString &message) |
Tool () | |
virtual void | update (float wall_dt, float ros_dt) |
~Tool () override | |
Protected Member Functions | |
virtual void | onPoseSet (const Ogre::Vector3 &position, const Ogre::Quaternion &orientation) |
When goal is set, publish result. More... | |
![]() | |
bool | getPositionAndOrientation (const Ogre::ManualObject *mesh, const Ogre::Ray &ray, Ogre::Vector3 &position, Ogre::Vector3 &orientation) |
void | getRawManualObjectData (const Ogre::ManualObject *mesh, const size_t sectionNumber, size_t &vertexCount, Ogre::Vector3 *&vertices, size_t &indexCount, unsigned long *&indices) |
bool | selectTriangle (rviz::ViewportMouseEvent &event, Ogre::Vector3 &position, Ogre::Vector3 &orientation) |
Protected Attributes | |
ros::NodeHandle | nh_ |
Node handle. More... | |
ros::Publisher | pose_pub_ |
Publisher. More... | |
rviz::BoolProperty * | switch_bottom_top_ |
Switch bottom / top for selection. More... | |
rviz::StringProperty * | topic_property_ |
Property for the topic. More... | |
![]() | |
rviz::Arrow * | arrow_ |
Ogre::Vector3 | ori_ |
Ogre::Vector3 | pos_ |
State | state_ |
![]() | |
bool | access_all_keys_ |
DisplayContext * | context_ |
QCursor | cursor_ |
QIcon | icon_ |
Ogre::SceneManager * | scene_manager_ |
char | shortcut_key_ |
Private Slots | |
void | updateTopic () |
Updates the topic on which the goal will be published. More... | |
Additional Inherited Members | |
![]() | |
void | close () |
void | nameChanged (const QString &name) |
![]() | |
Finished | |
Render | |
![]() | |
enum | State { Position, Orientation } |
Tool for publishing a goal within a mesh.
Definition at line 64 of file MeshGoalTool.hpp.
rviz_map_plugin::MeshGoalTool::MeshGoalTool | ( | ) |
Constructor.
Definition at line 52 of file MeshGoalTool.cpp.
|
virtual |
Callback that is executed when tool is initialized.
Reimplemented from rviz_map_plugin::MeshPoseTool.
Definition at line 65 of file MeshGoalTool.cpp.
|
protectedvirtual |
When goal is set, publish result.
position | Position |
orientation | Orientation |
Implements rviz_map_plugin::MeshPoseTool.
Definition at line 77 of file MeshGoalTool.cpp.
|
privateslot |
Updates the topic on which the goal will be published.
Definition at line 72 of file MeshGoalTool.cpp.
|
protected |
Node handle.
Definition at line 100 of file MeshGoalTool.hpp.
|
protected |
Publisher.
Definition at line 98 of file MeshGoalTool.hpp.
|
protected |
Switch bottom / top for selection.
Definition at line 96 of file MeshGoalTool.hpp.
|
protected |
Property for the topic.
Definition at line 94 of file MeshGoalTool.hpp.