mip_interface.c
Go to the documentation of this file.
1 
2 #include "mip_interface.h"
3 
4 #include "mip_field.h"
5 
7 
8 #include <assert.h>
9 
10 #include <stdio.h>
11 
12 
20 
52 
77 
93  mip_interface* device, uint8_t* parse_buffer, size_t parse_buffer_size,
94  timeout_type parse_timeout, timeout_type base_reply_timeout,
96  mip_update_callback update, void* user_pointer)
97 {
98  mip_parser_init(&device->_parser, parse_buffer, parse_buffer_size, &mip_interface_parse_callback, device, parse_timeout);
99 
101  device->_send_callback = send;
102  device->_recv_callback = recv;
103  device->_update_callback = update;
104  device->_user_pointer = user_pointer;
105 
106  mip_cmd_queue_init(&device->_queue, base_reply_timeout);
107 
109 }
110 
111 
113 //
114 // Accessors
115 //
117 
118 
129 {
130  device->_send_callback = callback;
131 }
132 
141 {
142  return device->_send_callback;
143 }
144 
145 
156 {
157  device->_recv_callback = callback;
158 }
159 
168 {
169  return device->_recv_callback;
170 }
171 
172 
189 {
190  device->_update_callback = callback;
191 }
192 
193 
201 {
202  return device->_update_callback;
203 }
204 
205 
213 {
214  device->_user_pointer = pointer;
215 }
216 
225 {
226  return device->_user_pointer;
227 }
228 
229 
234 {
235  return device->_max_update_pkts;
236 }
237 
254 {
255  device->_max_update_pkts = max_packets;
256 }
257 
258 
263 {
264  return &device->_parser;
265 }
266 
271 {
272  return &device->_queue;
273 }
274 
275 
277 //
278 // Communications
279 //
281 
282 
296 bool mip_interface_send_to_device(mip_interface* device, const uint8_t* data, size_t length)
297 {
298  return device->_send_callback && device->_send_callback(device, data, length);
299 }
300 
315 bool mip_interface_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, timeout_type wait_time, size_t* length_out, timestamp_type* timestamp_out)
316 {
317  return device->_recv_callback && device->_recv_callback(device, buffer, max_length, wait_time, length_out, timestamp_out);
318 }
319 
339 
341 {
342  if( !device->_update_callback )
343  return false;
344 
345  return device->_update_callback(device, wait_time);
346 }
347 
348 
364 {
365  if( !device->_recv_callback )
366  return false;
367 
368  uint8_t* ptr;
370  size_t max_count = mip_parser_get_write_ptr(parser, &ptr);
371 
372  size_t count = 0;
373  timestamp_type timestamp = 0;
374  if ( !mip_interface_recv_from_device(device, ptr, max_count, wait_time, &count, &timestamp) )
375  return false;
376 
377  assert(count <= max_count);
378 
379  mip_parser_process_written(parser, count, timestamp, 0);
380  mip_cmd_queue_update(mip_interface_cmd_queue(device), timestamp);
381 
382  return true;
383 }
384 
385 
401 remaining_count mip_interface_receive_bytes(mip_interface* device, const uint8_t* data, size_t length, timestamp_type timestamp)
402 {
403  return mip_parser_parse(&device->_parser, data, length, timestamp, device->_max_update_pkts);
404 }
405 
419 {
421 }
422 
434 {
435  mip_cmd_queue_process_packet(&device->_queue, packet, timestamp);
436  mip_dispatcher_dispatch_packet(&device->_dispatcher, packet, timestamp);
437 }
438 
448 bool mip_interface_parse_callback(void* device, const mip_packet* packet, timestamp_type timestamp)
449 {
450  mip_interface_receive_packet(device, packet, timestamp);
451 
452  return true;
453 }
454 
455 
457 //
458 // Command and data processing
459 //
461 
462 
472 {
473  enum mip_cmd_result status;
474  while( !mip_cmd_result_is_finished(status = mip_pending_cmd_status(cmd)) )
475  {
476  if( !mip_interface_update(device, true) )
477  {
478  // When this function returns the pending command may be deallocated and the
479  // queue will have a dangling pointer. Therefore, the command must be manually
480  // errored out and de-queued.
481  //
482  // Note: This fix can still cause a race condition in multithreaded apps if the
483  // update thread happens to run right before the cmd is dequeued. The user is
484  // advised to not fail the update callback when another thread is handling
485  // reception, unless that thread is not running. Generally such updates shouldn't
486  // fail as long as the other thread is working normally anyway.
487 
489  cmd->_status = MIP_STATUS_ERROR;
490 
491  return MIP_STATUS_ERROR;
492  }
493  }
494  return status;
495 }
496 
515 enum mip_cmd_result mip_interface_run_command(mip_interface* device, uint8_t descriptor_set, uint8_t cmd_descriptor, const uint8_t* cmd_data, uint8_t cmd_length)
516 {
517  return mip_interface_run_command_with_response(device, descriptor_set, cmd_descriptor, cmd_data, cmd_length, MIP_INVALID_FIELD_DESCRIPTOR, NULL, NULL);
518 }
519 
528  uint8_t descriptor_set, uint8_t cmd_descriptor, const uint8_t* cmd_data, uint8_t cmd_length,
529  uint8_t response_descriptor, uint8_t* response_buffer, uint8_t* response_length_inout)
530 {
531  assert((response_descriptor == MIP_INVALID_FIELD_DESCRIPTOR) || ((response_buffer != NULL) && (response_length_inout != NULL)) );
532 
533  uint8_t buffer[MIP_PACKET_LENGTH_MAX];
534 
535  mip_packet packet;
536  mip_packet_create(&packet, buffer, sizeof(buffer), descriptor_set);
537  mip_packet_add_field(&packet, cmd_descriptor, cmd_data, cmd_length);
538  mip_packet_finalize(&packet);
539 
541  const uint8_t response_length = response_length_inout ? *response_length_inout : 0;
542  mip_pending_cmd_init_with_response(&cmd, descriptor_set, cmd_descriptor, response_descriptor, response_buffer, response_length);
543 
544  enum mip_cmd_result result = mip_interface_run_command_packet(device, &packet, &cmd);
545 
546  if( response_length_inout )
547  *response_length_inout = mip_pending_cmd_response_length(&cmd);
548 
549  return result;
550 }
551 
563 {
564  if( !mip_interface_start_command_packet(device, packet, cmd) )
565  return MIP_STATUS_ERROR;
566 
567  return mip_interface_wait_for_reply(device, cmd);
568 }
569 
584 {
586 
588  {
590  return false;
591  }
592 
593  return true;
594 }
595 
612  uint8_t descriptor_set, bool after_fields, mip_dispatch_packet_callback callback, void* user_data)
613 {
614  mip_dispatch_handler_init_packet_handler(handler, descriptor_set, after_fields, callback, user_data);
615  mip_dispatcher_add_handler(&device->_dispatcher, handler);
616 }
617 
618 
635  uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_field_callback callback, void* user_data)
636 {
637  mip_dispatch_handler_init_field_handler(handler, descriptor_set, field_descriptor, callback, user_data);
638  mip_dispatcher_add_handler(&device->_dispatcher, handler);
639 }
640 
657  uint8_t descriptor_set, uint8_t field_descriptor,
658  mip_dispatch_extractor extractor, void* field_ptr)
659 {
660  mip_dispatch_handler_init_extractor(handler, descriptor_set, field_descriptor, extractor, field_ptr);
661  mip_dispatcher_add_handler(&device->_dispatcher, handler);
662 }
packet_length mip_packet_total_length(const mip_packet *packet)
Returns the total length of the packet, in bytes.
Definition: mip_packet.c:105
void * _user_pointer
Optional user-specified data pointer.
Definition: mip_interface.h:53
void mip_interface_set_max_packets_per_update(mip_interface *device, unsigned int max_packets)
Sets a limit on the number of packets which can be processed in one call to the mip_interface_receive...
bool mip_interface_start_command_packet(mip_interface *device, const mip_packet *packet, mip_pending_cmd *cmd)
Queues the command and sends the packet.
bool(* mip_update_callback)(struct mip_interface *device, timeout_type timeout)
Callback function typedef for custom update behavior.
Definition: mip_interface.h:38
void mip_packet_create(mip_packet *packet, uint8_t *buffer, size_t buffer_size, uint8_t descriptor_set)
Create a brand-new MIP packet in the given buffer.
Definition: mip_packet.c:62
void mip_interface_register_extractor(mip_interface *device, mip_dispatch_handler *handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_extractor extractor, void *field_ptr)
Registers a callback for packets of the specified descriptor set.
void mip_interface_register_field_callback(mip_interface *device, mip_dispatch_handler *handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_field_callback callback, void *user_data)
Registers a callback for packets of the specified descriptor set.
bool mip_interface_recv_from_device(mip_interface *device, uint8_t *buffer, size_t max_length, timeout_type wait_time, size_t *length_out, timestamp_type *timestamp_out)
Checks for data at the port and reads it into buffer.
mip_recv_callback mip_interface_recv_function(const mip_interface *device)
Gets the receive function pointer.
bool(* mip_recv_callback)(struct mip_interface *device, uint8_t *buffer, size_t max_length, timeout_type wait_time, size_t *out_length, timestamp_type *timestamp_out)
Receives new data from the device.
Definition: mip_interface.h:37
#define MIPPARSER_UNLIMITED_PACKETS
Specifies no limit when used as the max_packets argument to mip_parser_parse.
Definition: mip_parser.h:77
enum mip_cmd_result mip_interface_wait_for_reply(mip_interface *device, mip_pending_cmd *cmd)
Blocks until the pending command completes or times out.
Holds a list of pending commands.
Definition: mip_cmdqueue.h:93
mip_update_callback mip_interface_update_function(const mip_interface *device)
Gets the update function pointer.
string cmd
void mip_cmd_queue_update(mip_cmd_queue *queue, timestamp_type now)
Call periodically to make sure commands time out if no packets are received.
Definition: mip_cmdqueue.c:434
bool(* mip_dispatch_extractor)(const mip_field *field, void *ptr)
Signature for extraction callbacks.
Definition: mip_dispatch.h:55
void mip_interface_init(mip_interface *device, uint8_t *parse_buffer, size_t parse_buffer_size, timeout_type parse_timeout, timeout_type base_reply_timeout, mip_send_callback send, mip_recv_callback recv, mip_update_callback update, void *user_pointer)
Initialize the mip_interface components.
Definition: mip_interface.c:92
enum mip_cmd_result mip_pending_cmd_status(const mip_pending_cmd *cmd)
Returns the status of the pending command.
Definition: mip_cmdqueue.c:106
bool mip_interface_parse_callback(void *device, const mip_packet *packet, timestamp_type timestamp)
Wrapper around mip_interface_receive_packet for use with mip_parser.
void mip_interface_receive_packet(mip_interface *device, const mip_packet *packet, timestamp_type timestamp)
Processes a pre-parsed packet for command replies and data.
void * mip_interface_user_pointer(const mip_interface *device)
Retrieves the pointer set by mip_interface_set_user_pointer().
unsigned int _max_update_pkts
Max number of MIP packets to parse at once.
Definition: mip_interface.h:49
remaining_count mip_parser_parse(mip_parser *parser, const uint8_t *input_buffer, size_t input_count, timestamp_type timestamp, unsigned int max_packets)
Parses packets from the input data buffer.
Definition: mip_parser.c:114
size_t mip_parser_get_write_ptr(mip_parser *parser, uint8_t **const ptr_out)
Obtain a pointer into which data may be read for processing.
Definition: mip_parser.c:353
void mip_interface_process_unparsed_packets(mip_interface *device)
Process more packets from the internal buffer.
void mip_interface_set_send_function(mip_interface *device, mip_send_callback callback)
Sets the send callback function.
void mip_cmd_queue_init(mip_cmd_queue *queue, timeout_type base_reply_timeout)
Initializes a command queue.
Definition: mip_cmdqueue.c:194
bool mip_interface_update(struct mip_interface *device, timeout_type wait_time)
Call to process data from the device.
mip_parser _parser
MIP Parser for incoming MIP packets.
Definition: mip_interface.h:46
void mip_interface_set_recv_function(mip_interface *device, mip_recv_callback callback)
Sets the receive callback function.
mip_send_callback _send_callback
Optional function which is called to send raw bytes to the device.
Definition: mip_interface.h:50
remaining_count mip_interface_receive_bytes(mip_interface *device, const uint8_t *data, size_t length, timestamp_type timestamp)
Passes data from the device into the parser.
mip_cmd_queue _queue
Queue for checking command replies.
Definition: mip_interface.h:47
void(* mip_dispatch_packet_callback)(void *context, const mip_packet *packet, timestamp_type timestamp)
Signature for packet-level callbacks.
Definition: mip_dispatch.h:38
void mip_interface_set_update_function(mip_interface *device, mip_update_callback callback)
Sets the update function.
timestamp_type timeout_type
Definition: mip_types.h:35
mip_parser * mip_interface_parser(mip_interface *device)
Returns the MIP parser for the device.
enum mip_cmd_result _status
The current status of the command. Writing this to any MipAck value may cause deallocation.
Definition: mip_cmdqueue.h:57
bool mip_interface_default_update(struct mip_interface *device, timeout_type wait_time)
Polls the port for new data or command replies.
void mip_dispatcher_dispatch_packet(mip_dispatcher *self, const mip_packet *packet, timestamp_type timestamp)
Called to dispatch the callbacks for a given packet.
Definition: mip_dispatch.c:351
uint8_t mip_pending_cmd_response_length(const mip_pending_cmd *cmd)
Returns the length of the response data.
Definition: mip_cmdqueue.c:130
status
timestamp_type mip_parser_last_packet_timestamp(const mip_parser *parser)
Gets the timestamp of the last parsed packet.
Definition: mip_parser.c:321
void mip_parser_process_written(mip_parser *parser, size_t count, timestamp_type timestamp, unsigned int max_packets)
Notify the parser that data has been written to the pointer previously obtained via mip_parser_get_wr...
Definition: mip_parser.c:372
mip_cmd_result
Represents the status of a MIP command.
Definition: mip_result.h:23
unsigned int mip_interface_max_packets_per_update(const mip_interface *device)
Returns the maximum number of packets to parser per update call.
Structure representing a MIP Packet.
Definition: mip_packet.h:43
mip_cmd_queue * mip_interface_cmd_queue(mip_interface *device)
Returns the commmand queue for the device.
mip_recv_callback _recv_callback
Optional function which is called to receive raw bytes from the device.
Definition: mip_interface.h:51
Command could not be executed (error sending/receiving)
Definition: mip_result.h:25
Represents a command awaiting a reply from the device.
Definition: mip_cmdqueue.h:41
Handler information for MIP Packet or Field callbacks.
Definition: mip_dispatch.h:87
void mip_dispatch_handler_init_packet_handler(mip_dispatch_handler *handler, uint8_t descriptor_set, bool post_callback, mip_dispatch_packet_callback callback, void *user_data)
Initialize the dispatch handler with a packet callback.
Definition: mip_dispatch.c:49
bool mip_interface_send_to_device(mip_interface *device, const uint8_t *data, size_t length)
Sends data to the port (i.e.
void mip_dispatcher_add_handler(mip_dispatcher *self, mip_dispatch_handler *handler)
Registers a handler in the dispatch system.
Definition: mip_dispatch.c:187
void mip_cmd_queue_process_packet(mip_cmd_queue *queue, const mip_packet *packet, timestamp_type timestamp)
Process an incoming packet and check for replies to pending commands.
Definition: mip_cmdqueue.c:369
void mip_dispatcher_init(mip_dispatcher *self)
Initializes the mip_dispatcher object.
Definition: mip_dispatch.c:176
uint8_t parse_buffer[1024]
Definition: CV7_example.c:46
void mip_dispatch_handler_init_field_handler(mip_dispatch_handler *handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_field_callback callback, void *user_data)
Initialize the dispatch handler with a field callback.
Definition: mip_dispatch.c:84
State of the interface for communicating with a MIP device.
Definition: mip_interface.h:44
bool mip_packet_add_field(mip_packet *packet, uint8_t field_descriptor, const uint8_t *payload, uint8_t payload_length)
Adds a pre-constructed MIP field to the packet.
Definition: mip_packet.c:285
MIP Parser state.
Definition: mip_parser.h:55
enum mip_cmd_result mip_interface_run_command_packet(mip_interface *device, const mip_packet *packet, mip_pending_cmd *cmd)
Similar to mip_interface_start_command_packet but waits for the command to complete.
mip_send_callback mip_interface_send_function(const mip_interface *device)
Gets the send function pointer.
void mip_pending_cmd_init_with_response(mip_pending_cmd *cmd, uint8_t descriptor_set, uint8_t field_descriptor, uint8_t response_descriptor, uint8_t *response_buffer, uint8_t response_buffer_size)
Initialize a pending mip commmand with expected response data.
Definition: mip_cmdqueue.c:64
void mip_parser_init(mip_parser *parser, uint8_t *buffer, size_t buffer_size, mip_packet_callback callback, void *callback_object, timestamp_type timeout)
Initializes the MIP parser.
Definition: mip_parser.c:32
mip_interface device
Definition: CV7_example.c:47
int_least16_t remaining_count
Definition: mip_types.h:16
void(* mip_dispatch_field_callback)(void *context, const mip_field *field, timestamp_type timestamp)
Signature for field-level callbacks.
Definition: mip_dispatch.h:47
void mip_packet_finalize(mip_packet *packet)
Prepares the packet for transmission by adding the checksum.
Definition: mip_packet.c:439
parser
void mip_cmd_queue_enqueue(mip_cmd_queue *queue, mip_pending_cmd *cmd)
Queue a command to wait for replies.
Definition: mip_cmdqueue.c:215
bool(* mip_send_callback)(struct mip_interface *device, const uint8_t *data, size_t length)
Sends data to the port (i.e.
Definition: mip_interface.h:36
enum mip_cmd_result mip_interface_run_command_with_response(mip_interface *device, uint8_t descriptor_set, uint8_t cmd_descriptor, const uint8_t *cmd_data, uint8_t cmd_length, uint8_t response_descriptor, uint8_t *response_buffer, uint8_t *response_length_inout)
Runs a command using a pre-serialized payload.
uint64_t timestamp_type
Type used for packet timestamps and timeouts.
Definition: mip_types.h:32
bool mip_cmd_result_is_finished(enum mip_cmd_result status)
Determines if the command has completed, timed out, been cancelled, or otherwise is no longer waiting...
Definition: mip_result.c:43
void mip_interface_set_user_pointer(mip_interface *device, void *pointer)
Sets an optional user data pointer which can be retrieved later.
mip_dispatcher _dispatcher
Dispatcher for data callbacks.
Definition: mip_interface.h:48
mip_update_callback _update_callback
Optional function to call during updates.
Definition: mip_interface.h:52
enum mip_cmd_result mip_interface_run_command(mip_interface *device, uint8_t descriptor_set, uint8_t cmd_descriptor, const uint8_t *cmd_data, uint8_t cmd_length)
Runs a command using a pre-serialized payload.
void mip_cmd_queue_dequeue(mip_cmd_queue *queue, mip_pending_cmd *cmd)
Removes a pending command from the queue.
Definition: mip_cmdqueue.c:238
void mip_dispatch_handler_init_extractor(mip_dispatch_handler *handler, uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_extractor extractor, void *field_ptr)
Initialize the dispatch handler with an extraction callback.
Definition: mip_dispatch.c:129
const uint8_t * mip_packet_pointer(const mip_packet *packet)
Returns a pointer to the data buffer containing the packet.
Definition: mip_packet.c:121
void mip_interface_register_packet_callback(mip_interface *device, mip_dispatch_handler *handler, uint8_t descriptor_set, bool after_fields, mip_dispatch_packet_callback callback, void *user_data)
Registers a callback for packets of the specified descriptor set.


microstrain_inertial_driver
Author(s): Brian Bingham, Parker Hannifin Corp
autogenerated on Wed Mar 22 2023 02:35:06