Public Member Functions | |
def | __init__ |
def | changeTrigger |
def | getString |
def | startHeartbeat |
def | startVisualInspection |
Public Attributes | |
sim | |
write_start | |
Private Member Functions | |
def | __decodeString |
def | __evaluateResponse |
def | __getResponse |
def | __sendHeartbeat |
Wrapper that integrates python modbus into standardized ros msgs. The wrapper is able to read from and write to a modbus server running on a Cognex Insight 7200. The corresponding Insight Explorer project should also be contained in this ros package
Definition at line 42 of file insight_modbus_client.py.
def modbus_cognex_insight.insight_modbus_client.InsightModbusClient.__init__ | ( | self, | |
host, | |||
sim = True , |
|||
rate = 50 |
|||
) |
:param host: Contains the IP adress of the modbus server :type host: string :param rate: How often the registers on the modbusserver should be read per second :type rate: float :param reset_registers: Defines if the holding registers should be reset to 0 after they have been read. Only possible if they are writeable :type reset_registers: bool
Definition at line 48 of file insight_modbus_client.py.
def modbus_cognex_insight.insight_modbus_client.InsightModbusClient.__decodeString | ( | self, | |
ascii | |||
) | [private] |
Converts an ascii number to a string :param ascii: Integer code of a string encoded in ascii :type ascii: int :return: Returns two characters as string :rtype: string
Definition at line 156 of file insight_modbus_client.py.
def modbus_cognex_insight.insight_modbus_client.InsightModbusClient.__evaluateResponse | ( | self, | |
job_id, | |||
response, | |||
start_time, | |||
timeout | |||
) | [private] |
Evaluates the response :param job_id: The job from which we expect an answer :type job_id: int :param response: Contains the response from the modbus registers [is_alive,job_id,job_pass,job_fail,barcode] :type response: list :param start_time: Contains the time when the request was sent :type start_time: float :param timeout: Duration until the latest response of the inspection :type timeout: float :return: Depending on the job if it has passed or failed :rtype: bool
Definition at line 120 of file insight_modbus_client.py.
def modbus_cognex_insight.insight_modbus_client.InsightModbusClient.__getResponse | ( | self, | |
id, | |||
start_time, | |||
timeout | |||
) | [private] |
Reads the registers from the camera in the correct order: is alive job_id job_pass job_fail barcode :param job_id: The job from which we expect an answer :type job_id: int :param start_time: Contains the time when the request was sent :type start_time: float :param timeout: Duration until the latest response of the inspection :type timeout: float
Definition at line 85 of file insight_modbus_client.py.
def modbus_cognex_insight.insight_modbus_client.InsightModbusClient.__sendHeartbeat | ( | self | ) | [private] |
Sends an is alive signal to the cognex camera. If this is not send, the camera times out 1 hour after the last message in the best case scenario
Definition at line 224 of file insight_modbus_client.py.
Changes the trigger on the camera to manual and back to continous. This gives the camera some time to update its parameters
Definition at line 186 of file insight_modbus_client.py.
def modbus_cognex_insight.insight_modbus_client.InsightModbusClient.getString | ( | self, | |
start, | |||
num_registers | |||
) |
Reads num_registers from start and tries to recover the string that has been send by the modbus server :param start: Starting address of the modbus register to read the string :type: int :param:number of registers to read :type: int :return: Returns a string :rtype: string
Definition at line 168 of file insight_modbus_client.py.
Non blocking call to start the heartbeat loop
Definition at line 217 of file insight_modbus_client.py.
def modbus_cognex_insight.insight_modbus_client.InsightModbusClient.startVisualInspection | ( | self, | |
job_id, | |||
timeout = 5.0 |
|||
) |
Sends a modbus request to change the part detection. job_id 0 is reserved for the heartbeat :param job_id: part id in the insight explorer that should be detected :type job_id: int :param timeout: Duration how long this method should wait for a positive response from the part inspection. The default value should be sufficient. :type timeout: float
Definition at line 70 of file insight_modbus_client.py.
Definition at line 55 of file insight_modbus_client.py.
Definition at line 55 of file insight_modbus_client.py.