Skip to content

Commit 7242b9a

Browse files
committed
moved rtcf messages into separate packages (needed to make an RTT typekit from them)
1 parent 16e18b1 commit 7242b9a

18 files changed

+140
-64
lines changed

rtcf/CMakeLists.txt

Lines changed: 2 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -14,43 +14,16 @@ endif()
1414

1515
find_package(catkin REQUIRED COMPONENTS
1616
roscpp
17-
std_msgs
18-
message_generation
17+
rtcf_msgs
1918
rtt_ros
2019
rtt_roscomm
2120
rtt_rosclock
2221
)
2322

24-
##############
25-
## Messages ##
26-
##############
27-
28-
## Generate messages in the 'msg' folder
29-
add_message_files(
30-
FILES
31-
Mapping.msg
32-
IterationInformation.msg
33-
)
34-
35-
## Generate services in the 'srv' folder
36-
add_service_files(
37-
FILES
38-
LoadOrocosComponent.srv
39-
UnloadOrocosComponent.srv
40-
)
41-
42-
43-
## Generate added messages and services with any dependencies listed here
44-
generate_messages(
45-
DEPENDENCIES
46-
std_msgs # Or other packages containing msgs
47-
)
48-
49-
5023
catkin_package(
5124
INCLUDE_DIRS include
5225
CATKIN_DEPENDS
53-
message_runtime
26+
rtt_rtcf_msgs
5427
rtt_ros
5528
rtt_roscomm
5629
rtt_rosclock

rtcf/package.xml

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -11,15 +11,14 @@
1111

1212
<buildtool_depend>catkin</buildtool_depend>
1313

14+
<build_depend>rtcf_msgs</build_depend>
1415
<build_depend>roscpp</build_depend>
15-
<build_depend>std_msgs</build_depend>
16-
<build_depend>message_generation</build_depend>
1716
<build_depend>rtt_ros</build_depend>
1817
<build_depend>rtt_roscomm</build_depend>
1918
<build_depend>rtt_rosclock</build_depend>
2019
<build_depend>rtt</build_depend>
2120

22-
<exec_depend>message_runtime</exec_depend>
21+
<exec_depend>rtt_rtcf_msgs</exec_depend>
2322
<exec_depend>rtt_ros</exec_depend>
2423
<exec_depend>rtt_roscomm</exec_depend>
2524
<exec_depend>rtt_rosclock</exec_depend>

rtcf/src/rt_launcher/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
find_package(Boost REQUIRED program_options)
22

33
add_executable(rt_launcher rt_launcher_node.cpp)
4-
add_dependencies(rt_launcher ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)
4+
add_dependencies(rt_launcher ${catkin_EXPORTED_TARGETS})
55
target_link_libraries(rt_launcher ${catkin_LIBRARIES} ${Boost_LIBRARIES})

rtcf/src/rt_launcher/rt_launcher_node.cpp

Lines changed: 12 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
#include "rt_launcher_node.hpp"
22

3+
#include <rtcf_msgs/LoadOrocosComponent.h>
4+
#include <rtcf_msgs/Mapping.h>
35
#include <signal.h>
46

57
#include <boost/program_options.hpp>
@@ -8,11 +10,6 @@
810
#include <string>
911
#include <vector>
1012

11-
#include "ros/duration.h"
12-
#include "ros/service.h"
13-
#include "rtcf/LoadOrocosComponent.h"
14-
#include "rtcf/Mapping.h"
15-
1613
RTLauncherNode::RTLauncherNode(const ros::NodeHandle &node_handle) : node_handle_(node_handle){};
1714

1815
void RTLauncherNode::loop() { ros::spin(); };
@@ -23,23 +20,24 @@ void RTLauncherNode::shutdown() { shutdownServiceClients(); };
2320

2421
void RTLauncherNode::setupServiceClients() {
2522
ros::service::waitForService("/rt_runner/load_orocos_component", ros::Duration(-1));
26-
loadInRTRunnerClient = node_handle_.serviceClient<rtcf::LoadOrocosComponent>("/rt_runner/load_orocos_component");
23+
loadInRTRunnerClient =
24+
node_handle_.serviceClient<rtcf_msgs::LoadOrocosComponent>("/rt_runner/load_orocos_component");
2725

2826
ros::service::waitForService("/rt_runner/unload_orocos_component", ros::Duration(-1));
2927
unloadInRTRunnerClient =
30-
node_handle_.serviceClient<rtcf::UnloadOrocosComponent>("/rt_runner/unload_orocos_component");
28+
node_handle_.serviceClient<rtcf_msgs::UnloadOrocosComponent>("/rt_runner/unload_orocos_component");
3129
};
3230

3331
void RTLauncherNode::shutdownServiceClients() {
3432
loadInRTRunnerClient.shutdown();
3533
unloadInRTRunnerClient.shutdown();
3634
};
3735

38-
rtcf::LoadOrocosComponent RTLauncherNode::genLoadMsg() {
39-
rtcf::LoadOrocosComponent srv;
36+
rtcf_msgs::LoadOrocosComponent RTLauncherNode::genLoadMsg() {
37+
rtcf_msgs::LoadOrocosComponent srv;
4038

4139
for (auto mapping : launcher_attributes_.mappings) {
42-
rtcf::Mapping m;
40+
rtcf_msgs::Mapping m;
4341

4442
m.from_topic.data = mapping.from_topic;
4543
m.to_topic.data = mapping.to_topic;
@@ -59,8 +57,8 @@ rtcf::LoadOrocosComponent RTLauncherNode::genLoadMsg() {
5957
return srv;
6058
};
6159

62-
rtcf::UnloadOrocosComponent RTLauncherNode::genUnloadMsg() {
63-
rtcf::UnloadOrocosComponent srv;
60+
rtcf_msgs::UnloadOrocosComponent RTLauncherNode::genUnloadMsg() {
61+
rtcf_msgs::UnloadOrocosComponent srv;
6462

6563
srv.request.component_name.data = launcher_attributes_.name;
6664
srv.request.ns.data = launcher_attributes_.ns;
@@ -104,7 +102,7 @@ bool RTLauncherNode::loadROSParameters() {
104102
}
105103

106104
bool RTLauncherNode::loadInRTRunner() {
107-
rtcf::LoadOrocosComponent srv = genLoadMsg();
105+
rtcf_msgs::LoadOrocosComponent srv = genLoadMsg();
108106

109107
bool service_ok = loadInRTRunnerClient.call(srv);
110108
if (service_ok && srv.response.success.data) {
@@ -117,7 +115,7 @@ bool RTLauncherNode::loadInRTRunner() {
117115
};
118116

119117
bool RTLauncherNode::unloadInRTRunner() {
120-
rtcf::UnloadOrocosComponent srv = genUnloadMsg();
118+
rtcf_msgs::UnloadOrocosComponent srv = genUnloadMsg();
121119

122120
bool service_ok = unloadInRTRunnerClient.call(srv);
123121
if (service_ok && srv.response.success.data) {

rtcf/src/rt_launcher/rt_launcher_node.hpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,11 @@
11
#ifndef RT_LAUNCHER_NODE_H
22
#define RT_LAUNCHER_NODE_H
33

4+
#include <rtcf_msgs/LoadOrocosComponent.h>
5+
#include <rtcf_msgs/UnloadOrocosComponent.h>
6+
47
#include "ros/ros.h"
58
#include "ros/service_client.h"
6-
#include "rtcf/LoadOrocosComponent.h"
7-
#include "rtcf/UnloadOrocosComponent.h"
89
#include "rtcf/rtcf_types.hpp"
910

1011
class RTLauncherNode {
@@ -13,8 +14,8 @@ class RTLauncherNode {
1314

1415
LoadAttributes launcher_attributes_;
1516

16-
rtcf::LoadOrocosComponent genLoadMsg();
17-
rtcf::UnloadOrocosComponent genUnloadMsg();
17+
rtcf_msgs::LoadOrocosComponent genLoadMsg();
18+
rtcf_msgs::UnloadOrocosComponent genUnloadMsg();
1819

1920
public:
2021
RTLauncherNode(const ros::NodeHandle &node_handle);

rtcf/src/rt_runner/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,5 +11,5 @@ orocos_add_include_directories(rt_runner ${OROCOS-RTT_INCLUDE_DIRS})
1111
target_link_libraries(rt_runner ${OROCOS-RTT_LIBRARIES})
1212
target_compile_definitions(rt_runner PUBLIC -DRTT_STATIC)
1313

14-
add_dependencies(rt_runner ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)
14+
add_dependencies(rt_runner ${catkin_EXPORTED_TARGETS})
1515
target_link_libraries(rt_runner ${catkin_LIBRARIES})

rtcf/src/rt_runner/main_context.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44

55
#pragma GCC diagnostic push
66
#pragma GCC diagnostic ignored "-Wignored-qualifiers"
7+
#include <rtt_ros/rtt_ros.h>
78
#include <rtt_roscomm/rostopic.h>
89
#pragma GCC diagnostic pop
910

@@ -16,6 +17,7 @@ bool MainContext::configureHook() {
1617

1718
// create connection to ROS for iteration information
1819
this->ports()->addPort(port_iter_info_);
20+
rtt_ros::import("rtt_rtcf_msgs");
1921
// add a buffer to not miss something as this is important for debugging
2022
port_iter_info_.createStream(rtt_roscomm::topicBuffer("/rt_runner/" + port_iter_info_.getName(), 10));
2123

@@ -42,7 +44,7 @@ void MainContext::updateHook() {
4244
timing_analysis_.stop();
4345

4446
// publish debugging information
45-
rtcf::IterationInformation info;
47+
rtcf_msgs::IterationInformation info;
4648
info.stamp = timing_analysis_.getIterationStamp();
4749
info.duration_ns = (uint64_t)timing_analysis_.getCalculationDuration();
4850
port_iter_info_.write(info);

rtcf/src/rt_runner/main_context.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#ifndef MAIN_CONTEXT_H
22
#define MAIN_CONTEXT_H
33

4-
#include <rtcf/IterationInformation.h>
4+
#include <rtcf_msgs/IterationInformation.h>
55

66
#pragma GCC diagnostic push
77
#pragma GCC diagnostic ignored "-Wunused-parameter"
@@ -17,7 +17,7 @@ class MainContext : public RTT::TaskContext {
1717
RTOrder slaves_;
1818

1919
TimingAnalysis timing_analysis_;
20-
RTT::OutputPort<rtcf::IterationInformation> port_iter_info_;
20+
RTT::OutputPort<rtcf_msgs::IterationInformation> port_iter_info_;
2121

2222
public:
2323
MainContext(std::string const& name);

rtcf/src/rt_runner/rt_runner_node.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -141,8 +141,8 @@ bool RTRunnerNode::loadROSParameters() {
141141
return true;
142142
}
143143

144-
bool RTRunnerNode::loadOrocosComponentCallback(rtcf::LoadOrocosComponent::Request &req,
145-
rtcf::LoadOrocosComponent::Response &res) {
144+
bool RTRunnerNode::loadOrocosComponentCallback(rtcf_msgs::LoadOrocosComponent::Request &req,
145+
rtcf_msgs::LoadOrocosComponent::Response &res) {
146146
const std::lock_guard<std::mutex> lock(mtx_);
147147

148148
LoadAttributes attr;
@@ -168,8 +168,8 @@ bool RTRunnerNode::loadOrocosComponentCallback(rtcf::LoadOrocosComponent::Reques
168168
return true;
169169
};
170170

171-
bool RTRunnerNode::unloadOrocosComponentCallback(rtcf::UnloadOrocosComponent::Request &req,
172-
rtcf::UnloadOrocosComponent::Response &res) {
171+
bool RTRunnerNode::unloadOrocosComponentCallback(rtcf_msgs::UnloadOrocosComponent::Request &req,
172+
rtcf_msgs::UnloadOrocosComponent::Response &res) {
173173
const std::lock_guard<std::mutex> lock(mtx_);
174174

175175
UnloadAttributes attr;

rtcf/src/rt_runner/rt_runner_node.hpp

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,8 @@
22
#define RT_RUNNER_NODE_H
33

44
#include <ros/ros.h>
5-
#include <rtcf/LoadOrocosComponent.h>
6-
#include <rtcf/UnloadOrocosComponent.h>
5+
#include <rtcf_msgs/LoadOrocosComponent.h>
6+
#include <rtcf_msgs/UnloadOrocosComponent.h>
77
#include <std_srvs/Trigger.h>
88

99
#include <memory>
@@ -23,9 +23,10 @@ class RTRunnerNode {
2323
ros::ServiceServer activateRTLoopService_;
2424
ros::ServiceServer deactivateRTLoopService_;
2525

26-
bool loadOrocosComponentCallback(rtcf::LoadOrocosComponent::Request &req, rtcf::LoadOrocosComponent::Response &res);
27-
bool unloadOrocosComponentCallback(rtcf::UnloadOrocosComponent::Request &req,
28-
rtcf::UnloadOrocosComponent::Response &res);
26+
bool loadOrocosComponentCallback(rtcf_msgs::LoadOrocosComponent::Request &req,
27+
rtcf_msgs::LoadOrocosComponent::Response &res);
28+
bool unloadOrocosComponentCallback(rtcf_msgs::UnloadOrocosComponent::Request &req,
29+
rtcf_msgs::UnloadOrocosComponent::Response &res);
2930

3031
bool activateRTLoopCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
3132
bool deactivateRTLoopCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);

0 commit comments

Comments
 (0)