Hello,
I've created a new message to do that, including an array and another field, just to show how you can do that.
The command to create the package: catkin_create_pkg my_pkg roscpp std_msgs geometry_msgs
The message definition (my_pkg/msg/my_msg.msg)
geometry_msgs/Point[] points
uint8 another_field
In the my_pkg/package.xml file, don't forget to add the dependencies for generating the messages:
<build_depend>message_generation</build_depend>
<run_depend>message_runtime</run_depend>
my_pkg/CMakeLists.txt file:
cmake_minimum_required(VERSION 2.8.3)
project(my_pkg)
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
roscpp
std_msgs
message_generation
)
## Generate messages in the 'msg' folder
add_message_files(
FILES
my_msg.msg
# Message2.msg
)
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
geometry_msgs# std_msgs
)
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES my_pkg
CATKIN_DEPENDS geometry_msgs roscpp std_msgs message_runtime
# DEPENDS system_lib
)
include_directories(
${catkin_INCLUDE_DIRS}
)
add_executable(my_publisher src/my_publisher.cpp)
add_executable(my_subscriber src/my_subscriber.cpp)
add_dependencies(my_publisher ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(my_subscriber ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(my_publisher ${catkin_LIBRARIES})
target_link_libraries(my_subscriber ${catkin_LIBRARIES})
Finally, the publisher and subscriber files:
my_pkg/src/my_publisher.cpp
#include "ros/ros.h"
#include "geometry_msgs/Point.h"
#include "my_pkg/my_msg.h"
#include <vector>
struct Point {
float x;
float y;
};
int main(int argc, char **argv)
{
// ROS objects
ros::init(argc, argv, "my_publisher");
ros::NodeHandle n;
ros::Publisher pub = n.advertise<my_pkg::my_msg>("my_topic", 1);
ros::Rate loop_rate(0.5);
// the message to be published
my_pkg::my_msg msg;
msg.another_field = 0;
// creating the vector
Point my_array[11];
Point point;
for (int i=0; i < 11; i++) {
point.x = i;
point.y = i;
my_array[i] = point;
}
std::vector<Point> my_vector (my_array, my_array + sizeof(my_array) / sizeof(Point));
// loop control
int count = 0;
while (ros::ok())
{
msg.points.clear();
msg.another_field = count;
int i = 0;
for (std::vector<Point>::iterator it = my_vector.begin(); it != my_vector.end(); ++it) {
geometry_msgs::Point point;
point.x = (*it).x;
point.y = (*it).y;
point.z = 0;
msg.points.push_back(point);
i++;
}
ROS_INFO("%d", msg.another_field);
pub.publish(msg);
ros::spinOnce();
loop_rate.sleep();
++count;
}
return 0;
}
my_pkg/src/my_subscriber.cpp
#include "ros/ros.h"
#include "my_pkg/my_msg.h"
void clbk(const my_pkg::my_msg::ConstPtr& msg) {
ROS_INFO("%d", msg->another_field);
ROS_INFO("first point: x=%.2f, y=%.2f", msg->points[0].x, msg->points[0].y);
}
int main(int argc, char **argv)
{
// ROS objects
ros::init(argc, argv, "my_subscriber");
ros::NodeHandle n;
ros::Subscriber sub = n.subscribe("my_topic", 1, clbk);
ros::spin();
}
If you want to see step-by-step, I've created a video ( https://youtu.be/4eHWSXGqXg8 ).