1 #ifndef EFFORT_DISPLAY_H 2 #define EFFORT_DISPLAY_H 5 #include <boost/circular_buffer.hpp> 8 #include <sensor_msgs/JointState.h> 21 class CategoryProperty;
23 class RosTopicProperty;
35 #ifdef TF_MESSAGEFILTER_DEBUG 36 # undef TF_MESSAGEFILTER_DEBUG 38 #define TF_MESSAGEFILTER_DEBUG(fmt, ...) \ 39 ROS_DEBUG_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__) 41 #ifdef TF_MESSAGEFILTER_WARN 42 # undef TF_MESSAGEFILTER_WARN 44 #define TF_MESSAGEFILTER_WARN(fmt, ...) \ 45 ROS_WARN_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__) 49 typedef sensor_msgs::JointState
M;
53 typedef boost::function<void(const MConstPtr&, FilterFailureReason)>
FailureCallback;
54 #ifdef RVIZ_USE_BOOST_SIGNAL_1 55 typedef boost::signal<void(const MConstPtr&, FilterFailureReason)>
FailureSignal;
57 typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)>
FailureSignal;
77 , queue_size_(queue_size)
81 setTargetFrame(target_frame);
99 , queue_size_(queue_size)
104 setTargetFrame(target_frame);
115 message_connection_.disconnect();
116 message_connection_ = f.registerCallback(&MessageFilterJointState::incomingMessage,
this);
124 message_connection_.disconnect();
125 tf_.removeTransformsChangedListener(tf_connection_);
129 TF_MESSAGEFILTER_DEBUG(
"Successful Transforms: %llu, Failed Transforms: %llu, Discarded due to age: %llu, Transform messages received: %llu, Messages received: %llu, Total dropped: %llu",
130 (
long long unsigned int)successful_transform_count_, (
long long unsigned int)failed_transform_count_,
131 (
long long unsigned int)failed_out_the_back_count_, (
long long unsigned int)transform_message_count_,
132 (
long long unsigned int)incoming_message_count_, (
long long unsigned int)dropped_message_count_);
141 std::vector<std::string> frames;
142 frames.push_back(target_frame);
143 setTargetFrames(frames);
151 boost::mutex::scoped_lock list_lock(messages_mutex_);
152 boost::mutex::scoped_lock string_lock(target_frames_string_mutex_);
154 target_frames_ = target_frames;
156 std::stringstream ss;
157 for (std::vector<std::string>::iterator it = target_frames_.begin(); it != target_frames_.end(); ++it)
162 target_frames_string_ = ss.str();
169 boost::mutex::scoped_lock lock(target_frames_string_mutex_);
170 return target_frames_string_;
178 time_tolerance_ = tolerance;
186 boost::mutex::scoped_lock lock(messages_mutex_);
193 warned_about_unresolved_name_ =
false;
194 warned_about_empty_frame_id_ =
false;
197 void add(
const MEvent& evt)
199 boost::mutex::scoped_lock lock(messages_mutex_);
203 if (!testMessage(evt))
206 if (queue_size_ != 0 && message_count_ + 1 > queue_size_)
208 ++dropped_message_count_;
209 const MEvent& front = messages_.front();
210 TF_MESSAGEFILTER_DEBUG(
"Removed oldest message because buffer is full, count now %d (frame_id=%s, stamp=%f)", message_count_, front.
getMessage()->header.frame_id.c_str(), front.
getMessage()->header.stamp.toSec());
211 signalFailure(messages_.front(), filter_failure_reasons::Unknown);
213 messages_.pop_front();
218 messages_.push_back(evt);
224 ++incoming_message_count_;
232 void add(
const MConstPtr& message)
235 (*header)[
"callerid"] =
"unknown";
245 boost::mutex::scoped_lock lock(failure_signal_mutex_);
246 return message_filters::Connection(boost::bind(&MessageFilterJointState::disconnectFailure,
this, _1), failure_signal_.connect(callback));
251 queue_size_ = new_queue_size;
264 new_transforms_ =
false;
265 successful_transform_count_ = 0;
266 failed_transform_count_ = 0;
267 failed_out_the_back_count_ = 0;
268 transform_message_count_ = 0;
269 incoming_message_count_ = 0;
270 dropped_message_count_ = 0;
272 warned_about_unresolved_name_ =
false;
273 warned_about_empty_frame_id_ =
false;
275 tf_connection_ = tf_.addTransformsChangedListener(boost::bind(&MessageFilterJointState::transformsChanged,
this));
277 max_rate_timer_ = nh_.createTimer(max_rate_, &MessageFilterJointState::maxRateTimerCallback,
this);
290 if (frame_id.empty()) frame_id = * (target_frames_.begin());
292 if (frame_id.empty())
294 if (!warned_about_empty_frame_id_)
296 warned_about_empty_frame_id_ =
true;
297 TF_MESSAGEFILTER_WARN(
"Discarding message from [%s] due to empty frame_id. This message will only print once.", callerid.c_str());
299 signalFailure(evt, filter_failure_reasons::EmptyFrameID);
303 if (frame_id[0] !=
'/')
305 std::string unresolved = frame_id;
306 frame_id =
tf::resolve(tf_.getTFPrefix(), frame_id);
308 if (!warned_about_unresolved_name_)
310 warned_about_unresolved_name_ =
true;
311 ROS_WARN(
"Message from [%s] has a non-fully-qualified frame_id [%s]. Resolved locally to [%s]. This is will likely not work in multi-robot systems. This message will only print once.", callerid.c_str(), unresolved.c_str(), frame_id.c_str());
317 for (std::vector<std::string>::iterator target_it = target_frames_.begin(); target_it != target_frames_.end(); ++target_it)
319 const std::string& target_frame = *target_it;
321 if (target_frame != frame_id && stamp !=
ros::Time(0))
325 tf_.getLatestCommonTime(frame_id, target_frame, latest_transform_time, 0) ;
326 if (stamp + tf_.getCacheLength() < latest_transform_time)
328 ++failed_out_the_back_count_;
329 ++dropped_message_count_;
330 TF_MESSAGEFILTER_DEBUG(
"Discarding Message, in frame %s, Out of the back of Cache Time(stamp: %.3f + cache_length: %.3f < latest_transform_time %.3f. Message Count now: %d", message->header.frame_id.c_str(), message->header.stamp.toSec(), tf_.getCacheLength().toSec(), latest_transform_time.
toSec(), message_count_);
332 last_out_the_back_stamp_ = stamp;
333 last_out_the_back_frame_ = frame_id;
335 signalFailure(evt, filter_failure_reasons::OutTheBack);
342 bool ready = !target_frames_.empty();
343 for (std::vector<std::string>::iterator target_it = target_frames_.begin(); ready && target_it != target_frames_.end(); ++target_it)
345 std::string& target_frame = *target_it;
348 ready = ready && (tf_.canTransform(target_frame, frame_id, stamp) &&
349 tf_.canTransform(target_frame, frame_id, stamp + time_tolerance_) );
353 ready = ready && tf_.canTransform(target_frame, frame_id, stamp);
361 ++successful_transform_count_;
367 ++failed_transform_count_;
375 if (!messages_.empty() && getTargetFramesString() ==
" ")
377 ROS_WARN_NAMED(
"message_notifier",
"MessageFilter [target=%s]: empty target frame", getTargetFramesString().c_str());
382 L_Event::iterator it = messages_.begin();
383 for (; it != messages_.end(); ++i)
387 if (testMessage(evt))
390 it = messages_.erase(it);
401 boost::mutex::scoped_lock list_lock(messages_mutex_);
405 new_transforms_ =
false;
421 new_transforms_ =
true;
423 ++transform_message_count_;
428 if (next_failure_warning_.isZero())
435 if (incoming_message_count_ - message_count_ == 0)
440 double dropped_pct = (double)dropped_message_count_ / (
double)(incoming_message_count_ - message_count_);
441 if (dropped_pct > 0.95)
446 if ((
double)failed_out_the_back_count_ / (
double)dropped_message_count_ > 0.5)
448 TF_MESSAGEFILTER_WARN(
" The majority of dropped messages were due to messages growing older than the TF cache time. The last message's timestamp was: %f, and the last frame_id was: %s", last_out_the_back_stamp_.toSec(), last_out_the_back_frame_.c_str());
456 boost::mutex::scoped_lock lock(failure_signal_mutex_);
462 boost::mutex::scoped_lock lock(failure_signal_mutex_);
499 #ifdef RVIZ_USE_BOOST_SIGNAL_1 500 boost::signals::connection tf_connection_;
538 , messages_received_( 0 )
540 QString message_type = QString::fromStdString( ros::message_traits::datatype<sensor_msgs::JointState>() );
541 topic_property_->setMessageType( message_type );
542 topic_property_->setDescription( message_type +
" topic to subscribe to." );
548 fixed_frame_.toStdString(), 10, update_nh_ );
551 tf_filter_->registerCallback( boost::bind( &MessageFilterJointStateDisplay::incomingMessage,
this, _1 ));
552 context_->getFrameManager()->registerFilterForTransformStatusCheck( tf_filter_,
this );
565 messages_received_ = 0;
574 context_->queueRender();
586 sub_.subscribe( update_nh_, topic_property_->getTopicStd(), 10 );
587 setStatus( StatusProperty::Ok,
"Topic",
"OK" );
591 setStatus( StatusProperty::Error,
"Topic", QString(
"Error subscribing: " ) + e.what() );
613 tf_filter_->setTargetFrame( fixed_frame_.toStdString() );
627 ++messages_received_;
628 setStatus( StatusProperty::Ok,
"Topic", QString::number( messages_received_ ) +
" messages received" );
630 processMessage( msg );
636 virtual void processMessage(
const sensor_msgs::JointState::ConstPtr& msg ) = 0;
652 void setEffort(
double e);
654 void setMaxEffort(
double m);
655 double getMaxEffort();
656 bool getEnabled()
const;
661 void updateVisibility();
687 virtual void onInitialize();
688 virtual void reset();
692 void updateColorAndAlpha();
693 void updateHistoryLength();
694 void updateRobotDescription();
696 JointInfo* getJointInfo(
const std::string& joint);
697 JointInfo* createJoint(
const std::string &joint);
701 virtual void onEnable();
702 virtual void onDisable();
715 void processMessage(
const sensor_msgs::JointState::ConstPtr& msg );
719 boost::circular_buffer<boost::shared_ptr<EffortVisual> >
visuals_;
734 #endif // EFFORT_DISPLAY_H
virtual uint32_t getQueueSize()
uint32_t message_count_
The number of messages in the list. Used because messages_.size() has linear cost.
message_filters::Subscriber< sensor_msgs::JointState > sub_
uint64_t failed_out_the_back_count_
void add(const MConstPtr &message)
Manually add a message into this filter.
rviz::BoolProperty * all_enabled_property_
std::list< MEvent > L_Event
uint64_t dropped_message_count_
rviz::IntProperty * history_length_property_
virtual void setQueueSize(uint32_t new_queue_size)
boost::shared_ptr< M const > MConstPtr
MessageFilterJointStateDisplay()
bool testMessage(const MEvent &evt)
rviz::StringProperty * robot_description_property_
#define ROS_WARN_NAMED(name,...)
tf::MessageFilterJointState * tf_filter_
message_filters::Connection message_connection_
FailureSignal failure_signal_
boost::mutex failure_signal_mutex_
Display subclass using a tf::MessageFilter, templated on the ROS message type.
virtual void onDisable()
Derived classes override this to do the actual work of disabling themselves.
rviz::Property * joints_category_
uint32_t messages_received_
Transformer & tf_
The Transformer used to determine if transformation data is available.
A single element of a property tree, with a name, value, description, and possibly children...
void setTargetFrames(const std::vector< std::string > &target_frames)
Set the frames you need to be able to transform to before getting a message callback.
virtual void onEnable()
Derived classes override this to do the actual work of enabling themselves.
void setTolerance(const ros::Duration &tolerance)
Set the required tolerance for the notifier to return true.
#define TF_MESSAGEFILTER_WARN(fmt,...)
MessageFilterJointState(Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01))
Constructor.
bool warned_about_empty_frame_id_
uint32_t queue_size_
The maximum number of messages we queue up.
std::map< std::string, JointInfo * > M_JointInfo
bool add(const actionlib::TwoIntsGoal &req, actionlib::TwoIntsResult &res)
Property specialized to enforce floating point max/min.
void clear()
Clear any messages currently in the queue.
Property specialized to provide max/min enforcement for integers.
void disconnectFailure(const message_filters::Connection &c)
boost::signals2::connection getBoostConnection() const
uint64_t failed_transform_count_
boost::signals2::signal< void(const MConstPtr &, FilterFailureReason)> FailureSignal
virtual ~MessageFilterJointStateDisplay()
boost::shared_ptr< urdf::Model > robot_model_
void connectInput(F &f)
Connect this filter's input to another filter's output. If this filter is already connected...
void incomingMessage(const sensor_msgs::JointState::ConstPtr &msg)
Incoming message callback. Checks if the message pointer is valid, increments messages_received_, then calls processMessage().
boost::function< void(const MConstPtr &, FilterFailureReason)> FailureCallback
ros::Timer max_rate_timer_
std::string resolve(const std::string &prefix, const std::string &frame_name)
ros::NodeHandle nh_
The node used to subscribe to the topic.
const std::string & getPublisherName() const
boost::mutex target_frames_string_mutex_
virtual void onInitialize()
Override this function to do subclass-specific initialization.
uint64_t successful_transform_count_
ros::Duration time_tolerance_
Provide additional tolerance on time for messages which are stamped but can have associated duration...
std::string target_frames_string_
virtual void unsubscribe()
ros::Time last_out_the_back_stamp_
#define ROS_STATIC_ASSERT(cond)
rviz::FloatProperty * width_property_
std::string getTargetFramesString()
Get the target frames as a string for debugging.
~MessageFilterJointState()
Destructor.
MessageFilterJointStateDisplay MFDClass
Convenience typedef so subclasses don't have to use the long templated class name to refer to their s...
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
Register a callback to be called when a message is about to be dropped.
virtual void reset()
Called to tell the display to clear its state.
rviz::FloatProperty * max_effort_property_
void incomingMessage(const ros::MessageEvent< M const > &evt)
Callback that happens when we receive a message on the message topic.
uint64_t transform_message_count_
bool new_messages_
Used to skip waiting on new_data_ if new messages have come in while calling back.
void setTargetFrame(const std::string &target_frame)
Set the frame you need to be able to transform to before getting a message callback.
std::vector< std::string > V_string
boost::signals2::connection tf_connection_
void signalFailure(const MEvent &evt, FilterFailureReason reason)
uint64_t incoming_message_count_
bool warned_about_unresolved_name_
#define TF_MESSAGEFILTER_DEBUG(fmt,...)
boost::circular_buffer< boost::shared_ptr< EffortVisual > > visuals_
Property specialized for string values.
Property specialized to provide getter for booleans.
sensor_msgs::JointState M
rviz::FloatProperty * effort_property_
rviz::Property * category_
std::string robot_description_
ros::Time next_failure_warning_
boost::mutex messages_mutex_
The mutex used for locking message list operations.
volatile bool new_transforms_
Used to skip waiting on new_data_ if new transforms have come in while calling back or transforming d...
virtual void updateTopic()
ros::MessageEvent< M const > MEvent
std::set< JointInfo * > S_JointInfo
MessageFilterJointState(F &f, Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01))
Constructor.
#define ROSCONSOLE_DEFAULT_NAME
std::vector< std::string > target_frames_
The frames we need to be able to transform to before a message is ready.
virtual void fixedFrameChanged()
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void add(const MEvent &evt)
std::string last_out_the_back_frame_
void maxRateTimerCallback(const ros::TimerEvent &)
boost::shared_ptr< M > getMessage() const
L_Event messages_
The message list.
Helper superclass for MessageFilterDisplay, needed because Qt's moc and c++ templates don't work nice...