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 "initial_pose_tool.h"
00031 #include "common.h"
00032 #include "visualization_manager.h"
00033 #include "viewport_mouse_event.h"
00034 #include "properties/property.h"
00035 #include "properties/property_manager.h"
00036 
00037 #include "ogre_tools/camera_base.h"
00038 #include "ogre_tools/arrow.h"
00039 #include "ogre_tools/wx_ogre_render_window.h"
00040 
00041 #include <geometry_msgs/PoseStamped.h>
00042 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00043 
00044 #include <OGRE/OgreRay.h>
00045 #include <OGRE/OgrePlane.h>
00046 #include <OGRE/OgreCamera.h>
00047 #include <OGRE/OgreSceneNode.h>
00048 #include <OGRE/OgreViewport.h>
00049 
00050 #include <tf/transform_listener.h>
00051 
00052 #include <wx/event.h>
00053 
00054 namespace rviz
00055 {
00056 
00057 InitialPoseTool::InitialPoseTool( const std::string& name, char shortcut_key, VisualizationManager* manager )
00058 : PoseTool( name, shortcut_key, manager )
00059 {
00060   setTopic("initialpose");
00061 }
00062 
00063 InitialPoseTool::~InitialPoseTool()
00064 {
00065 }
00066 
00067 void InitialPoseTool::setTopic(const std::string& topic)
00068 {
00069   topic_ = topic;
00070   pub_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>(topic, 1);
00071 }
00072 
00073 void InitialPoseTool::onPoseSet(double x, double y, double theta)
00074 {
00075   std::string fixed_frame = manager_->getFixedFrame();
00076   geometry_msgs::PoseWithCovarianceStamped pose;
00077   pose.header.frame_id = fixed_frame;
00078   pose.pose.pose.position.x = x;
00079   pose.pose.pose.position.y = y;
00080 
00081   btQuaternion quat;
00082   quat.setRPY(0.0, 0.0, theta);
00083   tf::quaternionTFToMsg(quat,
00084                         pose.pose.pose.orientation);
00085   pose.pose.covariance[6*0+0] = 0.5 * 0.5;
00086   pose.pose.covariance[6*1+1] = 0.5 * 0.5;
00087   pose.pose.covariance[6*3+3] = M_PI/12.0 * M_PI/12.0;
00088   ROS_INFO("Setting pose: %.3f %.3f %.3f [frame=%s]", x, y, theta, fixed_frame.c_str());
00089   pub_.publish(pose);
00090 }
00091 
00092 void InitialPoseTool::enumerateProperties(PropertyManager* property_manager, const CategoryPropertyWPtr& parent)
00093 {
00094   topic_property_ = property_manager->createProperty<StringProperty>("Topic", "Tool " + getName(), boost::bind(&InitialPoseTool::getTopic, this), boost::bind(&InitialPoseTool::setTopic, this, _1), parent, this);
00095 }
00096 
00097 }
00098