ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

This is roughly what it looks like to adapt the roscpp talker to use a diagnosed updater and diagnosed publisher.

I haven't tested that this compiles, but it should be pretty close.

#include <ros/ros.h>
#include <std_msgs/String.h>

#include <diagnostic_updater/diagnostic_updater.h>
#include <diagnostic_updater/publisher.h>

#include <sstream>

int main(int argc, char **argv)
{
  ros::init(argc, argv, "talker");

  ros::NodeHandle n;

  // The Updater class advertises to /diagnostics, and has a
  // ~diagnostic_period parameter that says how often the diagnostics
  // should be published.
  diagnostic_updater::Updater updater;

  double desired_freq = 10.0; // desired publish frequency
  double min_freq = 9.0; // minimum frequency before error
  double max_freq = 11.0; // maximum frequency before error
  double freq_tolerance = 0.1; // Tolerance before stating error on publish frequency, fractional percent of desired frequencies.
  int window_size = 100; // Number of samples to consider in frequency
  double min_acceptable = 0.05; // The minimum publishing delay (in seconds) before publish times.
  double max_acceptable = 0.15; // Maximum delay between message publish times
  diagnostic_updater::DiagnosedPublisher<std_msgs::String> chatter_pub(n.advertise<std_msgs::String>("chatter", 1000),
               updater,
               diagnostic_updater::FrequencyStatusParam(&min_freq_, &max_freq_, freq_tolerance, window_size),
               diagnostic_updater::TimeStampStatusParam(min_acceptable, max_acceptable)));

  ros::Rate loop_rate(desired_freq);

  int count = 0;
  while (ros::ok())
  {
    std_msgs::String msg;

    std::stringstream ss;
    ss << "hello world " << count;
    msg.data = ss.str();

    ROS_INFO("%s", msg.data.c_str());

    chatter_pub.publish(msg);

    ros::spinOnce();

    loop_rate.sleep();
    ++count;
  }
  return 0;
}

The CMakeLists.txt to build this node in the beginner_tutorials package should be:

cmake_minimum_required(VERSION 2.8.3)
project(beginner_tutorials)

## Find catkin and any catkin packages
find_package(catkin REQUIRED COMPONENTS roscpp diagnostic_updater std_msgs)

## Declare a catkin package
catkin_package()

add_executable(talker src/talker.cpp)
target_link_libraries(talker ${catkin_LIBRARIES})