Skip to content
Snippets Groups Projects

Example for -> feature/ros connection

Open Sebastian Ebert requested to merge feature/ros-connection into noetic/develop
2 files
+ 21
8
Compare changes
  • Side-by-side
  • Inline
Files
2
+ 20
7
@@ -8,10 +8,13 @@
@@ -8,10 +8,13 @@
#include "ccf/controller/Controller.h"
#include "ccf/controller/Controller.h"
#include "ccf/connection/RosConnection.h"
#include "ccf/connection/RosConnection.h"
#include "ccf/util/NodeUtil.h"
void receiverCallback(const std::string& msg){
void receiverCallbackA(const std::string& msg){
std::cout << "RECEIVED: " << msg << std::endl;
std::cout << "RECEIVED on A: " << msg << std::endl;
 
}
 
 
void receiverCallbackB(const std::string& msg){
 
std::cout << "RECEIVED on B: " << msg << std::endl;
}
}
int main(int argc, char **argv) {
int main(int argc, char **argv) {
@@ -24,11 +27,21 @@ int main(int argc, char **argv) {
@@ -24,11 +27,21 @@ int main(int argc, char **argv) {
Controller controller{n};
Controller controller{n};
std::unique_ptr<RosConnection> connection = std::make_unique<RosConnection>("demo", n);
std::unique_ptr<RosConnection> connection = std::make_unique<RosConnection>(n, 3000, 3000);
connection->setTopic("demo");
connection->listen("topicA");
// connection->setHandle(n);
connection->listen("topicB");
 
 
connection->addPublisher("topicA");
 
controller.addConnection(std::move(connection));
controller.addConnection(std::move(connection));
controller.addCallback("demo",receiverCallback);
 
controller.addCallback("topicA",receiverCallbackA);
 
controller.addCallback("topicB",receiverCallbackB);
 
 
// make sure that the publisher got registered within the master
 
ros::Rate(ros::Duration(0.5)).sleep();
 
 
controller.sendToAll("topicA", "Hello World!");
ros::spin();
ros::spin();
Loading