File tree Expand file tree Collapse file tree 3 files changed +14
-14
lines changed
Expand file tree Collapse file tree 3 files changed +14
-14
lines changed Original file line number Diff line number Diff line change @@ -7,6 +7,7 @@ project(oc_chat_ros)
77find_package (catkin REQUIRED COMPONENTS
88 rospy
99 std_msgs
10+ message_generation
1011)
1112
1213## System dependencies are found with CMake's conventions
@@ -43,11 +44,11 @@ find_package(catkin REQUIRED COMPONENTS
4344## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
4445
4546## Generate messages in the 'msg' folder
46- # add_message_files(
47- # FILES
48- # Message1 .msg
47+ add_message_files(
48+ FILES
49+ ChatMessage .msg
4950# Message2.msg
50- # )
51+ )
5152
5253## Generate services in the 'srv' folder
5354# add_service_files(
@@ -64,10 +65,10 @@ find_package(catkin REQUIRED COMPONENTS
6465# )
6566
6667## Generate added messages and services with any dependencies listed here
67- # generate_messages(
68- # DEPENDENCIES
69- # std_msgs
70- # )
68+ generate_messages(
69+ DEPENDENCIES
70+ std_msgs
71+ )
7172
7273################################################
7374## Declare ROS dynamic reconfigure parameters ##
@@ -101,7 +102,7 @@ find_package(catkin REQUIRED COMPONENTS
101102catkin_package(
102103# INCLUDE_DIRS include
103104# LIBRARIES oc_chat_ros
104- # CATKIN_DEPENDS rospy std_msgs
105+ CATKIN_DEPENDS message_runtime rospy std_msgs
105106# DEPENDS system_lib
106107)
107108
Original file line number Diff line number Diff line change 4242 <buildtool_depend >catkin</buildtool_depend >
4343 <build_depend >rospy</build_depend >
4444 <build_depend >std_msgs</build_depend >
45- <build_depend >chatbot</build_depend >
4645 <run_depend >rospy</run_depend >
4746 <run_depend >std_msgs</run_depend >
48- <run_depend >chatbot</ run_depend >
49-
47+ <build_depend >message_generation</ build_depend >
48+ < run_depend >message_runtime</ run_depend >
5049 <!-- The export tag contains other, unspecified, tags -->
5150 <export >
5251 <!-- Other tools can request additional information be placed here -->
Original file line number Diff line number Diff line change 11#!/usr/bin/env python
22import rospy
3- from chatbot .msg import ChatMessage
3+ from oc_chat_ros .msg import ChatMessage
44from netcat import netcat
55
66def callback (data ):
77 rospy .loginfo (rospy .get_caller_id () + "I heard %s" , data .utterance )
8- netcat ("localhost" ,17040 ,data .utterance )
8+ netcat ("localhost" ,17040 ,"(chat \" " + data .utterance + " \" )" )
99
1010def listener ():
1111
You can’t perform that action at this time.
0 commit comments