Skip to content

Commit

Permalink
added point coordinate to point tool status text
Browse files Browse the repository at this point in the history
  • Loading branch information
David Gossow committed Jan 31, 2013
1 parent 86e79d3 commit 0167fb1
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion src/rviz/default_plugin/tools/point_tool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@

#include <geometry_msgs/PointStamped.h>

#include <sstream>

namespace rviz
{

Expand Down Expand Up @@ -98,7 +100,11 @@ int PointTool::processMouseEvent( ViewportMouseEvent& event )

if ( success )
{
setStatus( "<b>Left-Click:</b> Select this point." );
std::ostringstream s;
s << "<b>Left-Click:</b> Select this point.";
s.precision(3);
s << " [" << pos.x << "," << pos.y << "," << pos.z << "]";
setStatus( s.str().c_str() );

if( event.leftUp() )
{
Expand Down

0 comments on commit 0167fb1

Please sign in to comment.