A ROS package for multi-robot message transport based on zmqpp
This package is a separate package version of the swarm_bridage used in CREPES3
- HEADER Only, easy to use
- High Performance, capable to transfer odom message higher than 1000Hz with out fluctuation, tested on Ubuntu 18.04 / 20.04
- Automatically get self
ip, and Broadcast selfidand selfipusing UDP. - Automatically Connect with others Under Same Network, using TCP to transport messages in need
- ROS-like publish/subscribe API
- Capable of simulating Network Delay, by setting
simulationtotrueand givingvirtual_network_delaymanually in the launch file
Install zmqpp, spdlog, and dw first
sudo apt install libzmqpp-dev libspdlog-dev libdw-devAdd this package into your workspace, and compile it, a simple demo could be done by roslaunch:
roslaunch swarm_bridge test_swarm_bridge.launchor by rosmon:
mon launch swarm_bridge test_swarm_bridge.launchSee example for detailed usage
// Initialization
SwarmBridge::Ptr swarm_bridge(new SwarmBridge(nh));
// Register subscriber
swarm_bridge->subscribe<${YOUR_MSG_TYPE}>("${YOUR_TOPIC_NAME}", [&](${YOUR_MSG_TYPE} msg){${YOUR_CODE});
// Publish
swarm_bridge->publish<${YOUR_MSG_TYPE}>("${YOUR_TOPIC_NAME}", msg);Change ${YOUR_MSG_TYPE} into the message type you want to transfer, like nav_msgs::Odometry or visualization_msgs::Marker.
Change ${YOUR_TOPIC_NAME} into the name of the topic, just like ros.
Implement your customized code to substitute ${YOUR_CODE}
Sometimes there may meet situations that cannot automatically get ip in proper network.
E.g., using both wireless network and wired network, and want to transfer message under wireless network.
The priority of wired network usually higher than the wireless network, and the program will automatic get information under uninterested network.
To deal with this situation, please modify the param in launch file of net_mode to manual and set self_ip and broadcast_ip under proper network.
If you are using this project as a inner class in your work, and have multi ros callback queues, there might have a little problem in
template <typename T>
void SwarmBridge::publish(const std::string &topic_name, const T &msg)
{
...
if (this->simulation_)
{
auto start = std::chrono::steady_clock::now();
while (std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::steady_clock::now() - start).count() < this->virtual_network_delay_)
{
ros::spinOnce();
}
}
...
}Set the simulation to false might help.
- separate different groups for broadcast