#include <InteractiveObject.h>
Public Member Functions | |
void | addMenuEntry (std::string strLabel, std::string strIdentifier, std::string strParameter="") |
std::list < InteractiveObjectCallbackResult > | callbackResults () |
void | clearMenuEntries () |
void | clickCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
bool | insertIntoServer (interactive_markers::InteractiveMarkerServer *imsServer) |
InteractiveObject (std::string strName) | |
std::string | name () |
bool | removeFromServer () |
void | removeMenuEntry (std::string strIdentifier, std::string strParameter="") |
void | setMarker (visualization_msgs::Marker mkrMarker) |
void | setPose (std::string strFixedFrame, geometry_msgs::Pose posPose) |
void | setPose (geometry_msgs::Pose posPose) |
void | setSize (float fWidth, float fDepth, float fHeight) |
~InteractiveObject () | |
Private Attributes | |
visualization_msgs::InteractiveMarkerControl | m_imcControl |
visualization_msgs::InteractiveMarker | m_imMarker |
interactive_markers::InteractiveMarkerServer * | m_imsServer |
std::list < InteractiveObjectCallbackResult > | m_lstCallbackResults |
std::list< InteractiveMenuEntry > | m_lstMenuEntries |
interactive_markers::MenuHandler | m_mhMenu |
visualization_msgs::Marker | m_mkrMarker |
std::mutex | m_mtxCallbackResults |
Definition at line 69 of file InteractiveObject.h.
beliefstate::InteractiveObject::InteractiveObject | ( | std::string | strName | ) |
Definition at line 44 of file InteractiveObject.cpp.
Definition at line 61 of file InteractiveObject.cpp.
void beliefstate::InteractiveObject::addMenuEntry | ( | std::string | strLabel, |
std::string | strIdentifier, | ||
std::string | strParameter = "" |
||
) |
Definition at line 159 of file InteractiveObject.cpp.
Definition at line 213 of file InteractiveObject.cpp.
Definition at line 177 of file InteractiveObject.cpp.
void beliefstate::InteractiveObject::clickCallback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) |
Definition at line 89 of file InteractiveObject.cpp.
bool beliefstate::InteractiveObject::insertIntoServer | ( | interactive_markers::InteractiveMarkerServer * | imsServer | ) |
Definition at line 117 of file InteractiveObject.cpp.
std::string beliefstate::InteractiveObject::name | ( | ) |
Definition at line 155 of file InteractiveObject.cpp.
Definition at line 142 of file InteractiveObject.cpp.
void beliefstate::InteractiveObject::removeMenuEntry | ( | std::string | strIdentifier, |
std::string | strParameter = "" |
||
) |
Definition at line 188 of file InteractiveObject.cpp.
void beliefstate::InteractiveObject::setMarker | ( | visualization_msgs::Marker | mkrMarker | ) |
Definition at line 83 of file InteractiveObject.cpp.
void beliefstate::InteractiveObject::setPose | ( | std::string | strFixedFrame, |
geometry_msgs::Pose | posPose | ||
) |
Definition at line 72 of file InteractiveObject.cpp.
void beliefstate::InteractiveObject::setPose | ( | geometry_msgs::Pose | posPose | ) |
Definition at line 79 of file InteractiveObject.cpp.
void beliefstate::InteractiveObject::setSize | ( | float | fWidth, |
float | fDepth, | ||
float | fHeight | ||
) |
Definition at line 64 of file InteractiveObject.cpp.
visualization_msgs::InteractiveMarkerControl beliefstate::InteractiveObject::m_imcControl [private] |
Definition at line 75 of file InteractiveObject.h.
visualization_msgs::InteractiveMarker beliefstate::InteractiveObject::m_imMarker [private] |
Definition at line 73 of file InteractiveObject.h.
Definition at line 74 of file InteractiveObject.h.
std::list<InteractiveObjectCallbackResult> beliefstate::InteractiveObject::m_lstCallbackResults [private] |
Definition at line 77 of file InteractiveObject.h.
std::list<InteractiveMenuEntry> beliefstate::InteractiveObject::m_lstMenuEntries [private] |
Definition at line 76 of file InteractiveObject.h.
Definition at line 72 of file InteractiveObject.h.
visualization_msgs::Marker beliefstate::InteractiveObject::m_mkrMarker [private] |
Definition at line 71 of file InteractiveObject.h.
std::mutex beliefstate::InteractiveObject::m_mtxCallbackResults [private] |
Definition at line 78 of file InteractiveObject.h.