Template Class DiagnosedPublisher
Defined in File diagnosed_pub_sub.hpp
Inheritance Relationships
Base Type
public cras::DiagnosedPubSub< Message >(Template Class DiagnosedPubSub)
Class Documentation
-
template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
class DiagnosedPublisher : public cras::DiagnosedPubSub<Message> Wrapper for ROS publisher that automatically diagnoses the rate and delay of published messages.
Note
For the automatic diagnostics to work, you have to call the
publish()method from this class, not the one from the ROS publisher.- Template Parameters:
Message – Type of the published message.
Enable – SFINAE only. Do not set explicitly.
Public Functions
Add the given diagnostic task to the publisher.
- Parameters:
pub – [in] The ROS publisher.
diag – [in] The topic diagnostics task.
-
DiagnosedPublisher(const ::ros::Publisher &pub, const ::std::string &name, const ::cras::TopicStatusParam<Message> &diagParams)
Add a topic diagnostic task to the publisher.
- Parameters:
pub – [in] The ROS publisher.
name – [in] Name of the diagnostic task
diagParams – [in] Parameters of the topic diagnostics task.
-
DiagnosedPublisher(const ::ros::Publisher &pub, const ::cras::BoundParamHelperPtr ¶ms, const ::cras::SimpleTopicStatusParam<Message> &defaultParams)
Add a topic diagnostic task to the publisher.
See also
- Parameters:
pub – [in] The ROS publisher.
params – [in] ROS parameters from which the configuration of the diagnostic task is taken.
defaultParams – [in] Default parameters used when no ROS parameter exists.
-
DiagnosedPublisher(const ::ros::Publisher &pub, const ::cras::BoundParamHelperPtr ¶ms)
Add a topic diagnostic task to the publisher.
See also
- Parameters:
pub – [in] The ROS publisher.
params – [in] ROS parameters from which the configuration of the diagnostic task is taken.
-
DiagnosedPublisher(const ::ros::Publisher &pub, ::diagnostic_updater::Updater &updater, const ::cras::BoundParamHelperPtr ¶ms)
-
DiagnosedPublisher(const ::ros::Publisher &pub, ::diagnostic_updater::Updater &updater, const ::cras::BoundParamHelperPtr ¶ms, const ::ros::Rate &defaultRate)
-
DiagnosedPublisher(const ::ros::Publisher &pub, ::diagnostic_updater::Updater &updater, const ::cras::BoundParamHelperPtr ¶ms, const ::ros::Rate &defaultRate, const ::ros::Rate &defaultMinRate, const ::ros::Rate &defaultMaxRate)
-
::ros::Rate getDesiredRate() const
-
virtual void publish(const typename Message::Ptr &message)
Publish a message.
- Parameters:
message – [in] The message to publish.
-
virtual void publish(const Message &message)
Publish a message.
- Parameters:
message – [in] The message to publish.
-
const ::ros::Publisher &getPublisher() const
Get the ROS publisher.
- Returns:
The ROS publisher.
-
::ros::Publisher &getPublisher()
Get the ROS publisher.
- Returns:
The ROS publisher.
-
void setPublisher(const ::ros::Publisher &pub)
Change the ROS publisher.
- Parameters:
pub – [in] The new ROS publisher.
Protected Attributes
-
::ros::Publisher publisher
The ROS publisher.