00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "marker_selection_handler.h"
00031 #include "marker_base.h"
00032 #include "rviz/default_plugin/marker_display.h"
00033 #include "rviz/properties/property_manager.h"
00034 #include "rviz/properties/property.h"
00035
00036 #include <OGRE/OgreVector3.h>
00037 #include <OGRE/OgreQuaternion.h>
00038
00039 #include <boost/bind.hpp>
00040
00041 namespace rviz
00042 {
00043
00044 MarkerSelectionHandler::MarkerSelectionHandler(const MarkerBase* marker, MarkerID id)
00045 : marker_(marker)
00046 , id_(id)
00047 {
00048 }
00049
00050 MarkerSelectionHandler::~MarkerSelectionHandler()
00051 {
00052 }
00053
00054 Ogre::Vector3 MarkerSelectionHandler::getPosition()
00055 {
00056 return Ogre::Vector3(marker_->getMessage()->pose.position.x, marker_->getMessage()->pose.position.y, marker_->getMessage()->pose.position.z);
00057 }
00058
00059 Ogre::Quaternion MarkerSelectionHandler::getOrientation()
00060 {
00061 return Ogre::Quaternion(marker_->getMessage()->pose.orientation.w, marker_->getMessage()->pose.orientation.x, marker_->getMessage()->pose.orientation.y, marker_->getMessage()->pose.orientation.z);
00062 }
00063
00064 void MarkerSelectionHandler::createProperties(const Picked& obj, PropertyManager* property_manager)
00065 {
00066 std::stringstream prefix;
00067 prefix << "Marker " << id_.first << "/" << id_.second;
00068 CategoryPropertyWPtr cat = property_manager->createCategory(prefix.str(), prefix.str());
00069 properties_.push_back(property_manager->createProperty<StringProperty>("ID", prefix.str(), boost::bind(&MarkerSelectionHandler::getId, this), StringProperty::Setter(), cat));
00070 properties_.push_back(property_manager->createProperty<Vector3Property>("Position", prefix.str(), boost::bind(&MarkerSelectionHandler::getPosition, this), Vector3Property::Setter(), cat));
00071 properties_.push_back(property_manager->createProperty<QuaternionProperty>("Orientation", prefix.str(), boost::bind(&MarkerSelectionHandler::getOrientation, this), QuaternionProperty::Setter(), cat));
00072 }
00073
00074 }