ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
On the arduino side, array messages have an extra variable added to their class definitions used to define their length. In our case, this means that the Float32MultiArray
msg has a data
and data_length
field; in order to set the data
field we first need to set the data_length
field:
#include <ros.h>
#include <std_msgs/Float32MultiArray.h>
int array_length = 3;
float values[array_length] = {1.0, 2.0, 3.0};
ros::NodeHandle nh;
std_msgs::Float32MultiArray array_msg;
ros::Publisher pub("array_publisher", &array_msg);
void setup() {
nh.initNode();
nh.advertise(pub);
}
void loop(){
array_msg.data_length = array_length;
array_msg.data = values;
pub.publish(&array_msg);
nh.spinOnce();
delay(1000);
}
For more information, see the array section of the rosserial limitations page.