Skip to content
This repository has been archived by the owner on Dec 10, 2019. It is now read-only.

Commit

Permalink
add new version of python subscriber
Browse files Browse the repository at this point in the history
  • Loading branch information
alesolano committed May 6, 2019
1 parent d4a8b06 commit 3173476
Show file tree
Hide file tree
Showing 3 changed files with 41 additions and 2 deletions.
3 changes: 2 additions & 1 deletion mara_minimal_subscriber/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,8 @@ install(TARGETS

install(
PROGRAMS
scripts/mara_minimal_subscriber.py
scripts/mara_minimal_subscriber_v1.py
scripts/mara_minimal_subscriber_v2.py
DESTINATION lib/${PROJECT_NAME})

ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

# Function that will be called once a message is published to the topic we are subscribed
def minimal_callback(msg):
print('Position:' + str(msg.position))
print('Position:', str(msg.position))

# -------- #

Expand Down
38 changes: 38 additions & 0 deletions mara_minimal_subscriber/scripts/mara_minimal_subscriber_v2.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
#!/usr/bin/python3

import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from hrim_actuator_rotaryservo_msgs.msg import StateRotaryServo

class MinimalSubscriber(Node):

def __init__(self):
# Initialize Node with name "mara_minimal_subscriber"
super().__init__('mara_minimal_subscriber')

# Subscribe to topic "/hrim_actuation_servomotor_000000000001/state_axis1" and link it to "minimal_callback" function
self.create_subscription(StateRotaryServo, '/hrim_actuation_servomotor_000000000001/state_axis1',
self.minimal_callback,
qos_profile=qos_profile_sensor_data) # QoS profile for reading (joint) sensors


def minimal_callback(self, msg):
'''
Function that will be called once a message is published to the topic we are subscribed
'''
self.get_logger().info('Position: {}'.format(msg.position))


def main(args=None):
rclpy.init(args=args)

node = MinimalSubscriber()
rclpy.spin(node)

node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()

0 comments on commit 3173476

Please sign in to comment.