43 lines
974 B
Python
43 lines
974 B
Python
|
#!/usr/bin/env python
|
||
|
|
||
|
# -*- coding: utf-8 -*-
|
||
|
"""
|
||
|
Created on Mon Feb 10 17:09:57 2020
|
||
|
|
||
|
@author: Maxi
|
||
|
"""
|
||
|
|
||
|
import roslib
|
||
|
import rospy
|
||
|
import sys
|
||
|
|
||
|
import std_msgs.msg as msg
|
||
|
from dynamic_reconfigure.server import Server as DynamicReconfigureServer
|
||
|
|
||
|
# Import custom message data and dynamic reconfigure variables.
|
||
|
from Steve.msg import node_example
|
||
|
from Steve.cfg import node_example_paramsConfig as ConfigType
|
||
|
|
||
|
import RPi.GPIO as GPIO
|
||
|
import Pin
|
||
|
from Switch import Switch
|
||
|
|
||
|
|
||
|
class RaisedSwitch(Switch):
|
||
|
def __init__(self):
|
||
|
self.pin = Pin.limit_raised
|
||
|
self.pin_out = Pin.limit_raised_out
|
||
|
self.event_based = True
|
||
|
self.setup_pwr_high()
|
||
|
self.SwitchPub = rospy.Publisher('raised_switch', msg.String, queue_size=1)
|
||
|
|
||
|
Switch.__init__(self)
|
||
|
|
||
|
|
||
|
if __name__ == '__main__': # name == main when ros opens ***.py
|
||
|
# instantiate class
|
||
|
try:
|
||
|
raised_switch = RaisedSwitch()
|
||
|
except rospy.ROSInterruptException:
|
||
|
pass
|