Skip to content

Commit

Permalink
#378 solution for the OGRE problem.
Browse files Browse the repository at this point in the history
  • Loading branch information
miguelriemoliveira committed Apr 7, 2022
1 parent 7a35250 commit 8afb566
Show file tree
Hide file tree
Showing 7 changed files with 412 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ def setupVisualization(dataset, args, selected_collection_key):
# graphics['ros']['tf_broadcaster'] = tf.TransformBroadcaster()
graphics['ros']['tf_broadcaster'] = tf2_ros.TransformBroadcaster()

rospy.sleep(0.2) # Sleep a litle to make sure the time.now() returns a correct time.
rospy.sleep(0.2) # Sleep a little to make sure the time.now() returns a correct time.
now = rospy.Time.now()

graphics['ros']['publisher_models'] = rospy.Publisher('~robot_meshes', MarkerArray, queue_size=0, latch=True)
Expand Down
4 changes: 4 additions & 0 deletions atom_rviz_plugins/image_display_with_click/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ link_directories(${catkin_LIBRARY_DIRS})
# source codes #
set(HEADERS
include/image_display_with_click/image_display_with_click.h
include/image_display_with_click/image_display_with_click_base.h
include/image_display_with_click/mouse_watcher.h
)
#qt5_wrap_ui(UIC_FILES
Expand All @@ -70,12 +71,15 @@ set(HEADERS
set(SOURCE_FILES
src/plugin_load.cpp
src/image_display_with_click.cpp
src/image_display_with_click_base.cpp
src/mouse_watcher.cpp
)

add_library(${PROJECT_NAME} SHARED ${SOURCE_FILES} ${HEADERS} ${UIC_FILES})
# add_library(${PROJECT_NAME} ${SOURCE_FILES})
set_target_properties(${PROJECT_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
target_include_directories(${PROJECT_NAME} PRIVATE "${OGRE_PREFIX_DIR}/include")
# target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES})



Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "std_msgs/String.h"

#include <image_display_with_click/mouse_watcher.h>
#include <image_display_with_click/image_display_with_click_base.h>

namespace Ogre
{
Expand All @@ -30,10 +31,11 @@ namespace Ogre
} // namespace Ogre

using namespace std;
using namespace rviz;

namespace atom_rviz
{
class ImageDisplayWithClick : public rviz::ImageDisplayBase
class ImageDisplayWithClick : public atom_rviz::ImageDisplayWithClickBase
{
Q_OBJECT
public:
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
#ifndef IMAGE_DISPLAY_WITH_CLICK_BASE_H
#define IMAGE_DISPLAY_WITH_CLICK_BASE_H

#include <QObject>

#ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
#include <message_filters/subscriber.h>
#include <tf2_ros/message_filter.h>
#include <sensor_msgs/Image.h>

#include <image_transport/image_transport.h>
#include <image_transport/subscriber_filter.h>

#include "rviz/display_context.h"
#include "rviz/frame_manager.h"
#include "rviz/properties/ros_topic_property.h"
#include "rviz/properties/enum_property.h"
#include "rviz/properties/int_property.h"

#include "rviz/display.h"
#include "rviz/rviz_export.h"
#endif

using namespace rviz;

namespace atom_rviz
{
/** @brief Display subclass for subscribing and displaying to image messages.
*
* This class brings together some common things used for subscribing and displaying image messages in
* Display
* types. It has a tf2_ros::MessageFilter and image_tranport::SubscriberFilter to filter incoming image
* messages, and
* it handles subscribing and unsubscribing when the display is
* enabled or disabled. */

class RVIZ_EXPORT ImageDisplayWithClickBase : public Display
{
Q_OBJECT
public:
/** @brief Constructor. */
ImageDisplayWithClickBase();
~ImageDisplayWithClickBase() override;

void setTopic(const QString& topic, const QString& datatype) override;

protected Q_SLOTS:
/** @brief Update topic and resubscribe */
virtual void updateTopic();

/** @brief Update queue size of tf filter */
virtual void updateQueueSize();

/** @brief Fill list of available and working transport options */
void fillTransportOptionList(EnumProperty* property);

protected:
void onInitialize() override;

/** @brief Reset display. */
void reset() override;

/** @brief Enabling TF filtering by defining a target frame. */
void enableTFFilter(std::string& targetFrame)
{
targetFrame_ = targetFrame;
reset();
}

/** @brief ROS topic management. */
virtual void subscribe();
virtual void unsubscribe();

void fixedFrameChanged() override;

/** @brief Incoming message callback. Checks if the message pointer
* is valid, increments messages_received_, then calls
* processMessage(). */
void incomingMessage(const sensor_msgs::Image::ConstPtr& msg);

/** @brief Callback for messages, whose frame_id cannot resolved */
void failedMessage(const sensor_msgs::Image::ConstPtr& msg, tf2_ros::FilterFailureReason reason);

/** @brief Implement this to process the contents of a message.
*
* This is called by incomingMessage(). */
virtual void processMessage(const sensor_msgs::Image::ConstPtr& msg) = 0;

void scanForTransportSubscriberPlugins();

boost::scoped_ptr<image_transport::ImageTransport> it_;
boost::shared_ptr<image_transport::SubscriberFilter> sub_;
boost::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::Image> > tf_filter_;

std::string targetFrame_;

uint32_t messages_received_;

RosTopicProperty* topic_property_;
EnumProperty* transport_property_;
IntProperty* queue_size_property_;

std::string transport_;

std::set<std::string> transport_plugin_types_;

BoolProperty* unreliable_property_;
};

} // end namespace rviz

#endif // IMAGE_DISPLAY_BASE_H
4 changes: 3 additions & 1 deletion atom_rviz_plugins/image_display_with_click/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@

<depend>class_loader</depend>
<depend>pluginlib</depend>
<depend>rviz</depend>
<!-- <depend>rviz</depend>-->
<depend>qtbase5-dev</depend>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>atom_msgs</build_depend>
Expand All @@ -67,6 +67,8 @@
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>

<build_depend>rviz</build_depend>
<exec_depend>rviz</exec_depend>
<export>
<rviz plugin="${prefix}/plugin_description.xml"/>
</export>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ using namespace rviz;

namespace atom_rviz
{
ImageDisplayWithClick::ImageDisplayWithClick() : ImageDisplayBase(), texture_()
ImageDisplayWithClick::ImageDisplayWithClick() : ImageDisplayWithClickBase(), texture_()
{
cout << "Called ImageDisplay::ImageDisplay()" << endl;
normalize_property_ = new BoolProperty(
Expand Down Expand Up @@ -56,9 +56,12 @@ namespace atom_rviz
{

cout << "Called ImageDisplay::onInitialize()" << endl;
ImageDisplayBase::onInitialize();
ImageDisplayWithClickBase::onInitialize();
{
static uint32_t count = 0;
static uint32_t count = 10000; //NOTE this must start with a different number than 0, otherwise it will
// collide with the scene managers created by ImageDisplay
// https://github.com/lardemua/atom/issues/378#issuecomment-1091711581

std::stringstream ss;
ss << "ImageDisplay" << count++;
img_scene_manager_ = Ogre::Root::getSingleton().createSceneManager(Ogre::ST_GENERIC, ss.str());
Expand Down Expand Up @@ -136,7 +139,7 @@ namespace atom_rviz
void ImageDisplayWithClick::onDisable()
{
render_panel_->getRenderWindow()->setActive(false);
ImageDisplayBase::unsubscribe();
ImageDisplayWithClickBase::unsubscribe();
reset();
}

Expand Down Expand Up @@ -210,7 +213,7 @@ namespace atom_rviz

void ImageDisplayWithClick::reset()
{
ImageDisplayBase::reset();
ImageDisplayWithClickBase::reset();
texture_.clear();
render_panel_->getCamera()->setPosition(Ogre::Vector3(999999, 999999, 999999));
}
Expand Down
Loading

0 comments on commit 8afb566

Please sign in to comment.