Skip to content

Commit

Permalink
Migrate focus tool (#266)
Browse files Browse the repository at this point in the history
* Move focus tool from rviz to rviz_default_plugins

* Make focus tool work and fix linters

* Minor refactoring of move tool

* Minor refactoring of focus tool

* Refactoring of focus_tool

* Fix windows warnings
  • Loading branch information
anhosi authored and wjwwood committed Jun 13, 2018
1 parent 5261bdd commit 96ab696
Show file tree
Hide file tree
Showing 7 changed files with 172 additions and 140 deletions.
113 changes: 0 additions & 113 deletions rviz/src/rviz/default_plugin/tools/focus_tool.cpp

This file was deleted.

1 change: 1 addition & 0 deletions rviz_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,7 @@ set(rviz_default_plugins_source_files
src/rviz_default_plugins/robot/robot_element_base_class.cpp
src/rviz_default_plugins/robot/tf_link_updater.cpp
src/rviz_default_plugins/tools/measure/measure_tool.cpp
src/rviz_default_plugins/tools/focus/focus_tool.cpp
src/rviz_default_plugins/tools/move/move_tool.cpp
src/rviz_default_plugins/tools/point/point_tool.cpp
src/rviz_default_plugins/tools/select/selection_tool.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,11 @@ namespace rviz_default_plugins
namespace tools
{

class DisplayContext;

class RVIZ_DEFAULT_PLUGINS_PUBLIC MoveTool : public rviz_common::Tool
{
public:
MoveTool();
virtual ~MoveTool();
~MoveTool() override;

void activate() override;
void deactivate() override;
Expand Down
9 changes: 9 additions & 0 deletions rviz_default_plugins/plugins_description.xml
Original file line number Diff line number Diff line change
Expand Up @@ -187,6 +187,15 @@
</description>
</class>

<class
name="rviz_default_plugins/FocusCamera"
type="rviz_default_plugins::tools::FocusTool"
base_class_type="rviz_common::Tool"
>
<description>
Click onto any object to focus the camera there.
</description>
</class>

<!-- View Controller plugins -->

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,137 @@
/*
* Copyright (c) 2013, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <sstream>

#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wunused-parameter"
# pragma GCC diagnostic ignored "-Wpedantic"
#else
#pragma warning(push)
#pragma warning(disable : 4996)
#endif

#include <OgreCamera.h>
#include <OgreRay.h>
#include <OgreVector3.h>
#include <OgreViewport.h>

#ifndef _WIN32
# pragma GCC diagnostic pop
#else
# pragma warning(pop)
#endif

#include "rviz_common/display_context.hpp"
#include "rviz_common/interaction/view_picker_iface.hpp"
#include "rviz_common/load_resource.hpp"
#include "rviz_common/render_panel.hpp"
#include "rviz_common/viewport_mouse_event.hpp"
#include "rviz_common/view_controller.hpp"
#include "rviz_rendering/render_window.hpp"

#include "./focus_tool.hpp"


namespace rviz_default_plugins
{
namespace tools
{

FocusTool::FocusTool()
: Tool()
{}

FocusTool::~FocusTool() = default;

void FocusTool::onInitialize()
{
std_cursor_ = rviz_common::getDefaultCursor();
hit_cursor_ = rviz_common::makeIconCursor("package://rviz_common/icons/crosshair.svg");
}

void FocusTool::activate()
{}

void FocusTool::deactivate()
{}

int FocusTool::processMouseEvent(rviz_common::ViewportMouseEvent & event)
{
int flags = 0;

Ogre::Vector3 position;

bool success = context_->getViewPicker()->get3DPoint(event.panel, event.x, event.y, position);
setCursor(success ? hit_cursor_ : std_cursor_);

if (!success) {
computePositionForDirection(event, position);
setStatus("<b>Left-Click:</b> Look in this direction.");
} else {
setStatusFrom(position);
}

if (event.leftUp()) {
if (event.panel->getViewController()) {
event.panel->getViewController()->lookAt(position);
}
flags |= Finished;
}

return flags;
}

void FocusTool::setStatusFrom(const Ogre::Vector3 & position)
{
std::ostringstream s;
s << "<b>Left-Click:</b> Focus on this point.";
s.precision(3);
s << " [" << position.x << "," << position.y << "," << position.z << "]";
setStatus(s.str().c_str());
}

void FocusTool::computePositionForDirection(
const rviz_common::ViewportMouseEvent & event, Ogre::Vector3 & position)
{
auto viewport =
rviz_rendering::RenderWindowOgreAdapter::getOgreViewport(event.panel->getRenderWindow());
Ogre::Ray mouse_ray = viewport->getCamera()->getCameraToViewportRay(
static_cast<float>(event.x) / static_cast<float>(viewport->getActualWidth()),
static_cast<float>(event.y) / static_cast<float>(viewport->getActualHeight()));

position = mouse_ray.getPoint(1.0);
}

} // namespace tools
} // namespace rviz_default_plugins

#include <pluginlib/class_list_macros.hpp> // NOLINT
PLUGINLIB_EXPORT_CLASS(rviz_default_plugins::tools::FocusTool, rviz_common::Tool)
Original file line number Diff line number Diff line change
Expand Up @@ -27,38 +27,46 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef RVIZ_FOCUS_TOOL_H
#define RVIZ_FOCUS_TOOL_H

#include "rviz/tool.h"
#ifndef RVIZ_DEFAULT_PLUGINS__TOOLS__FOCUS__FOCUS_TOOL_HPP_
#define RVIZ_DEFAULT_PLUGINS__TOOLS__FOCUS__FOCUS_TOOL_HPP_

#include <QCursor>

namespace rviz
#include "rviz_common/tool.hpp"
#include "rviz_common/viewport_mouse_event.hpp"

namespace rviz_default_plugins
{
namespace tools
{

//! The Focus Tool allows the user to set the focal point of the current
//! view controller with a single mouse click.
class FocusTool: public Tool
class FocusTool : public rviz_common::Tool
{
public:
FocusTool();
virtual ~FocusTool();
~FocusTool() override;

void onInitialize() override;

virtual void onInitialize();
void activate() override;
void deactivate() override;

virtual void activate();
virtual void deactivate();
int processMouseEvent(rviz_common::ViewportMouseEvent & event) override;

virtual int processMouseEvent( ViewportMouseEvent& event );
private:
void computePositionForDirection(
const rviz_common::ViewportMouseEvent & event, Ogre::Vector3 & position);

void setStatusFrom(const Ogre::Vector3 & position);

protected:
QCursor std_cursor_;
QCursor hit_cursor_;
};

}

#endif

} // namespace tools
} // namespace rviz_default_plugins

#endif // RVIZ_DEFAULT_PLUGINS__TOOLS__FOCUS__FOCUS_TOOL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,7 @@ MoveTool::MoveTool()
setIcon(rviz_common::loadPixmap("package://rviz_default_plugins/icons/classes/MoveCamera.png"));
}

MoveTool::~MoveTool()
{}
MoveTool::~MoveTool() = default;

void MoveTool::activate()
{}
Expand Down Expand Up @@ -81,12 +80,5 @@ int MoveTool::processKeyEvent(QKeyEvent * event, rviz_common::RenderPanel * pane
} // namespace tools
} // namespace rviz_default_plugins

#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wpedantic"
#endif
#include <pluginlib/class_list_macros.hpp> // NOLINT
PLUGINLIB_EXPORT_CLASS(rviz_default_plugins::tools::MoveTool, rviz_common::Tool)
#ifndef _WIN32
# pragma GCC diagnostic pop
#endif

0 comments on commit 96ab696

Please sign in to comment.