Gazebo-ROS plugin does not detect messages sent by other Gazebo-ROS plugin
I have a gazebo-ros world plugin which subscribes to a ROS topic and published into another ROS topic. This plugin is loaded into two worlds that run in two separate simulation on separate ROS master and Gazebo master. The communication between the ROS masters is achieved using Multimaster FKIE package.
The setting for the master_sync node is following
rosrun master_sync_fkie master_sync _ignore_nodes:=['/gazebo*','/tf*','/clock'] _ignore_topics:=['/gazebo*','/tf*','/clock']
The plugin for each of the worlds starts a ROS node with a different name, publishes to a different topic and reads the topic that the other simulation publishes to.
- simulation 1
- node name: node1
- publishes /topic1
- subscribes /topic2
- simulation 2
- node name: node2
- publishes /topic2
- subscribes /topic1
When one of the simulation publishes a message to its topic, let's say simulation 1 published into /topic1
, then the simulation 2 does not detect any message on /topic1
, even though I can see the messages arrive to the topic using the rostopic echo /topic1
in the terminal belonging to the simulation 2. And if I publish the same message in the terminal belonging to the simulation 1 using the command rostopic pub /topic1 std_msgs/Float32 "data: 1.0"
the simulation 2 does detect this message.
This is how I subscribe to topic in the plugin
ros::Subscriber rosSub = this->rosNode->subscribe(other_clock_topic, 10, &MyPlugin::onMsg, this);
This is how I advertise the topic in the plugin
ros::Publisher rosPub = this->rosNode->advertise<std_msgs::Float32>(my_clock_topic, 10, true);
This is the onMsg callback function
void MyPlugin::onMsg(const std_msgs::Float32Ptr& msg)
{
std::cout << "[MyPlugin.cc] detected msg: " << msg->data << "\n";
this->other_sim_time = msg->data;
}
This is how I publish to the plugin's topic
void MyPlugin::publishTime()
{
std_msgs::Float32 msg;
msg.data = (float)this->my_sim_time;
std::cout << "[MyPlugin.cc] Publishing msg: " << msg.data << "\n";
std::cout << "[MyPlugin.cc] Msg data type: " << typeid(msg.data).name() << "\n";
this->rosPub.publish(msg);
}
I do not see any reason, why would the plugin's callback only pick up on the messages sent from the terminal. There should be no difference between messages sent from the terminal and from the plugin, right? And again, I can see the messages from plugin arrive on the topic at the other simulation's terminal, so the Multimaster FKIE does transfer those.
So why is this happening? How can I fix this?
Asked by kumpakri on 2019-06-26 02:57:12 UTC
Comments