-
Notifications
You must be signed in to change notification settings - Fork 479
/
independent_listener.cc
72 lines (60 loc) · 2.17 KB
/
independent_listener.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
/*
* Copyright (C) 2012 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#include <gazebo/transport/transport.hh>
#include <gazebo/msgs/msgs.hh>
#include <gazebo/gazebo_client.hh>
#include <iostream>
/////////////////////////////////////////////////
// Function is called every time a message is received.
void posesStampedCallback(ConstPosesStampedPtr &posesStamped)
{
std::cout << posesStamped->DebugString();
::google::protobuf::int32 sec = posesStamped->time().sec();
::google::protobuf::int32 nsec = posesStamped->time().nsec();
std::cout << "Read time: sec: " << sec << " nsec: " << nsec << std::endl;
for (int i =0; i < posesStamped->pose_size(); ++i)
{
const ::gazebo::msgs::Pose &pose = posesStamped->pose(i);
std::string name = pose.name();
if (name == std::string("box"))
{
const ::gazebo::msgs::Vector3d &position = pose.position();
double x = position.x();
double y = position.y();
double z = position.z();
std::cout << "Read position: x: " << x
<< " y: " << y << " z: " << z << std::endl;
}
}
}
/////////////////////////////////////////////////
int main(int _argc, char **_argv)
{
// Load gazebo
gazebo::client::setup(_argc, _argv);
// Create our node for communication
gazebo::transport::NodePtr node(new gazebo::transport::Node());
node->Init();
// Listen to Gazebo pose info topic
gazebo::transport::SubscriberPtr sub =
node->Subscribe("~/pose/info", posesStampedCallback);
// Busy wait loop...replace with your own code as needed.
while (true)
gazebo::common::Time::MSleep(10);
// Make sure to shut everything down.
gazebo::client::shutdown();
}