Gazebo ROS
BACK: Plugins
Gazebo plugins can also be registered as ROS nodes, but under rqt_graph, they will all be under the node ‘/gazebo.’ To interface to ROS, I had one plugin to handle all of the ROS communication and then take the data and send it within the same plugin, in a ros_gazebo_interface.cpp
.
Check out the example here that I did for the HiPeR Lab:
Initializing Gazebo Plugin as a ROS Node
In main():
//init ROS
if (!ros::isInitialized()) {
int argc = 0;
char ** argv = NULL;
ros::init(argc, argv, "gazebo_client", ros::init_options::NoSigintHandler);
}
this->nh.reset(new ros::NodeHandle("gazebo_client"));
Subscriber Example
In main():
//ROS Subscriber to Radio Command. Define the subscriber parameters and then sub.
ros::SubscribeOptions so =
ros::SubscribeOptions::create<hiperlab_rostools::radio_command>(
"/radio_command" + std::to_string(vehicleID),
1,
boost::bind(&GazeboRosInterface::RadioCmdCallback, this, _1),
ros::VoidPtr(), &this->rosQueue);
this->sub_radio_cmd = this->nh->subscribe(so);
In RadioCmdCallback():
//Callback function for whenever a radio command message is recieved.
void GazeboRosInterface::RadioCmdCallback(const hiperlab_rostools::radio_command::ConstPtr &msg) {
doStuff();
}
Publisher Example
In main():
//ROS Publisher to simulator Truth
this->simulator_truth_pub = this->nh->advertise<hiperlab_rostools::simulator_truth>(
"/simulator_truth" + std::to_string(vehicleID),
1);
Multi-threading to constantly subscribe to published data
In main():
//handle ROS multi-threading
this->rosQueueThread = std::thread(std::bind(&GazeboRosInterface::QueueThread, this));
In QueueThread():
//Handle ROS multi-threading
void GazeboRosInterface::QueueThread() {
static const double timeout = 0.01;
while(this->nh->ok())
{
this->rosQueue.callAvailable(ros::WallDuration(timeout));
}