def __init__(self):
        self.wifi_manager_enabled = rospy.get_param("~wifi_manager_enabled")
        self.launch_ros_processes = rospy.get_param("~launch_ros_processes")
        self.modbus_server_enabled = rospy.get_param("~modbus_server_enabled")
        self.modbus_server_address = rospy.get_param("~modbus_server_address")
        self.modbus_server_port = rospy.get_param("~modbus_server_port")
        self.niryo_one_ros_setup = None
    
        if self.launch_ros_processes:
            self.niryo_one_ros_setup = NiryoOneRosSetup()
            rospy.sleep(10) # let some time for other processes to launch (does not affect total launch time)
        
        # Start wifi manager
        if self.wifi_manager_enabled:
            self.wifi_manager = WifiConnectionManager()
      
        self.fans_manager = FansManager()
        self.ros_log_manager = RosLogManager()
        self.shutdown_manager = ShutdownManager()
        self.led_manager = LEDManager()
        self.niryo_one_button = NiryoButton()
        self.digital_io_panel = DigitalIOPanel()

        # Start Modbus server
        if self.modbus_server_enabled:
            self.modbus_server = ModbusServer(self.modbus_server_address, self.modbus_server_port)
            rospy.on_shutdown(self.modbus_server.stop)
            self.modbus_server.start()
class NiryoOneRpi:
    def setup_fans(self):
        GPIO.setwarnings(False)
        GPIO.setmode(GPIO.BCM)
        GPIO.setup(FAN_1_GPIO, GPIO.OUT)
        GPIO.setup(FAN_2_GPIO, GPIO.OUT)
        rospy.sleep(0.1)
        GPIO.output(FAN_1_GPIO, GPIO.HIGH)
        GPIO.output(FAN_2_GPIO, GPIO.HIGH)
        rospy.loginfo("------ RPI FANS ON ------")

    def __init__(self):
        self.wifi_manager_enabled = rospy.get_param("~wifi_manager_enabled")
        self.launch_ros_processes = rospy.get_param("~launch_ros_processes")
        self.modbus_server_enabled = rospy.get_param("~modbus_server_enabled")
        self.modbus_server_address = rospy.get_param("~modbus_server_address")
        self.modbus_server_port = rospy.get_param("~modbus_server_port")
        self.niryo_one_ros_setup = None

        if self.launch_ros_processes:
            self.niryo_one_ros_setup = NiryoOneRosSetup()
            rospy.sleep(
                10
            )  # let some time for other processes to launch (does not affect total launch time)

        # Start wifi manager
        if self.wifi_manager_enabled:
            self.wifi_manager = WifiConnectionManager()

        self.setup_fans()
        self.ros_log_manager = RosLogManager()
        self.led_manager = LEDManager()
        self.niryo_one_button = NiryoButton()
        self.digital_io_panel = DigitalIOPanel()

        # Start Modbus server
        if self.modbus_server_enabled:
            self.modbus_server = ModbusServer(self.modbus_server_address,
                                              self.modbus_server_port)
            rospy.on_shutdown(self.modbus_server.stop)
            self.modbus_server.start()
Beispiel #3
0
#!/usr/bin/env python

import rospy
from niryo_one_modbus.modbus_server import ModbusServer

if __name__ == '__main__':

    rospy.init_node('modbus_server_test')

    server = ModbusServer("0.0.0.0", 5020)
    rospy.on_shutdown(server.stop)

    server.start()
    rospy.spin()