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 "goal_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
00042 #include <OGRE/OgreRay.h>
00043 #include <OGRE/OgrePlane.h>
00044 #include <OGRE/OgreCamera.h>
00045 #include <OGRE/OgreSceneNode.h>
00046 #include <OGRE/OgreViewport.h>
00047
00048 #include <tf/transform_listener.h>
00049
00050 #include <wx/event.h>
00051
00052 namespace rviz
00053 {
00054
00055 GoalTool::GoalTool( const std::string& name, char shortcut_key, VisualizationManager* manager )
00056 : PoseTool( name, shortcut_key, manager )
00057 {
00058 setTopic("goal");
00059 }
00060
00061 GoalTool::~GoalTool()
00062 {
00063 }
00064
00065 void GoalTool::setTopic(const std::string& topic)
00066 {
00067 topic_ = topic;
00068 pub_ = nh_.advertise<geometry_msgs::PoseStamped>(topic, 1);
00069 }
00070
00071 void GoalTool::onPoseSet(double x, double y, double theta)
00072 {
00073 std::string fixed_frame = manager_->getFixedFrame();
00074 tf::Quaternion quat;
00075 quat.setRPY(0.0, 0.0, theta);
00076 tf::Stamped<tf::Pose> p = tf::Stamped<tf::Pose>(tf::Pose(quat, tf::Point(x, y, 0.0)), ros::Time::now(), fixed_frame);
00077 geometry_msgs::PoseStamped goal;
00078 tf::poseStampedTFToMsg(p, goal);
00079 ROS_INFO("Setting goal: Frame:%s, Position(%.3f, %.3f, %.3f), Orientation(%.3f, %.3f, %.3f, %.3f) = Angle: %.3f\n", fixed_frame.c_str(),
00080 goal.pose.position.x, goal.pose.position.y, goal.pose.position.z,
00081 goal.pose.orientation.x, goal.pose.orientation.y, goal.pose.orientation.z, goal.pose.orientation.w, theta);
00082 pub_.publish(goal);
00083 }
00084
00085 void GoalTool::enumerateProperties(PropertyManager* property_manager, const CategoryPropertyWPtr& parent)
00086 {
00087 topic_property_ = property_manager->createProperty<StringProperty>("Topic", "Tool " + getName(), boost::bind(&GoalTool::getTopic, this), boost::bind(&GoalTool::setTopic, this, _1), parent, this);
00088
00089
00090 }
00091
00092 }
00093