$search
00001 #!/usr/bin/env python 00002 00003 """ 00004 sample_node.py - This sample program subscribes to the /serializer/SensorState 00005 topic and echos the results. It also moves a servo on GPIO pin 8 (servo ID 1) 00006 if the value of the first sensor (index 0) is above or below a certain threshold. 00007 00008 Created for the Pi Robot Project: http://www.pirobot.org 00009 Copyright (c) 2011 Patrick Goebel. All rights reserved. 00010 00011 This program is free software; you can redistribute it and/or modify 00012 it under the terms of the GNU General Public License as published by 00013 the Free Software Foundation; either version 2 of the License, or 00014 (at your option) any later version. 00015 00016 This program is distributed in the hope that it will be useful, 00017 but WITHOUT ANY WARRANTY; without even the implied warranty of 00018 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00019 GNU General Public License for more details at: 00020 00021 http://www.gnu.org/licenses/gpl.html 00022 """ 00023 00024 import roslib; roslib.load_manifest('serializer') 00025 import rospy 00026 from serializer.srv import * 00027 from serializer.msg import * 00028 00029 class sample_node(): 00030 def __init__(self): 00031 # Name this node 00032 rospy.init_node("sample_node") 00033 00034 # Execute this function when shutting down 00035 rospy.on_shutdown(self.shutdown) 00036 00037 # Set the update rate to 1 second by default 00038 self.rate = rospy.get_param("~node_rate", 1) 00039 r = rospy.Rate(self.rate) 00040 00041 # Initialize the sensor value array 00042 self.sensor_state = SensorState() 00043 00044 # Subscribe to the senors topic 00045 rospy.Subscriber('/serializer/sensors', SensorState, self.getSensorState) 00046 00047 # Subscribe to the SetServo service 00048 rospy.wait_for_service('/serializer/SetServo') 00049 self.servo_proxy = rospy.ServiceProxy('/serializer/SetServo', SetServo) 00050 00051 # Begin the main loop 00052 while not rospy.is_shutdown(): 00053 # Echo back the current sensor values 00054 rospy.loginfo(self.sensor_state) 00055 00056 # Move one of the servos depending on the value of one of the sensors 00057 # try: 00058 # if self.sensor_state.value[0] > 6.4: 00059 # self.servo_proxy(1, 50) 00060 # else: 00061 # self.servo_proxy(1, -50) 00062 # except: 00063 # pass 00064 00065 # Sleep for 1/rate seconds 00066 r.sleep() 00067 00068 # Callback for the sensor state subscriber 00069 def getSensorState(self, data): 00070 self.sensor_state = data 00071 00072 # Shutdown function just prints a message. 00073 def shutdown(self): 00074 rospy.loginfo("Shutting down Sample Node...") 00075 00076 if __name__ == '__main__': 00077 try: 00078 my_node = sample_node() 00079 except rospy.ROSInterruptException: 00080 pass