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

Revision history [back]

If your data is always going to be a 4x5 array, you could create a custom message that contained an array of 20 integers and then do a little math to determine how to translate (row,col) access to entries in the 1D array (correct way to do this would depend on if you wanted to use column-major or row-major storage). This would work fine, but could definitely be error prone.

An alternative would be to create a custom message containing arrays of, e.g., 5 integers that would represent rows, then create another custom message that contained an array of length 4 of the first message. In C++, this would become a std::vector< std::vector<int> >. This would also work fine.

There is no reason you can't use the Int32MultiArray from std_msgs, and you certainly don't have to use push_back. You could just initialize a std::vector of length 20 for the data field. Here's an example:

#include "ros/ros.h"
#include "std_msgs/Int32MultiArray.h"
#include "std_msgs/MultiArrayDimension.h"
#include <iostream>
#include <vector>
#include <array>

#define H (4)
#define W (5)


int main(int argc, char **argv)
{
    ros::init(argc, argv, "talker");
    ros::NodeHandle n;
    ros::Publisher pub = n.advertise<std_msgs::Int32MultiArray>("matrix_pub", 1);
    ros::Rate loop_rate(10);
    std_msgs::Int32MultiArray dat;
    int array[H][W] = {
        {0, 1, 2, 3, 4},
        {10, 11, 12, 13, 14},
        {20, 21, 22, 23, 24},
        {30, 31, 32, 33, 34}};

    // fill out message:
    dat.layout.dim.push_back(std_msgs::MultiArrayDimension());
    dat.layout.dim.push_back(std_msgs::MultiArrayDimension());
    dat.layout.dim[0].label = "height";
    dat.layout.dim[1].label = "width";
    dat.layout.dim[0].size = H;
    dat.layout.dim[1].size = W;
    dat.layout.dim[0].stride = H*W;
    dat.layout.dim[1].stride = W;
    dat.layout.data_offset = 0;
    std::vector<int> vec(W*H, 0);
    for (int i=0; i<H; i++)
        for (int j=0; j<W; j++)
            vec[i*W + j] = array[i][j];
    dat.data = vec;

    while (ros::ok())
    {
        pub.publish(dat);
        loop_rate.sleep();
    }

    return 0;
}