src
examples
MessageReceive
messagereceive.cpp
Go to the documentation of this file.
1
26
#include "stdafx.h"
27
#include <string>
28
#include <stdio.h>
29
#include "ros.h"
30
#include <geometry_msgs/PoseWithCovarianceStamped.h>
31
#include <windows.h>
32
33
using
std::string;
34
35
void
estimated_pose_callback
(
const
geometry_msgs::PoseWithCovarianceStamped & pose)
36
{
37
printf (
"Received pose %f, %f, %f\n"
, pose.pose.pose.position.x,
38
pose.pose.pose.position.y, pose.pose.pose.position.z);
39
}
40
41
int
_tmain
(
int
argc, _TCHAR * argv[])
42
{
43
ros::NodeHandle
nh;
44
char
*ros_master =
"1.2.3.4"
;
45
46
printf (
"Connecting to server at %s\n"
, ros_master);
47
nh.initNode (ros_master);
48
49
ros::Subscriber < geometry_msgs::PoseWithCovarianceStamped >
50
poseSub (
"estimated_pose"
, &
estimated_pose_callback
);
51
nh.
subscribe
(poseSub);
52
53
printf (
"Waiting to receive messages\n"
);
54
while
(1)
55
{
56
nh.spinOnce ();
57
Sleep (100);
58
}
59
60
printf (
"All done!\n"
);
61
return
0;
62
}
_tmain
int _tmain(int argc, _TCHAR *argv[])
Definition:
messagereceive.cpp:41
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Subscriber
estimated_pose_callback
void estimated_pose_callback(const geometry_msgs::PoseWithCovarianceStamped &pose)
Definition:
messagereceive.cpp:35
ros::NodeHandle
rosserial_windows
Author(s): Kareem Shehata
autogenerated on Wed Mar 2 2022 00:58:24