Skip to content

Commit 2dbce10

Browse files
authored
Change EffortDisplay superclass from MessageFilterDisplay to RosTopicDisplay to avoid dropping messages with empty frame_id. (#1312)
Problem: EffortDisplay does not react on JointState messages with emty frame_id. Also the following warning is displayed: [rviz2]: Message Filter dropping message: frame '' at time ..... for reason 'the frame id of the message is empty' Reason: MessageFilterDisplay uses tf2_ros::MessageFilter which checks that frame_id is not empty. This mechanism is designed to perform message frame change "on-fly" but it is nao applicable to JointState messages. Solution: Use RosTopicDisplay instead of MessageFilterDisplay. Use type erased signal/slot pair to ensure messages are processed in the main thread.
1 parent 9f1f447 commit 2dbce10

File tree

2 files changed

+20
-7
lines changed

2 files changed

+20
-7
lines changed

rviz_default_plugins/include/rviz_default_plugins/displays/effort/effort_display.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838
#include <string>
3939

4040
#include <rclcpp/rclcpp.hpp>
41-
#include <rviz_common/message_filter_display.hpp>
41+
#include <rviz_common/ros_topic_display.hpp>
4242
#include <rviz_common/properties/bool_property.hpp>
4343
#include <rviz_common/properties/int_property.hpp>
4444
#include <rviz_common/properties/float_property.hpp>
@@ -90,7 +90,7 @@ public Q_SLOTS:
9090
};
9191

9292
class RVIZ_DEFAULT_PLUGINS_PUBLIC EffortDisplay
93-
: public rviz_common::MessageFilterDisplay<sensor_msgs::msg::JointState>
93+
: public rviz_common::RosTopicDisplay<sensor_msgs::msg::JointState>
9494
{
9595
Q_OBJECT
9696

@@ -122,6 +122,7 @@ private Q_SLOTS:
122122
void onEnable() override;
123123
void onDisable() override;
124124
void processMessage(sensor_msgs::msg::JointState::ConstSharedPtr msg) override;
125+
void processTypeErasedMessage(std::shared_ptr<const void> type_erased_msg) override;
125126

126127
void load();
127128
void clear();

rviz_default_plugins/src/rviz_default_plugins/displays/effort/effort_display.cpp

Lines changed: 17 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -112,7 +112,7 @@ bool JointInfo::getEnabled() const
112112
}
113113

114114
EffortDisplay::EffortDisplay()
115-
: rviz_common::MessageFilterDisplay<sensor_msgs::msg::JointState>()
115+
: rviz_common::RosTopicDisplay<sensor_msgs::msg::JointState>()
116116
{
117117
alpha_property_ = new rviz_common::properties::FloatProperty(
118118
"Alpha", 1.0f, "0 is fully transparent, 1.0 is fully opaque.",
@@ -155,7 +155,7 @@ EffortDisplay::~EffortDisplay()
155155

156156
void EffortDisplay::onInitialize()
157157
{
158-
MFDClass::onInitialize();
158+
RTDClass::onInitialize();
159159
updateHistoryLength();
160160
}
161161

@@ -170,7 +170,7 @@ void EffortDisplay::updateHistoryLength()
170170
// Clear the visuals by deleting their objects.
171171
void EffortDisplay::reset()
172172
{
173-
MFDClass::reset();
173+
RTDClass::reset();
174174
visuals_.clear();
175175
}
176176

@@ -288,11 +288,23 @@ std::string concat(const std::string & prefix, const std::string & frame)
288288

289289
void EffortDisplay::processMessage(sensor_msgs::msg::JointState::ConstSharedPtr msg)
290290
{
291+
if (!msg) {
292+
return;
293+
}
294+
295+
// Use type erased signal/slot machinery to ensure messages are
296+
// processed in the main thread.
297+
Q_EMIT typeErasedMessageTaken(std::static_pointer_cast<const void>(msg));
298+
}
299+
300+
void EffortDisplay::processTypeErasedMessage(std::shared_ptr<const void> type_erased_msg)
301+
{
302+
auto msg = std::static_pointer_cast<const sensor_msgs::msg::JointState>(type_erased_msg);
303+
291304
// Robot model might not be loaded yet
292305
if (!robot_model_) {
293306
setStatus(
294-
rviz_common::properties::StatusLevel::Error,
295-
"Process message",
307+
rviz_common::properties::StatusLevel::Error, "Topic",
296308
QString("Robot model might not be loaded yet"));
297309
return;
298310
}

0 commit comments

Comments
 (0)