Skip to content

Commit

Permalink
First working ROS Package
Browse files Browse the repository at this point in the history
  • Loading branch information
Miguelmelon committed May 3, 2024
1 parent 543d300 commit 2fa3976
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 2 deletions.
2 changes: 1 addition & 1 deletion people_tracking_v2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ catkin_package(
# DEPENDS system_lib
)

catkin_install_python(PROGRAMS scripts/publisher_node.py
catkin_install_python(PROGRAMS scripts/publisher_node.py scripts/subscriber_node.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

Expand Down
2 changes: 1 addition & 1 deletion people_tracking_v2/scripts/publisher_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ def talk_to_me():
pub = rospy.Publisher('talking_topic', String, queue_size=10)
rospy.init_node('publisher_node', anonymous=True)
rate = rospy.Rate(1)
rospy.loginfo("PPublisher Node started, now publishing messages")
rospy.loginfo("Publisher Node started, now publishing messages")
while not rospy.is_shutdown():
msg = "Hello Keloke - %s" % rospy.get_time()
pub.publish(msg)
Expand Down
19 changes: 19 additions & 0 deletions people_tracking_v2/scripts/subscriber_node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
#!/usr/bin/env python

import rospy
from std_msgs.msg import String

def callback(data):
rospy.loginfo("RECEIVED DATA: %s", data.data)

def listener():
rospy.init_node("subscriber_node", anonymous=True)
rospy.Subscriber('talking_topic', String, callback)
rospy.spin()


if __name__ == '__main__':
try:
listener()
except rospy.ROSInterruptException:
pass

0 comments on commit 2fa3976

Please sign in to comment.