ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I've had my best success by decomposing the message definition.
circle.msg:
float32[] circle
circles.msg:
circle[] circles
This translates to "circles is an array of circle" and "circle is an array of float32".
2 | No.2 Revision |
I've had my best success by decomposing the message definition.
Working example:
Messages:
circle.msg:Group.msg: float32[]circledata Groups.msg: Group[] group
Code:
circles.msg: circle[] circles#include <stdio.h> #include <stdlib.h> #include <string.h> #include <ros/ros.h> #include <ros/console.h> // messages #include "groups/Group.h" #include "groups/Groups.h" void echo_groups (const groups::Groups::ConstPtr& msg) { for(std::vector<groups::Group>::const_iterator gp = msg->group.begin(); gp != msg->group.end(); ++gp) { for (std::vector<float>::const_iterator dp = gp->data.begin(); dp != gp->data.end(); ++dp) std::cout << *dp << ' '; std::cout << '\n'; } } int main (int argc, char **argv) { ros::init (argc, argv, "groups"); ros::NodeHandle n; ros::Subscriber groups_sub = n.subscribe ("echo_groups", 8, echo_groups); ros::spin(); return 0; }This translates to "circles is an array of circle" and "circle is an array of float32".
Test:
rostopic pub -1 /echo_groups groups/Groups "[data:[1.1, 1.2, 1.3], data:[2.1, 2.2, 2.3]"
3 | No.3 Revision |
I've had my best success by decomposing the message definition.
Working example:
Messages:
Group.msg:
float32[] data
Groups.msg:
Group[] group
Code:
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <ros/ros.h>
#include <ros/console.h>
// messages
#include "groups/Group.h"
#include "groups/Groups.h"
void echo_groups (const groups::Groups::ConstPtr& msg)
{
for(std::vector<groups::Group>::const_iterator gp = msg->group.begin(); gp != msg->group.end(); ++gp) {
for (std::vector<float>::const_iterator dp = gp->data.begin(); dp != gp->data.end(); ++dp)
std::cout << *dp << ' ';
std::cout << '\n';
}
}
int main (int argc, char **argv)
{
ros::init (argc, argv, "groups");
ros::NodeHandle n;
ros::Subscriber groups_sub = n.subscribe ("echo_groups", 8, echo_groups);
ros::spin();
return 0;
}
Test:
rostopic pub -1 /echo_groups groups/Groups "[data:[1.1, 1.2, 1.3], data:[2.1, 2.2, 2.3]"
2.3]]"
4 | No.4 Revision |
I've had my best success by decomposing the message definition.
Working example:
Messages:
Group.msg:
float32[] data
Groups.msg:
Group[] group
Code:
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <ros/ros.h>
#include <ros/console.h>
// messages
#include "groups/Group.h"
#include "groups/Groups.h"
void echo_groups (const groups::Groups::ConstPtr& msg)
{
for(std::vector<groups::Group>::const_iterator gp = msg->group.begin(); gp != msg->group.end(); ++gp) {
for (std::vector<float>::const_iterator dp = gp->data.begin(); dp != gp->data.end(); ++dp)
std::cout << *dp << ' ';
std::cout << '\n';
}
}
int main (int argc, char **argv)
{
ros::init (argc, argv, "groups");
ros::NodeHandle n;
ros::Subscriber groups_sub = n.subscribe ("echo_groups", 8, echo_groups);
ros::spin();
return 0;
}
Test:
rostopic pub -1 /echo_groups groups/Groups "[data:[1.1, 1.2, 1.3], data:[2.1, 2.2, 2.3]]"
Output:
1.1 1.2 1.3
2.1 2.2 2.3
5 | No.5 Revision |
I've had my best success by decomposing the message definition.
Working example:
Messages:
Group.msg:
float32[] data
Groups.msg:
Group[] group
CMakeLists.txt
cmake_minimum_required(VERSION 2.8.3)
project(groups)
find_package(catkin REQUIRED COMPONENTS roscpp std_msgs message_generation)
add_message_files(DIRECTORY msg FILES Group.msg Groups.msg)
generate_messages(DEPENDENCIES std_msgs)
catkin_package(CATKIN_DEPENDS roscpp std_msgs message_runtime)
include_directories(include ${catkin_INCLUDE_DIRS})
link_directories(${catkin_LIBRARY_DIRS})
add_executable(groups src/groups.cpp)
target_link_libraries(groups ${catkin_LIBRARIES})
add_dependencies(groups groups_generate_messages_cpp)
install(TARGETS groups
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
)
install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} FILES_MATCHING PATTERN "*.h" )
install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch )
Code:
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <ros/ros.h>
#include <ros/console.h>
// messages
#include "groups/Group.h"
#include "groups/Groups.h"
void echo_groups (const groups::Groups::ConstPtr& msg)
{
for(std::vector<groups::Group>::const_iterator gp = msg->group.begin(); gp != msg->group.end(); ++gp) {
for (std::vector<float>::const_iterator dp = gp->data.begin(); dp != gp->data.end(); ++dp)
std::cout << *dp << ' ';
std::cout << '\n';
}
}
int main (int argc, char **argv)
{
ros::init (argc, argv, "groups");
ros::NodeHandle n;
ros::Subscriber groups_sub = n.subscribe ("echo_groups", 8, echo_groups);
ros::spin();
return 0;
}
Test:
rostopic pub -1 /echo_groups groups/Groups "[data:[1.1, 1.2, 1.3], data:[2.1, 2.2, 2.3]]"
Output:
1.1 1.2 1.3
2.1 2.2 2.3