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