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

How can we actually use Float32MultiArray to publish 2D array using Python?

asked 2019-06-12 15:30:37 -0500

dual-swordsman gravatar image

Hi,

I am frustrated trying to understand the concept of Float32MultiArray. I have been reading the documentations from Float32MultiArray API , MultiArrayLayout and MultiArrayDimesion but I still don't get how to do it.

Code examples are mostly in C++ (which makes me more confuse that I already am) and many of them conclude to just make their own message file. Some suggest to slice and combine the two arrays into one array then publish it. In the subscriber, the array will be then slice and split up accordingly. My array is a 2*4096 so it is hard for me to do that really. Note that I am a amateur programmer. Please help addressing my question regarding this message type so that the future amateur like me could learn better. My specifications is ROS Indigo, Python 2.7.6 and Ubuntu 14.04. Yeah my tools are old.

My list of questions are as follows:

1) How do we publish and subscribe a Float32MultiArray (or any kind of MultiArray) in Python? What is the standard procedure or steps? From what I have read, I don't understand what is stride from MultiArrayDimesion ? Why do people use stride like this: What does this means mat.data[offset + i + dstride1*j] = num?

dstride0 = mat.layout.dim[0].stride
dstride1 = mat.layout.dim[1].stride
offset = mat.layout.data_offset
while not rospy.is_shutdown():
    tmpmat = np.zeros((3,3))
    for i in range(3):
        for j in range(3):
            num = random.randrange(0,10)
            mat.data[offset + i + dstride1*j] = num
            tmpmat[i,j] = num
    pub.publish(mat)
    rospy.loginfo("I'm sending:")
    print tmpmat,"\r\n"
    r.sleep()

2) Can Float32MultiArray publish 2 array at the same time? I found answer from 2010 post saying that ROS doesn't support 2D message publishing. Is ROS supporting it now in 2019?

3) If I were to make my own message, *can I declare 2 or more array in my message? *Would that message type works? Does ROS support that?

4) Is there any *detail guide or video on using this message type apart from API that has so little explanation ? *I really want to understand about this message type.

5) Any suggestion so that I could publish 2*4096 array of signal amplitude and time (nanosec) for signal processing in my subscriber?

I really hope any expert could address my questions. I think it is really related to ROS rather than my homework. The lack of documentation and examples in python really hinder me from understanding and overcoming this issue. Hope the answers to this question would benefit anyone who looking for the same answers.

Thank you in advance.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
7

answered 2019-06-12 18:22:09 -0500

I can help clear up the questions about ROS MultiArray messages, but first as has been suggested I can show you how to define a custom message specifically for your ground penetrating RADAR sensor. The language of ROS message files is described here, as well as a description how to update your CMakeLists.txt file so that they will be built correctly.

The idea here is to define a message type which represents a sample and another message type which contains an array of these samples along with any additional data. Keeping in mind that ROS uses SI units by convention. First the sample message:

GPRSample.msg

# Ground Penetrating Radar Sample Message
float32 delay_secs
float amplitude

I'm not sure if your sensor produces an amplitude metric in units at all or if you get an un-quantified integer value. This could be an example where we don't use SI units in ROS, the laser_scan message for example uses a float32 of no unit to describe reflected pulse intensity because none of the LIDAR manufacturers I know of publish the units of the intensity data their sensors produce.

GPREcho.msg

# Ground Penetrating Radar Echo Message
Header header

# power emitted by Radar (just a guess, don't know if this is relevant)
float emitter_power_watts

# variable length array of gpr samples
GPRSample[] samples

When these two message are built you can then use in python as below

from <your_package_name>.msg import GPRSample
from <your_package_name>.msg import GPREcho
def make_message():
    gpr_msg = GPREcho()
    for i in range(10):
        gpr_sample = GPRSample()
        gpr_sample.delay_secs = i / 1000000000.0
        gpr_sample.amplitude = 10 * sin(i)
        gpr_msg.samples += [gpr_sample]

    gpr_msg.emitter_power_watts = 10
    gpr_msg.header.frame_id = "sensor_frame"
    gpr_msg.header.stamp = rospy.get_rostime()
    return gpr_msg

Using custom messages in this way means that there is useful meta-data along with your raw values, so that other developers and parts of the ROS system can know exactly what the data is. This is not possible with a simple matrix of values, the solution above is how we would recommend you solve this problem. However I will also address your questions about ROS MultiArrays because you're not the first and won't be the last person to be confused by them.

All of the MultiArray messages specify a 1 dimensional flat array which contains the actual data within the array. As well as this it also defines the structure of an n dimensional array which maps onto this 1 dimensional data, this allows it to represent a 3D cube of data, a 2D matrix, a 4D tensor, anything you want. However this power also makes it quite complicated to use in simple cases.

Taking your use case you want to define a 2D matrix of size 2x4096, and we'll use row-major ordering. Create a FloatMultiArray message and put the data into first as a flat array of 8192 elements.

msg = Float32MultiArray()
msg.data = my_data.reshape([8196])

Now we need to define the layout so that ROS knows this data is actually a 2x4096 ... (more)

edit flag offensive delete link more

Comments

3

I do recommend defining custom messages though, it's a bit of a pain at first but when you get used to it you'll never look back.

Just some rationale for this comment: as I wrote in #q325416, using std_msgs for this would allow any subscriber of Float32MultiArray messages to subscribe to your GPR publisher. Even if my node expects image data encoded in a Float32MultiArray, it would succeed in subscribing. It would completely misinterpret the data though, as it expect 2d image data, not GPR return samples.

Unfortunately, when using std_msgs directly, there is no way for your node to convey the fact that it is publishing GPR data -- other than extensively documenting it. But people don't read documentation. They start nodes, .launch files, etc. Until things stop working.

By creating a custom, semantically meaningful message, such as the one @PeteBlackerThe3rd shows in his answer, it would ...(more)

gvdhoorn gravatar image gvdhoorn  ( 2019-06-13 02:28:39 -0500 )edit
3

.. simply because the types would be incompatible.

Additionally, the custom message perfectly captures the semantics (ie: meaning) of the data: each field has an appropriate name and that name almost explains what data it carries. This should reduce the amount of guessing (or reading of documentation) on the part of the consumer signficantly and greatly aids in making sure producer and consumer both understand the data they are exchanging.

People that start out with ROS typically go to std_msgs as they feel they are "exchanging integers, strings and arrays". That is understandable, but I hope it's clearer now that you're really exchanging data with meaning, and that without capturing those semantics in your messages, you may as well send over everything as raw byte arrays.

gvdhoorn gravatar image gvdhoorn  ( 2019-06-13 02:36:29 -0500 )edit
3

One final comment: even though I seem to be suggesting to create custom messages for everything (as they better capture the semantics of the data), there is one thing you should always do: always prefer to use "official" messages for your data first.

So instead of creating a custom message to carry the distances measured by a ultrasonic sensor, use sensor_msgs/Range. Instead of creating a message that carries a single float64[] for the joint states of a robot, use sensor_msgs/JointState. And so on.

Using such messages will greatly increase the chance that you'll be able to reuse software from others, and tools such as RViz for instance will work with messages from sensor_msgs, but not with your own custom ones (unless you write a plugin).

gvdhoorn gravatar image gvdhoorn  ( 2019-06-13 02:40:53 -0500 )edit

@PeteBlackerThe3rd@gvdhoorn thank you so much for detailed explanation for my questions. Everything is clearing up now. I really appreciate both of your help. I will take the suggestion of using custom message as it is much more suitable and simpler in my project. :D

dual-swordsman gravatar image dual-swordsman  ( 2019-06-13 16:16:21 -0500 )edit

How do I say that this question is already answered?

dual-swordsman gravatar image dual-swordsman  ( 2019-06-13 16:17:31 -0500 )edit

Great, glad we could help. If you click the tick mark at the top left of this answer it will mark it as accepted.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2019-06-13 17:11:51 -0500 )edit

Thank you! :)

dwd394 gravatar image dwd394  ( 2022-08-01 21:45:00 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2019-06-12 15:30:37 -0500

Seen: 16,179 times

Last updated: Jun 12 '19