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

How to get message type in rospy?

asked 2013-04-09 01:26:05 -0500

liborw gravatar image

updated 2017-11-04 11:29:27 -0500

Ed Venator gravatar image

I want to write a library that works with multiple message types, is there a way how to get the type of the message and it's fields?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2013-04-09 01:30:30 -0500

dornhege gravatar image

There should be defines in the message for _type and the python __slots__ are defined for the fields.

edit flag offensive delete link more
1

answered 2017-10-16 05:37:51 -0500

RDaneelOlivaw gravatar image

updated 2017-10-17 07:19:14 -0500

Here I want to add an example of use of this _typeaccess. For various reasons:

1) I'm giving here a complete example on how to use this _type access, not only an indication of how its done, which I find more enriching for anyone that want to use this.

2) Although this example is trivial, I've come across a lot of poeple trying to use a unique callback for multiple subscribers, and this _typevariable is perfect for this application. It opens the possiblity of using callback another way.

The cleanest way is to use: msg._type

Here I leave an example of two susbcribers in ros using the same callback. The callback called common_callback will process the messages differently depending on their type. In this case it processes type LaserScan or Odometry, but this can be used for anything really because the output of the msg._type is sensor_msgs/LaserScanor nav_msgs/Odometry. So its easy too work with that.

I'll leave a video with a full blown example of how to use this: Video Example

Here que have the python code:

#! /usr/bin/env python

import rospy
from std_msgs.msg import Int32
from sensor_msgs.msg import LaserScan
from nav_msgs.msg import Odometry
from geometry_msgs.msg import Point

"""
user:~$ rosmsg show sensor_msgs/LaserScan
std_msgs/Header header
  uint32 seq
  time stamp
  string frame_id
float32 angle_min
float32 angle_max
float32 angle_increment
float32 time_increment
float32 scan_time
float32 range_min
float32 range_max
float32[] ranges
float32[] intensities
"""
"""
user:~$ rosmsg show nav_msgs/Odometry
std_msgs/Header header
  uint32 seq
  time stamp
  string frame_id
string child_frame_id
geometry_msgs/PoseWithCovariance pose
  geometry_msgs/Pose pose
    geometry_msgs/Point position
      float64 x
      float64 y
      float64 z
    geometry_msgs/Quaternion orientation
      float64 x
      float64 y
      float64 z
      float64 w
  float64[36] covariance
geometry_msgs/TwistWithCovariance twist
  geometry_msgs/Twist twist
    geometry_msgs/Vector3 linear
      float64 x
      float64 y
      float64 z
    geometry_msgs/Vector3 angular
      float64 x
      float64 y
      float64 z
  float64[36] covariance
"""

class MultipleSubs(object):
    def __init__(self):

        self.laser_center_distance = 100.0
        self.kobuki_position = Point()

        sub_laserscan = rospy.Subscriber('/kobuki/laser/scan', LaserScan, self.common_callback)
        sub_odom = rospy.Subscriber('/odom', Odometry, self.common_callback)

    def common_callback(self,msg):

        input_message_type = str(msg._type)

        rospy.logdebug("msg._type ==>"+input_message_type)
        #rospy.loginfo("type(msg)"+str(type(msg)))

        if input_message_type == "sensor_msgs/LaserScan":
            rospy.loginfo("sub_laserscan called me, with type msg==>"+input_message_type)

            self.laser_center_distance = msg.ranges[len(msg.ranges)/2]

        if input_message_type == "nav_msgs/Odometry":
            rospy.loginfo("sub_odom called me, with type msg==>"+input_message_type)

            self.kobuki_position = msg.pose.pose.position

if __name__ == "__main__":
    #rospy.init_node('topic_publisher', log_level=rospy.DEBUG)
    #rospy.init_node('topic_publisher', log_level=rospy.INFO)
    rospy.init_node('topic_publisher', log_level=rospy.WARN)

    multiple_subs_object = MultipleSubs()
    rate = rospy.Rate(2)

    while not rospy.is_shutdown(): 
      rospy.logwarn("Kobuki Center Laser Distance Reading==>"+str(multiple_subs_object.laser_center_distance))
      rospy.logwarn("Kobuki Odometry Position Reading==>"+str(multiple_subs_object.kobuki_position))
      rate.sleep()

Hope this helps ;).

edit flag offensive delete link more

Comments

1

So to make posting an answer to an already answered, 4 years (!) old question that had the original answer also accepted worth it: can you include some words on why you would ever want to do this? Because it looks like the if: .. else: .. essentially just replaces the two callbacks. Callbacks ..

gvdhoorn gravatar image gvdhoorn  ( 2017-10-16 05:54:54 -0500 )edit
1

.. aren't expensive, and for any real world application would seem to make a setup like this much more readible (one level of conditionals less, one level of indentation less, etc).

gvdhoorn gravatar image gvdhoorn  ( 2017-10-16 05:55:57 -0500 )edit

I've edited the answer with a tinny explanation on why I decided to complement the answer. Basically I myself preffer having answers with example code and also giving alternative programming options although I myself use multiple callbacks instead of this unique calback option.

RDaneelOlivaw gravatar image RDaneelOlivaw  ( 2017-10-17 07:18:29 -0500 )edit
1

Thanks for replying, really appreciated.

I've come across a lot of poeple trying to use a unique callback for multiple subscribers, and this _type variable is perfect for this application.

I don't really understand this: why is this 'perfect for this application'? Are you thinking of a case ..

gvdhoorn gravatar image gvdhoorn  ( 2017-10-17 08:33:04 -0500 )edit
1

.. where there are multiple subscriptions to different topics, or to the same topic? If the former, the topics are different, so are the types, which leads to checking _type, but that is not a rationale. If the latter, the types would be the same, so how does checking msg._type help then?

gvdhoorn gravatar image gvdhoorn  ( 2017-10-17 08:34:29 -0500 )edit

Its the case of people that want to use the SAME callback for multiple topic susbcribers. Why do they want that? Some people said that they find it more compact , others simply want to see if its possible, others just try it because it helps them understand better Topics.

RDaneelOlivaw gravatar image RDaneelOlivaw  ( 2017-10-17 10:10:33 -0500 )edit

I personally would tend to do it in different callback but I really find it interesting from the learning point of view to experiment different options. It gives you a broader understanding.

RDaneelOlivaw gravatar image RDaneelOlivaw  ( 2017-10-17 10:12:29 -0500 )edit

I understand that this example is for teaching purposes, but I would highly recommend against using one callback function for multiple data types. Using multiple callbacks is much more readable and (to me) is much more "intuitive."

jayess gravatar image jayess  ( 2018-01-03 23:19:06 -0500 )edit

Question Tools

Stats

Asked: 2013-04-09 01:26:05 -0500

Seen: 8,585 times

Last updated: Nov 04 '17