-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmodded_publisher_member_function.py
65 lines (52 loc) · 1.93 KB
/
modded_publisher_member_function.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import rclpy
from rclpy.node import Node
import py_pubsub.ultrasonic_distance as p
from std_msgs.msg import String
from sensor_msgs.msg import Range
class MinimalPublisher(Node):
def __init__(self):
super().__init__('minimal_publisher')
self.publisher_ = self.create_publisher(Range, 'distance', 10)
timer_period = 0.1 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0
def timer_callback(self):
# msg = String()
# msg.data = 'Hello World: %d' % self.i
# self.publisher_.publish(msg)
# self.get_logger().info('Publishing: "%s"' % msg.data)
# self.i += 1
rg = p.distance()
r = Range()
r.header.stamp = self.get_clock().now().to_msg()
r.header.frame_id = "/sonar_link"
r.radiation_type = 0
r.field_of_view = .31
r.min_range = .02
r.max_range = 1.4
r.range = rg
self.publisher_.publish(r)
def main(args=None):
rclpy.init(args=args)
minimal_publisher = MinimalPublisher()
rclpy.spin(minimal_publisher)
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()