$search
#include <interactive_marker.h>
Classes | |
struct | MenuNode |
Public Member Functions | |
const std::string & | getName () |
const Ogre::Quaternion & | getOrientation () |
const Ogre::Vector3 & | getPosition () |
const std::string & | getReferenceFrame () |
float | getSize () |
void | handleMenuSelect (wxCommandEvent &evt) |
bool | handleMouseEvent (ViewportMouseEvent &event, const std::string &control_name) |
InteractiveMarker (InteractiveMarkerDisplay *owner, VisualizationManager *vis_manager, std::string topic_ns, std::string client_id) | |
void | processMessage (visualization_msgs::InteractiveMarkerPoseConstPtr message) |
bool | processMessage (visualization_msgs::InteractiveMarkerConstPtr message) |
void | publishFeedback (visualization_msgs::InteractiveMarkerFeedback &feedback, bool mouse_point_valid=false, const Ogre::Vector3 &mouse_point_rel_world=Ogre::Vector3(0, 0, 0)) |
void | requestPoseUpdate (Ogre::Vector3 position, Ogre::Quaternion orientation) |
void | rotate (Ogre::Quaternion delta_orientation, const std::string &control_name) |
void | setPose (Ogre::Vector3 position, Ogre::Quaternion orientation, const std::string &control_name) |
void | setReferencePose (Ogre::Vector3 position, Ogre::Quaternion orientation) |
void | setShowAxes (bool show) |
void | setShowDescription (bool show) |
void | startDragging () |
void | stopDragging () |
void | translate (Ogre::Vector3 delta_position, const std::string &control_name) |
void | update (float wall_dt) |
virtual | ~InteractiveMarker () |
Protected Types | |
typedef boost::shared_ptr < InteractiveMarkerControl > | InteractiveMarkerControlPtr |
Protected Member Functions | |
wxString | makeMenuString (const std::string &entry) |
void | populateMenu (wxMenu *menu, std::vector< uint32_t > &ids) |
void | publishPose () |
void | reset () |
void | updateReferencePose () |
Protected Attributes | |
ogre_tools::Axes * | axes_ |
Ogre::SceneNode * | axes_node_ |
std::string | client_id_ |
std::list < InteractiveMarkerControlPtr > | controls_ |
std::string | description_ |
InteractiveMarkerControlPtr | description_control_ |
bool | dragging_ |
ros::Publisher | feedback_pub_ |
bool | frame_locked_ |
bool | got_3d_point_for_menu_ |
double | heart_beat_t_ |
std::string | last_control_name_ |
boost::shared_ptr< wxMenu > | menu_ |
std::map< uint32_t, MenuNode > | menu_entries_ |
boost::recursive_mutex | mutex_ |
std::string | name_ |
std::string | old_target_frame_ |
Ogre::Quaternion | orientation_ |
InteractiveMarkerDisplay * | owner_ |
bool | pose_changed_ |
bool | pose_update_requested_ |
Ogre::Vector3 | position_ |
std::string | reference_frame_ |
Ogre::SceneNode * | reference_node_ |
ros::Time | reference_time_ |
Ogre::Quaternion | requested_orientation_ |
Ogre::Vector3 | requested_position_ |
float | scale_ |
boost::shared_ptr< boost::thread > | sys_thread_ |
Ogre::Vector3 | three_d_point_for_menu_ |
double | time_since_last_feedback_ |
std::vector< uint32_t > | top_level_menu_ids_ |
std::string | topic_ns_ |
VisualizationManager * | vis_manager_ |
Definition at line 63 of file interactive_marker.h.
typedef boost::shared_ptr<InteractiveMarkerControl> rviz::InteractiveMarker::InteractiveMarkerControlPtr [protected] |
Definition at line 153 of file interactive_marker.h.
rviz::InteractiveMarker::InteractiveMarker | ( | InteractiveMarkerDisplay * | owner, | |
VisualizationManager * | vis_manager, | |||
std::string | topic_ns, | |||
std::string | client_id | |||
) |
Definition at line 33 of file interactive_marker.cpp.
rviz::InteractiveMarker::~InteractiveMarker | ( | ) | [virtual] |
Definition at line 54 of file interactive_marker.cpp.
const std::string& rviz::InteractiveMarker::getName | ( | void | ) | [inline] |
Definition at line 101 of file interactive_marker.h.
const Ogre::Quaternion& rviz::InteractiveMarker::getOrientation | ( | ) | [inline] |
Definition at line 97 of file interactive_marker.h.
const Ogre::Vector3& rviz::InteractiveMarker::getPosition | ( | ) | [inline] |
Definition at line 96 of file interactive_marker.h.
const std::string& rviz::InteractiveMarker::getReferenceFrame | ( | ) | [inline] |
Definition at line 100 of file interactive_marker.h.
float rviz::InteractiveMarker::getSize | ( | ) | [inline] |
Definition at line 99 of file interactive_marker.h.
void rviz::InteractiveMarker::handleMenuSelect | ( | wxCommandEvent & | evt | ) |
Definition at line 463 of file interactive_marker.cpp.
bool rviz::InteractiveMarker::handleMouseEvent | ( | ViewportMouseEvent & | event, | |
const std::string & | control_name | |||
) |
Definition at line 407 of file interactive_marker.cpp.
wxString rviz::InteractiveMarker::makeMenuString | ( | const std::string & | entry | ) | [protected] |
Definition at line 214 of file interactive_marker.cpp.
void rviz::InteractiveMarker::populateMenu | ( | wxMenu * | menu, | |
std::vector< uint32_t > & | ids | |||
) | [protected] |
Definition at line 188 of file interactive_marker.cpp.
void rviz::InteractiveMarker::processMessage | ( | visualization_msgs::InteractiveMarkerPoseConstPtr | message | ) |
Definition at line 68 of file interactive_marker.cpp.
bool rviz::InteractiveMarker::processMessage | ( | visualization_msgs::InteractiveMarkerConstPtr | message | ) |
Definition at line 88 of file interactive_marker.cpp.
void rviz::InteractiveMarker::publishFeedback | ( | visualization_msgs::InteractiveMarkerFeedback & | feedback, | |
bool | mouse_point_valid = false , |
|||
const Ogre::Vector3 & | mouse_point_rel_world = Ogre::Vector3(0,0,0) | |||
) |
Definition at line 502 of file interactive_marker.cpp.
void rviz::InteractiveMarker::publishPose | ( | ) | [protected] |
Definition at line 313 of file interactive_marker.cpp.
void rviz::InteractiveMarker::requestPoseUpdate | ( | Ogre::Vector3 | position, | |
Ogre::Quaternion | orientation | |||
) |
Definition at line 323 of file interactive_marker.cpp.
void rviz::InteractiveMarker::reset | ( | ) | [protected] |
Definition at line 61 of file interactive_marker.cpp.
void rviz::InteractiveMarker::rotate | ( | Ogre::Quaternion | delta_orientation, | |
const std::string & | control_name | |||
) |
Definition at line 378 of file interactive_marker.cpp.
void rviz::InteractiveMarker::setPose | ( | Ogre::Vector3 | position, | |
Ogre::Quaternion | orientation, | |||
const std::string & | control_name | |||
) |
Definition at line 339 of file interactive_marker.cpp.
void rviz::InteractiveMarker::setReferencePose | ( | Ogre::Vector3 | position, | |
Ogre::Quaternion | orientation | |||
) |
void rviz::InteractiveMarker::setShowAxes | ( | bool | show | ) |
Definition at line 366 of file interactive_marker.cpp.
void rviz::InteractiveMarker::setShowDescription | ( | bool | show | ) |
Definition at line 357 of file interactive_marker.cpp.
void rviz::InteractiveMarker::startDragging | ( | ) |
Definition at line 384 of file interactive_marker.cpp.
void rviz::InteractiveMarker::stopDragging | ( | ) |
Definition at line 391 of file interactive_marker.cpp.
void rviz::InteractiveMarker::translate | ( | Ogre::Vector3 | delta_position, | |
const std::string & | control_name | |||
) |
Definition at line 372 of file interactive_marker.cpp.
void rviz::InteractiveMarker::update | ( | float | wall_dt | ) |
Definition at line 282 of file interactive_marker.cpp.
void rviz::InteractiveMarker::updateReferencePose | ( | ) | [protected] |
Definition at line 232 of file interactive_marker.cpp.
ogre_tools::Axes* rviz::InteractiveMarker::axes_ [protected] |
Definition at line 191 of file interactive_marker.h.
Ogre::SceneNode* rviz::InteractiveMarker::axes_node_ [protected] |
Definition at line 192 of file interactive_marker.h.
std::string rviz::InteractiveMarker::client_id_ [protected] |
Definition at line 198 of file interactive_marker.h.
std::list<InteractiveMarkerControlPtr> rviz::InteractiveMarker::controls_ [protected] |
Definition at line 154 of file interactive_marker.h.
std::string rviz::InteractiveMarker::description_ [protected] |
Definition at line 157 of file interactive_marker.h.
Definition at line 194 of file interactive_marker.h.
bool rviz::InteractiveMarker::dragging_ [protected] |
Definition at line 159 of file interactive_marker.h.
ros::Publisher rviz::InteractiveMarker::feedback_pub_ [protected] |
Definition at line 196 of file interactive_marker.h.
bool rviz::InteractiveMarker::frame_locked_ [protected] |
Definition at line 140 of file interactive_marker.h.
bool rviz::InteractiveMarker::got_3d_point_for_menu_ [protected] |
Definition at line 204 of file interactive_marker.h.
double rviz::InteractiveMarker::heart_beat_t_ [protected] |
Definition at line 187 of file interactive_marker.h.
std::string rviz::InteractiveMarker::last_control_name_ [protected] |
Definition at line 185 of file interactive_marker.h.
boost::shared_ptr<wxMenu> rviz::InteractiveMarker::menu_ [protected] |
Definition at line 169 of file interactive_marker.h.
std::map< uint32_t, MenuNode > rviz::InteractiveMarker::menu_entries_ [protected] |
Definition at line 179 of file interactive_marker.h.
boost::recursive_mutex rviz::InteractiveMarker::mutex_ [protected] |
Definition at line 200 of file interactive_marker.h.
std::string rviz::InteractiveMarker::name_ [protected] |
Definition at line 156 of file interactive_marker.h.
std::string rviz::InteractiveMarker::old_target_frame_ [protected] |
Definition at line 160 of file interactive_marker.h.
Ogre::Quaternion rviz::InteractiveMarker::orientation_ [protected] |
Definition at line 147 of file interactive_marker.h.
InteractiveMarkerDisplay* rviz::InteractiveMarker::owner_ [protected] |
Definition at line 134 of file interactive_marker.h.
bool rviz::InteractiveMarker::pose_changed_ [protected] |
Definition at line 150 of file interactive_marker.h.
bool rviz::InteractiveMarker::pose_update_requested_ [protected] |
Definition at line 163 of file interactive_marker.h.
Ogre::Vector3 rviz::InteractiveMarker::position_ [protected] |
Definition at line 146 of file interactive_marker.h.
std::string rviz::InteractiveMarker::reference_frame_ [protected] |
Definition at line 138 of file interactive_marker.h.
Ogre::SceneNode* rviz::InteractiveMarker::reference_node_ [protected] |
Definition at line 143 of file interactive_marker.h.
ros::Time rviz::InteractiveMarker::reference_time_ [protected] |
Definition at line 139 of file interactive_marker.h.
Ogre::Quaternion rviz::InteractiveMarker::requested_orientation_ [protected] |
Definition at line 165 of file interactive_marker.h.
Ogre::Vector3 rviz::InteractiveMarker::requested_position_ [protected] |
Definition at line 164 of file interactive_marker.h.
float rviz::InteractiveMarker::scale_ [protected] |
Definition at line 167 of file interactive_marker.h.
boost::shared_ptr< boost::thread > rviz::InteractiveMarker::sys_thread_ [protected] |
Definition at line 202 of file interactive_marker.h.
Ogre::Vector3 rviz::InteractiveMarker::three_d_point_for_menu_ [protected] |
Definition at line 205 of file interactive_marker.h.
double rviz::InteractiveMarker::time_since_last_feedback_ [protected] |
Definition at line 151 of file interactive_marker.h.
std::vector<uint32_t> rviz::InteractiveMarker::top_level_menu_ids_ [protected] |
Definition at line 182 of file interactive_marker.h.
std::string rviz::InteractiveMarker::topic_ns_ [protected] |
Definition at line 197 of file interactive_marker.h.
Definition at line 135 of file interactive_marker.h.