gazebo$ find . -name *proto
./gazebo/msgs/cylindergeom.proto
./gazebo/msgs/undo_redo.proto
./gazebo/msgs/cessna.proto
./gazebo/msgs/pose_animation.proto
./gazebo/msgs/link_data.proto
./gazebo/msgs/int.proto
./gazebo/msgs/propagation_grid.proto
./gazebo/msgs/rest_login.proto
./gazebo/msgs/pid.proto
./gazebo/msgs/sky.proto
http://gazebosim.org/tutorials?tut=topics_subscribed&ver=1.9
Gazebo communicates on TCP/IP sockets, which allows separate programs to interface with Gazebo. Boost ASIO is used by Gazebo to manage the communication layer, and Google Protobufs are used as the message passing and serialization library. Messages are sent on named channels called topics via publishers. On the other side of a topic are subscribers, which receive callbacks when messages arrive. In summary, to send messages one must publish messages using a publisher on a named topic, and to receive messages one must subscribe to a named topic using a subscriber.
The easiest way to communicate with Gazebo over TCP/IP sockets is to link against the Gazebo libraries, and use the provided functions.
The Gazebo transport system is documented here and messages are documented here.
A list of all the topics in use on a running system can be found with the following command (make sure Gazebo is running first):
gztopic list
This example subscribes to a WorldStatistics message and assumes that you can link against Gazebo.
Download listener.cc and CMakeLists.txt from the above link and put them into to a folder called listener at your home directory. Compile the example:
cd ~/listener
mkdir build
cd build
cmake ..
make
The example program ''listener'' should be built in the build directory. When you run ''listener'' with gazebo running, it will output something like the following:
# Starting in ~/listener/build/
./listener
Msg Waiting for master
Msg Connected to gazebo master @ http://127.0.0.1:11345
Msg Publicized address: 192.168.1.67
sim_time {
sec: 1104
nsec: 855000000
}
pause_time {
sec: 0
nsec: 0
}
real_time {
sec: 1108
nsec: 263362269
}
paused: false
iterations: 1104855
sim_time {
sec: 1105
nsec: 55000000
}
pause_time {
sec: 0
nsec: 0
}
real_time {
sec: 1108
nsec: 464165998
}
paused: false
iterations: 1105055
Load gazebo and run the transport system
gazebo::load(_argc, _argv);
gazebo::run();
Next create a Node, which provides functions to create publishers and subscribers.
gazebo::transport::NodePtr node(new gazebo::transport::Node());
node->Init();
Create a subscriber on the ''world_stats'' topic. Gazebo publishes a stream of stats on this topic.
gazebo::transport::SubscriberPtr sub = node->Subscribe("~/world_stats", cb);
You'll need to create a callback function that will print the message to the console, which we called cb in the previous line.
void cb(ConstWorldStatisticsPtr &_msg)
{
std::cout << _msg->DebugString();
}
At this point you'll have to create a wait loop while messages come in, or do some other processing. Here is simple wait loop.
while (true)
gazebo::common::Time::MSleep(10);
Once you're done, finalize the transport system
gazebo::transport::fini();
listener.cc
/*
* 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
#include
#include
#include
/////////////////////////////////////////////////
// Function is called everytime a message is received.
void cb(ConstWorldStatisticsPtr &_msg)
{
// Dump the message contents to stdout.
std::cout << _msg->DebugString();
}
/////////////////////////////////////////////////
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 world_stats topic
gazebo::transport::SubscriberPtr sub = node->Subscribe("~/world_stats", cb);
// 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();
}
cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
find_package(gazebo REQUIRED)
include_directories(${GAZEBO_INCLUDE_DIRS})
link_directories(${GAZEBO_LIBRARY_DIRS})
list(APPEND CMAKE_CXX_FLAGS "${GAZEBO_CXX_FLAGS}")
add_executable(listener listener.cc)
target_link_libraries(listener ${GAZEBO_LIBRARIES} pthread)
订阅图片
/*
* 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
#include
#include
#include
Mat mRGBAImg;
// std_msgs::Header header;
void cb(ConstImageStampedPtr &_msg)
{
// Dump the message contents to stdout.
// std::cout << _msg->DebugString()<image().data().size()<time().sec()<<"."<< _msg->time().nsec()<image().width()<<"."<< _msg->image().height();
header.stamp.sec = _msg->time().sec();
header.stamp.nsec= _msg->time().nsec();
_msg->time();
mRGBAImg=Mat(cv::Size(_msg->image().width(),_msg->image().height()),CV_8UC3);
//uchar * rgba_data = _msg->image().data() ;
//mRGBAImg.data = rgba_data;
memcpy(mRGBAImg.data,_msg->image().data().c_str(),_msg->image().data().size());
imshow("hha", mRGBAImg);
waitKey(3);
}
/////////////////////////////////////////////////
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 world_stats topic
gazebo::transport::SubscriberPtr sub = node->Subscribe("~/camera/link/camera/image", cb);
// 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();
}