STEVE_Cammast/Steve/Scripts/StowedSwitch.py

48 lines
1.2 KiB
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 StowedSwitch(Switch):
def __init__(self):
""" TODO : Flanke abstellen, nur auf HIGH / LOW abfragen """
self.pin = Pin.limit_stowed
self.pin_out = Pin.limit_stowed_out
self.event_based = False # detect only status changes
self.setup_pwr_low()
self.SwitchPub = rospy.Publisher('stowed_switch', msg.String, queue_size=1)
Switch.__init__(self)
if __name__ == '__main__': # name == main when ros opens ***.py
# initialize the node
# rospy.init_node('Switch')
# instantiate class
try:
# my_switch = StowedSwitch()
stow_switch = StowedSwitch()
# raised_switch = RaisedSwitch()
except rospy.ROSInterruptException:
pass