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