Skip to content

Commit

Permalink
Migrate select tool (#256)
Browse files Browse the repository at this point in the history
* Move select tool

* Make select tool compile

* Add Selection Panel

* Fix selection

* Move Viewport methods to SelectionManager

* Extract rendering functionality from SelectionManager

- Push necessary functionality to DisplayContext
- Not many more methods needed to extract VisualizationManager dependency
- This allows unittesting of selection_manager

* First simple test for selection_manager

- Add a second constructor for testing
- Delete publisher code (can't work well with tests)

* Inline ViewPort functions

- avoid overloaded functions for Ogre::Viewport in addition to those
  expecting a RenderWindow

* Cleanup of tool base class and failed tool

* Add tests for SelectionTool

* Fix selection behaviour of PointCloud.

* Rework test setup for selection_manager

* Reduce public interface of selection manager

- Some functions may need to be made public again once more of rviz is ported.

* Refactor SelectionHandler

* Add SelectionHandlerTest

* Add tests for selection manager

* Refactor SelectionHandler.

* small first refactorings

- introduce structs to simplify function signatures
- replace typedefs with using

* Move SelectionRenderer to public interface

* First simple refactoring pass

* Refactor SelectionRenderer

* Replace output parameters with class member usage

* Rename namespace rviz_common::selection to rviz_common::interaction

* Extract additional methods in SelectionRenderer

* Add tests for SelectionHandler and fix linters

* Introduce HandlerManager

- extracts the object handling from SelectionManager
- prerequisite for splitting the 3D picking from the SelectionManager
- Add HandlerManager to DisplayContext/ VisualizationManager
- Use HandlerManager from SelectionManager and for SelectionHandler

* Adapt all selection handlers to new interface and add tests

- offer a template function to create SelectionHandlers
- add tests to point_cloud_selection_handler + refactoring
- Fix sloppy following behaviour of the selection box for PoseDisplay and Arrow marker

* Extract non selection parts of SelectionManager into ViewPicker

* Let SelectionManager listen to HandlerManager changes

* Rewrite SelectionHandler tests

* Clean up SelectionManager and SelectionRenderer interface

* Move preRenderPass and postRenderPass runs into renderer

* Encapsulate HandlersMap and improve user experience

- Refactor HandlerManager to no longer expose the handlers map
- returns a HandlerRange instead which can be iterated over and
  contains directly the handlers
- Use deadlock free locking variant
- Add documentation

* Cleanup include statements

* Cleanup style

* Use shared_ptrs instead of raw pointers

Store only weak_ptrs in mocks so that the cleanup can happen during teardown.

* Minor refactoring of ViewPicker

* Try to fix Windows build

* Replace SetUp/Teardown in tests with constructor

* Replace SetUp/Teardown with constructor in the remaining packages
  • Loading branch information
Martin-Idel-SI authored and wjwwood committed May 16, 2018
1 parent e8181a4 commit a62340f
Show file tree
Hide file tree
Showing 99 changed files with 4,689 additions and 2,554 deletions.
37 changes: 32 additions & 5 deletions rviz_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -108,8 +108,9 @@ set(rviz_common_headers_to_moc
include/rviz_common/render_panel.hpp
src/rviz_common/scaled_image_widget.hpp
src/rviz_common/screenshot_dialog.hpp
include/rviz_common/selection/selection_manager.hpp
include/rviz_common/selection/selection_manager_iface.hpp
include/rviz_common/interaction/selection_manager.hpp
include/rviz_common/interaction/selection_manager_iface.hpp
include/rviz_common/interaction/selection_renderer.hpp
src/rviz_common/splash_screen.hpp
# src/rviz_common/time_panel.hpp
include/rviz_common/tool.hpp
Expand Down Expand Up @@ -185,9 +186,12 @@ set(rviz_common_source_files
src/rviz_common/ros_integration/ros_node_storage.cpp
src/rviz_common/scaled_image_widget.cpp
src/rviz_common/screenshot_dialog.cpp
# src/rviz_common/selection_panel.cpp
src/rviz_common/selection/selection_handler.cpp
src/rviz_common/selection/selection_manager.cpp
src/rviz_common/selection_panel.cpp
src/rviz_common/interaction/handler_manager.cpp
src/rviz_common/interaction/selection_handler.cpp
src/rviz_common/interaction/selection_manager.cpp
src/rviz_common/interaction/selection_renderer.cpp
src/rviz_common/interaction/view_picker.cpp
src/rviz_common/splash_screen.cpp
# src/rviz_common/time_panel.cpp
src/rviz_common/tool_manager.cpp
Expand Down Expand Up @@ -346,6 +350,29 @@ if(BUILD_TESTING)
if((APPLE AND NOT CMAKE_BUILD_TYPE STREQUAL "Debug") OR DISPLAYPRESENT OR EnableDisplayTests STREQUAL "True")
message(STATUS "Enabling tests requiring a display")

ament_add_gmock(selection_manager_test
test/interaction/selection_manager_test.cpp
test/interaction/mock_selection_renderer.hpp
test/interaction/selection_test_fixture.hpp
test/display_context_fixture.cpp)
if(TARGET selection_manager_test)
target_link_libraries(selection_manager_test
rviz_common
rviz_ogre_vendor::OgreMain
rviz_ogre_vendor::OgreOverlay)
endif()

ament_add_gmock(selection_handler_test
test/interaction/selection_handler_test.cpp
test/interaction/selection_test_fixture.hpp
test/display_context_fixture.cpp)
if(TARGET selection_handler_test)
target_link_libraries(selection_handler_test
rviz_common
rviz_ogre_vendor::OgreMain
rviz_ogre_vendor::OgreOverlay)
endif()

ament_add_gtest(rviz_common_display_test
test/display_test.cpp
test/mock_display.cpp
Expand Down
6 changes: 3 additions & 3 deletions rviz_common/default.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@ Panels:
Splitter Ratio: 0.5
Tree Height: 464
# TODO(wjwwood): restore these panels when ported
# - Class: rviz/Selection
# Name: Selection
- Class: rviz_common/Selection
Name: Selection
# - Class: rviz/Tool Properties
# Expanded:
# - /2D Pose Estimate1
Expand Down Expand Up @@ -58,7 +58,7 @@ Visualization Manager:
# - Class: rviz/Interact
# Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
# - Class: rviz/Select
- Class: rviz_default_plugins/Select
# - Class: rviz/FocusCamera
# - Class: rviz/Measure
# - Class: rviz/SetInitialPose
Expand Down
26 changes: 23 additions & 3 deletions rviz_common/include/rviz_common/display_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,12 +63,14 @@ class Node;
namespace rviz_common
{

namespace selection
namespace interaction
{

class SelectionManagerIface;
class HandlerManagerIface;
class ViewPickerIface;

} // namespace selection
} // namespace interaction

class BitAllocator;
class DisplayFactory;
Expand Down Expand Up @@ -112,9 +114,19 @@ class RVIZ_COMMON_PUBLIC DisplayContext : public QObject

/// Return a pointer to the SelectionManager.
virtual
rviz_common::selection::SelectionManagerIface *
std::shared_ptr<rviz_common::interaction::SelectionManagerIface>
getSelectionManager() const = 0;

/// Return a pointer to the HandlerManager.
virtual
std::shared_ptr<rviz_common::interaction::HandlerManagerIface>
getHandlerManager() const = 0;

/// Return a pointer to the ViewPicker.
virtual
std::shared_ptr<rviz_common::interaction::ViewPickerIface>
getViewPicker() const = 0;

/// Return the FrameManager instance.
virtual
FrameManagerIface *
Expand Down Expand Up @@ -200,6 +212,14 @@ class RVIZ_COMMON_PUBLIC DisplayContext : public QObject
std::shared_ptr<rclcpp::Clock>
getClock() = 0;

virtual
void
lockRender() = 0;

virtual
void
unlockRender() = 0;

public Q_SLOTS:
/// Queue a render.
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef RVIZ_COMMON__SELECTION__FORWARDS_HPP_
#define RVIZ_COMMON__SELECTION__FORWARDS_HPP_
#ifndef RVIZ_COMMON__INTERACTION__FORWARDS_HPP_
#define RVIZ_COMMON__INTERACTION__FORWARDS_HPP_

#include <map>
#include <set>
Expand All @@ -51,16 +51,16 @@

namespace rviz_common
{
namespace selection
namespace interaction
{

typedef uint32_t CollObjectHandle;
typedef std::vector<CollObjectHandle> V_CollObject;
typedef std::vector<V_CollObject> VV_CollObject;
typedef std::set<CollObjectHandle> S_CollObject;
using CollObjectHandle = uint32_t;
using V_CollObject = std::vector<CollObjectHandle>;
using VV_CollObject = std::vector<V_CollObject>;
using S_CollObject = std::set<CollObjectHandle>;

typedef std::set<uint64_t> S_uint64;
typedef std::vector<uint64_t> V_uint64;
using S_uint64 = std::set<uint64_t>;
using V_uint64 = std::vector<uint64_t>;

struct Picked
{
Expand All @@ -74,7 +74,7 @@ struct Picked
S_uint64 extra_handles;
};

typedef std::unordered_map<CollObjectHandle, Picked> M_Picked;
using M_Picked = std::unordered_map<CollObjectHandle, Picked>;

inline uint32_t colorToHandle(Ogre::PixelFormat fmt, uint32_t col)
{
Expand All @@ -99,7 +99,7 @@ inline CollObjectHandle colorToHandle(const Ogre::ColourValue & color)
}


} // namespace selection
} // namespace interaction
} // namespace rviz_common

#endif // RVIZ_COMMON__SELECTION__FORWARDS_HPP_
#endif // RVIZ_COMMON__INTERACTION__FORWARDS_HPP_
99 changes: 99 additions & 0 deletions rviz_common/include/rviz_common/interaction/handler_manager.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
/*
* Copyright (c) 2008, Willow Garage, Inc.
* Copyright (c) 2017, Open Source Robotics Foundation, Inc.
* Copyright (c) 2018, Bosch Software Innovations GmbH.
* 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 copyright holder 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.
*/

#ifndef RVIZ_COMMON__INTERACTION__HANDLER_MANAGER_HPP_
#define RVIZ_COMMON__INTERACTION__HANDLER_MANAGER_HPP_

#include "handler_manager_iface.hpp"

#include <mutex>
#include <vector>

#include "rviz_common/interaction/forwards.hpp"
#include "rviz_common/interaction/handler_manager_listener.hpp"
#include "rviz_common/interaction/selection_handler.hpp"
#include "rviz_common/visibility_control.hpp"


namespace rviz_common
{

class DisplayContext;

namespace interaction
{

class RVIZ_COMMON_PUBLIC HandlerManager
: public HandlerManagerIface
{
public:
HandlerManager();

~HandlerManager() override;

void addHandler(CollObjectHandle handle, SelectionHandlerWeakPtr handler) override;

void removeHandler(CollObjectHandle handle) override;

SelectionHandlerPtr getHandler(CollObjectHandle handle) override;

std::unique_lock<std::recursive_mutex> lock() override;

std::unique_lock<std::recursive_mutex> lock(std::defer_lock_t defer_lock) override;

void addListener(HandlerManagerListener * listener) override;

void removeListener(HandlerManagerListener * listener) override;

CollObjectHandle createHandle() override;

void enableInteraction(bool enable) override;

bool getInteractionEnabled() const override;

HandlerRange handlers() override;

private:
uint32_t uid_counter_;

bool interaction_enabled_;

std::recursive_mutex handlers_mutex_;
std::recursive_mutex uid_mutex_;

M_ObjectHandleToSelectionHandler handlers_;
std::vector<HandlerManagerListener *> listeners_;
};

} // namespace interaction
} // namespace rviz_common

#endif // RVIZ_COMMON__INTERACTION__HANDLER_MANAGER_HPP_
Loading

0 comments on commit a62340f

Please sign in to comment.