Skip to content
Snippets Groups Projects
Commit b0f4a0c8 authored by Sebastian Ebert's avatar Sebastian Ebert
Browse files

working on ros connection

parent 601928ea
No related branches found
No related tags found
1 merge request!1Example for -> feature/ros connection
This commit is part of merge request !1. Comments created here will be created in the context of that merge request.
......@@ -135,6 +135,7 @@ include_directories(
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
add_executable(${PROJECT_NAME}_demo src/demo.cpp ${PROTO_SRCS} ${PROTO_HDRS})
add_executable(${PROJECT_NAME}_ros_demo src/ros_demo.cpp ${PROTO_SRCS} ${PROTO_HDRS})
## Rename C++ executable without prefix
......@@ -142,16 +143,20 @@ add_executable(${PROJECT_NAME}_demo src/demo.cpp ${PROTO_SRCS} ${PROTO_HDRS})
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
set_target_properties(${PROJECT_NAME}_demo PROPERTIES OUTPUT_NAME demo PREFIX "")
set_target_properties(${PROJECT_NAME}_ros_demo PROPERTIES OUTPUT_NAME ros_nnnnndemo PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
add_dependencies(${PROJECT_NAME}_demo ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(${PROJECT_NAME}_ros_demo ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
target_link_libraries(${PROJECT_NAME}_demo
${catkin_LIBRARIES}
)
target_link_libraries(${PROJECT_NAME}_ros_demo
${catkin_LIBRARIES}
)
#############
## Install ##
......
<launch>
<node pkg="ccf_base_application" type="ros_demo" name="my_ros_demo" output="screen">
</node>
</launch>
//
// Created by sebastian on 02.11.21.
//
#include <ros/ros.h>
#include <ros/package.h>
#include <std_msgs/Empty.h>
#include "ccf/controller/Controller.h"
#include "ccf/connection/RosConnection.h"
#include "ccf/util/NodeUtil.h"
void receiverCallback(const std::string& msg){
std::cout << "RECEIVED: " << msg << std::endl;
}
int main(int argc, char **argv) {
GOOGLE_PROTOBUF_VERIFY_VERSION;
ros::init(argc, argv, "ros_demo");
ros::NodeHandle n;
Controller controller{n};
std::unique_ptr<RosConnection> connection = std::make_unique<RosConnection>("demo", n);
connection->setTopic("demo");
// connection->setHandle(n);
controller.addConnection(std::move(connection));
controller.addCallback("demo",receiverCallback);
ros::spin();
return 0;
}
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment