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

How to use diagnostic_updater for talker node? [closed]

asked 2017-11-03 09:24:55 -0500

SumitP gravatar image

updated 2017-11-10 09:22:23 -0500

I want to know the status of talker node. For example frequency at which talker node is publishing the data, size of the published data.

Using diagnostic tools like diagnostic updater, diagnostic aggregator.

Please help me to solve this problem.

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by SumitP
close date 2017-11-10 09:22:47.785492

2 Answers

Sort by » oldest newest most voted
2

answered 2017-11-06 16:58:54 -0500

ahendrix gravatar image

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})
edit flag offensive delete link more

Comments

That's great. Thank you.

SumitP gravatar image SumitP  ( 2017-11-07 01:42:34 -0500 )edit

After compiling the talker node, there are errors in diagnostic_updater/include/diagnostic_updater/publisher.h

error: ‘const struct std_msgs::String_<std::allocator<void> >’ has no member named ‘header’ virtual void publish(const T& message) { tick(message.header.stamp);

SumitP gravatar image SumitP  ( 2017-11-07 02:21:48 -0500 )edit

error: ‘struct std_msgs::String_<std::allocator<void> >’ has no member named ‘header’ tick(message->header.stamp); publisher_.publish(message); }

Please can you check with this error.

SumitP gravatar image SumitP  ( 2017-11-07 02:22:25 -0500 )edit

Ah; the DiagnosedPublisher requires a message type with a header.

ahendrix gravatar image ahendrix  ( 2017-11-07 22:38:58 -0500 )edit

I have changed it but I got one more error including previous errors.

error: no matching function for call to ‘diagnostic_updater::DiagnosedPublisher<std_msgs::header_<std::allocator<void> > >::publish(std_msgs::String&)’ chatter_pub.publish(message);

SumitP gravatar image SumitP  ( 2017-11-08 04:19:09 -0500 )edit

I found the solution. Thank for your support.

SumitP gravatar image SumitP  ( 2017-11-10 09:21:02 -0500 )edit

Is there any chance you could edit the answer or publish the working code in your question? Looks like it would be pretty handy

TheMilkman gravatar image TheMilkman  ( 2018-09-18 02:19:43 -0500 )edit
0

answered 2017-11-06 09:58:35 -0500

jayess gravatar image

You can get a lot of information about topics using rostopic. For example:

Frequency:

rostopic hz /topic

Bandwidth:

rostopic bw /topic

Please check out the wiki entry to see all of the details of what's possible.

edit flag offensive delete link more

Comments

Okay, But is it possible with diagnostic tools? I want to use with diagnostics like diagnostic aggregator or diagnostic updater.

SumitP gravatar image SumitP  ( 2017-11-06 10:09:06 -0500 )edit

Ah sorry. I didn't notice that part of the title of your question. You probably want to tag your question with that (not just diagnostics) and specifically mention it in your question too. It's pretty easy to miss that detail when it's only in the title.

jayess gravatar image jayess  ( 2017-11-06 10:13:01 -0500 )edit

Okay, Sorry for that. So, is there a solution for question?

SumitP gravatar image SumitP  ( 2017-11-06 10:33:40 -0500 )edit

Not sure, I've never used those packages.

jayess gravatar image jayess  ( 2017-11-06 10:38:15 -0500 )edit

Okay, Thank you.

SumitP gravatar image SumitP  ( 2017-11-07 02:23:47 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2017-11-03 09:24:55 -0500

Seen: 1,335 times

Last updated: Nov 10 '17