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

Revision history [back]

The multi-array messages in std_msgs are very useful for sending matrices. All of these message definitions include a MultiArrayLayout message and just a simple array. For example, check out the definition of the Float32MultiArray. The MultiArrayLayout describes the size and shape of the matrix. This allows a node receiving one of these messages to properly unpack the array into a multidimensional array without requiring a priori knowledge of the matrix structure.

If you are trying to do mathematical calculations on those matrices in C++, it's probably worth checking into using a standard package for matrix math such as Eigen.

The multi-array messages in std_msgs are very useful for sending matrices. All of these message definitions include a MultiArrayLayout message and just a simple array. For example, check out the definition of the Float32MultiArray. The MultiArrayLayout MultiArrayLayout describes the size and shape of the matrix. This allows a node receiving one of these messages to properly unpack the array into a multidimensional array without requiring a priori knowledge of the matrix structure.

If you are trying to do mathematical calculations on those matrices in C++, it's probably worth checking into using a standard package for matrix math such as Eigen.

The multi-array messages in std_msgs are very useful for sending matrices. All of these message definitions include a MultiArrayLayout message and just a simple array. For example, check out the definition of the Float32MultiArray. The MultiArrayLayout describes the size and shape of the matrix. This allows a node receiving one of these messages to properly unpack the array into a multidimensional array without requiring a priori knowledge of the matrix structure.

If you are trying to do mathematical calculations on those matrices in C++, it's probably worth checking into using a standard package for matrix math such as Eigen.

EDIT

As requested, I've written a few simple demos. The demo consists of a Python script that fills out a 3x3 matrix using random integers in [0,10) and publishes that matrix as a Float32MultiArray on the /sent_matrix topic. There is then a C++ receiver that listens to that topic. In the callback I first access a few elements of the message using the formula in the MultiArrayLayout documentation, and I then convert the entire message into an Eigen::MatrixXf. Once I have that Eigen matrix I do a few simple matrix math operations and print them to the terminal. Finally I attempt to implement the nested for loop that was described in the original question. The entire ROS package is available at this gist: https://gist.github.com/jarvisschultz/7a886ed2714fac9f5226

The relevant Python code for filling out the matrix is below:

mat = Float32MultiArray()
mat.layout.dim.append(MultiArrayDimension())
mat.layout.dim.append(MultiArrayDimension())
mat.layout.dim[0].label = "height"
mat.layout.dim[1].label = "width"
mat.layout.dim[0].size = 3
mat.layout.dim[1].size = 3
mat.layout.dim[0].stride = 3*3
mat.layout.dim[1].stride = 3
mat.layout.data_offset = 0
mat.data = [0]*9

dstride1 = mat.layout.dim[1].stride
offset = mat.layout.data_offset
while not rospy.is_shutdown():
    for i in range(3):
        for j in range(3):
            num = random.randrange(0,10)
            mat.data[offset + i + dstride1*j] = num

The relevant C++ code for performing the original question could be boiled down to:

void matrixcb(const std_msgs::Float32MultiArray::ConstPtr& msg)
{
    float h = msg->layout.dim[0].size;
    float w = msg->layout.dim[1].size;
    std::vector<float> data = msg->data;
    Eigen::Map<Eigen::MatrixXf> mat(data.data(), h, w);
    Eigen::MatrixXf newmat = mat;
    for (int i=0; i<h-1; i++) 
        for (int j=0; j<w; j++) 
            newmat(i,j) = mat(i+1,j)+2;
    std::cout << "newmat = " << std::endl << newmat << std::endl;

    return;
}