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

How to subscribe to a topic whom type is gazebo_msg/ContactState

asked 2016-09-24 07:22:23 -0500

Masoud gravatar image

updated 2016-09-25 04:24:57 -0500

Hi everybody

I'm trying to write a subscriber following this tutorial) to listen to a topic which is published by a contact sensor (libgazebo_ros_bumper.so). Here is the structure of this topic shown in "topic monitor":

image description

Assuming that we want to write the size of ContactState message published by this topic, I wrote this program and compiled it (using catkin_make command) successfully:

#include "ros/ros.h"
#include "std_msgs/String.h"
#include "gazebo_msgs/ContactState.h"
#include <sstream>

void chatterCallback(const gazebo_msgs::ContactState cs)
{
  int a;
  a = sizeof(cs);
  std::stringstream ss;
  ss << a;
  ROS_INFO("The size of recieved ContactState message is: %d", a);
}

int main(int argc, char **argv)
{

  ros::init(argc, argv, "listener");
  ros::NodeHandle n;
  ros::Subscriber sub = n.subscribe("contact_sensor_state", 1000, chatterCallback);
  ros::spin();

  return 0;
}

However, Nothing happen whenever I run this subscriber node using rosrun command. It seems that ROS never call chatterCallback function. How should I edit ros::Subscriber sub = n.subscribe("contact_sensor_state", 1000, chatterCallback); to fix this issue?

I also have 2 more simple question regarding the above question:

1) How can I store the valued published by "contact_sensor_state/states/[0]/total_wrench/force/z" in a double variable in my program? (Shay answered this question)

2) Is it possible to advertise a variable in my program? I mean is it possible for a node to be both a subscriber and publisher. If yes, how should I edit the code to do this? (Shay answered this question)

I'm using ROS indigo, gazebo 2.2 and ubuntu 14.04.

Thanks

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
2

answered 2016-09-24 08:00:31 -0500

Shay gravatar image

updated 2016-09-24 08:14:31 -0500

The message variable should be a reference variable. You can refer to the code below.

#include "ros/ros.h"
#include "std_msgs/String.h"
#include "gazebo_msgs/ContactState.h"
#include <sstream>

void chatterCallback(const gazebo_msgs::ContactStateConstPtr& cs)
{
  int a;
  a = sizeof(cs);
  std::stringstream ss;
  ss << a;
  ROS_INFO("The size of recieved ContactState message is: %d", a);

  double z = cs->states[0].total_wrench.force.z; //here is for you question 1).
}

int main(int argc, char **argv)
{

  ros::init(argc, argv, "listener");
  ros::NodeHandle n;
  ros::Subscriber sub = n.subscribe("contact_sensor_state", 1000, chatterCallback);

  ros::Publisher pub = n.advertise<std_msgs::String>("mymsg",1000); //here is for you question 2).
  std_msgs::String msg = "Hello"; //here is for you question 2).

  ros::Rate loop_rate(10);

  while (ros::ok())
  {
      pub.publish(msg); //here is for you question 2).

      ros::spinOnce();
      loop_rate.sleep();
  }
  return 0;
}
edit flag offensive delete link more
0

answered 2016-09-25 01:03:48 -0500

Masoud gravatar image

Dear Shay and other ROS users,

Thanks for your attention. I replaced my code with the one that you provide and tried to compile it, but I got some error during compiling which made me to comment and edit some lines. Now, the final code that has been compiled successfully is as follow:

#include "ros/ros.h"
#include "std_msgs/String.h"
#include "gazebo_msgs/ContactState.h"
#include <sstream>

void chatterCallback(const gazebo_msgs::ContactState::ConstPtr& cs) // this line has been edited by adding "::" between ContactState and ConstPtr&
{
  int a;
  a = sizeof(cs);
  std::stringstream ss;
  ss << a;
  ROS_INFO("The size of recieved ContactState message is: %d", a);

  // double z = cs->states[0].total_wrench.force.z; // this line has been commented due to this error : ‘const struct gazebo_msgs::ContactState_<std::allocator<void> >’ has no member named ‘states’
}

int main(int argc, char **argv)
{

  ros::init(argc, argv, "listener");
  ros::NodeHandle n;
  ros::Subscriber sub = n.subscribe("contact_sensor_state", 1000, chatterCallback);

  ros::Publisher pub = n.advertise<std_msgs::String>("mymsg",1000); //here is for you question 2).
  std_msgs::String msg;
  msg.data = "Hello"; // this line has been edited due to this error: conversion from ‘const char [6]’ to non-scalar type ‘std_msgs::String’ requested

  ros::Rate loop_rate(10);

  while (ros::ok())
  {
      pub.publish(msg);

      ros::spinOnce();
      loop_rate.sleep();
  }
  return 0;
}

After executing this new code using rosrun, I realized that my main problem remains unsolved. I mean ROS don't call chatterCallback function as new messages published by "contact_sensor_state" :(

Does anybody knows what is the problem here? Isn't it better to specify type of topic in addition of it's name at ros::Subscriber sub = n.subscribe("contact_sensor_state", 1000, chatterCallback);. How should I edit this line to specify type of topic??

Hope for your help

edit flag offensive delete link more

Comments

The subscribe() can only specify topic name, buffer length and callback function. I don't know why the chatterCallback didn't be called.

Shay gravatar image Shay  ( 2016-09-25 02:16:34 -0500 )edit

Thank you shay... I tried subscribing to JointState (sensor_msg/JointState) topic by a similar code and it works well.. I don't know whats is the problem of ContactStates topic. Can I listen to the children's of ContactState topic (for example listening to "contact_sensor_state/states")?

Masoud gravatar image Masoud  ( 2016-09-25 02:50:10 -0500 )edit

Finally, I figured out what was the source of the problem. There was a mistype error in type of the message as well as the title of this question. I've dropped the letter "s" from "ContactsState" in my code...

I want to thank you Shay for your participation and good answers.

Masoud gravatar image Masoud  ( 2016-09-25 04:14:14 -0500 )edit

@_@..... yeah, I'm glad you solve it.

Shay gravatar image Shay  ( 2016-09-25 06:04:16 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-09-24 07:22:23 -0500

Seen: 2,466 times

Last updated: Sep 25 '16