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 
45 
95 
120 
145  mip_interface* device, uint8_t* parse_buffer, size_t parse_buffer_size,
146  mip_timeout parse_timeout, mip_timeout base_reply_timeout,
148  mip_update_callback update, void* user_pointer)
149 {
150  mip_parser_init(&device->_parser, parse_buffer, parse_buffer_size, &mip_interface_parse_callback, device, parse_timeout);
151 
153  device->_send_callback = send;
154  device->_recv_callback = recv;
156  device->_user_pointer = user_pointer;
157 
158  mip_cmd_queue_init(&device->_queue, base_reply_timeout);
159 
161 }
162 
163 
165 //
166 // Accessors
167 //
169 
170 
181 {
182  device->_send_callback = callback;
183 }
184 
193 {
194  return device->_send_callback;
195 }
196 
197 
208 {
209  device->_recv_callback = callback;
210 }
211 
220 {
221  return device->_recv_callback;
222 }
223 
224 
241 {
242  device->_update_callback = callback;
243 }
244 
245 
253 {
254  return device->_update_callback;
255 }
256 
257 
265 {
266  device->_user_pointer = pointer;
267 }
268 
277 {
278  return device->_user_pointer;
279 }
280 
281 
286 {
287  return device->_max_update_pkts;
288 }
289 
306 {
307  device->_max_update_pkts = max_packets;
308 }
309 
310 
315 {
316  return &device->_parser;
317 }
318 
323 {
324  return &device->_queue;
325 }
326 
327 
329 //
330 // Communications
331 //
333 
334 
348 bool mip_interface_send_to_device(mip_interface* device, const uint8_t* data, size_t length)
349 {
351 }
352 
367 bool mip_interface_recv_from_device(mip_interface* device, uint8_t* buffer, size_t max_length, mip_timeout wait_time, size_t* length_out, mip_timestamp* timestamp_out)
368 {
369  return device->_recv_callback && device->_recv_callback(device, buffer, max_length, wait_time, length_out, timestamp_out);
370 }
371 
391 
393 {
394  if( !device->_update_callback )
395  return false;
396 
397  return device->_update_callback(device, wait_time);
398 }
399 
400 
416 {
417  if( !device->_recv_callback )
418  return false;
419 
420  uint8_t* ptr;
422  size_t max_count = mip_parser_get_write_ptr(parser, &ptr);
423 
424  size_t count = 0;
425  mip_timestamp timestamp = 0;
426  if ( !mip_interface_recv_from_device(device, ptr, max_count, wait_time, &count, &timestamp) )
427  return false;
428 
429  assert(count <= max_count);
430 
431  mip_parser_process_written(parser, count, timestamp, 0);
432 
434 
435  return true;
436 }
437 
438 
454 size_t mip_interface_receive_bytes(mip_interface* device, const uint8_t* data, size_t length, mip_timestamp timestamp)
455 {
457 }
458 
472 {
474 }
475 
487 {
488  mip_cmd_queue_process_packet(&device->_queue, packet, timestamp);
489  mip_dispatcher_dispatch_packet(&device->_dispatcher, packet, timestamp);
490 }
491 
501 bool mip_interface_parse_callback(void* device, const mip_packet* packet, mip_timestamp timestamp)
502 {
503  mip_interface_receive_packet(device, packet, timestamp);
504 
505  return true;
506 }
507 
508 
510 //
511 // Command and data processing
512 //
514 
515 
525 {
526  enum mip_cmd_result status;
528  {
529  if( !mip_interface_update(device, true) )
530  {
531  // When this function returns the pending command may be deallocated and the
532  // queue will have a dangling pointer. Therefore, the command must be manually
533  // errored out and de-queued.
534  //
535  // Note: This fix can still cause a race condition in multithreaded apps if the
536  // update thread happens to run right before the cmd is dequeued. The user is
537  // advised to not fail the update callback when another thread is handling
538  // reception, unless that thread is not running. Generally such updates shouldn't
539  // fail as long as the other thread is working normally anyway.
540 
542  cmd->_status = MIP_STATUS_ERROR;
543 
544  return MIP_STATUS_ERROR;
545  }
546  }
547  return status;
548 }
549 
568 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)
569 {
570  return mip_interface_run_command_with_response(device, descriptor_set, cmd_descriptor, cmd_data, cmd_length, MIP_INVALID_FIELD_DESCRIPTOR, NULL, NULL);
571 }
572 
598  uint8_t descriptor_set, uint8_t cmd_descriptor, const uint8_t* cmd_data, uint8_t cmd_length,
599  uint8_t response_descriptor, uint8_t* response_buffer, uint8_t* response_length_inout)
600 {
601  assert((response_descriptor == MIP_INVALID_FIELD_DESCRIPTOR) || ((response_buffer != NULL) && (response_length_inout != NULL)) );
602 
603  uint8_t buffer[MIP_PACKET_LENGTH_MAX];
604 
605  mip_packet packet;
606  mip_packet_create(&packet, buffer, sizeof(buffer), descriptor_set);
607  mip_packet_add_field(&packet, cmd_descriptor, cmd_data, cmd_length);
608  mip_packet_finalize(&packet);
609 
611  const uint8_t response_length = response_length_inout ? *response_length_inout : 0;
612  mip_pending_cmd_init_with_response(&cmd, descriptor_set, cmd_descriptor, response_descriptor, response_buffer, response_length);
613 
614  enum mip_cmd_result result = mip_interface_run_command_packet(device, &packet, &cmd);
615 
616  if( response_length_inout )
617  *response_length_inout = mip_pending_cmd_response_length(&cmd);
618 
619  return result;
620 }
621 
633 {
635  return MIP_STATUS_ERROR;
636 
638 }
639 
654 {
656 
658  {
660  return false;
661  }
662 
663  return true;
664 }
665 
682  uint8_t descriptor_set, bool after_fields, mip_dispatch_packet_callback callback, void* user_data)
683 {
684  mip_dispatch_handler_init_packet_handler(handler, descriptor_set, after_fields, callback, user_data);
686 }
687 
688 
705  uint8_t descriptor_set, uint8_t field_descriptor, mip_dispatch_field_callback callback, void* user_data)
706 {
707  mip_dispatch_handler_init_field_handler(handler, descriptor_set, field_descriptor, callback, user_data);
709 }
710 
727  uint8_t descriptor_set, uint8_t field_descriptor,
728  mip_dispatch_extractor extractor, void* field_ptr)
729 {
730  mip_dispatch_handler_init_extractor(handler, descriptor_set, field_descriptor, extractor, field_ptr);
732 }
mip_interface::_update_callback
mip_update_callback _update_callback
Optional function to call during updates.
Definition: mip_interface.h:52
mip_interface_parse_callback
bool mip_interface_parse_callback(void *device, const mip_packet *packet, mip_timestamp timestamp)
Wrapper around mip_interface_receive_packet for use with mip_parser.
Definition: mip_interface.c:501
mip_interface_set_user_pointer
void mip_interface_set_user_pointer(mip_interface *device, void *pointer)
Sets an optional user data pointer which can be retrieved later.
Definition: mip_interface.c:264
mip_interface::_parser
mip_parser _parser
MIP Parser for incoming MIP packets.
Definition: mip_interface.h:46
mip_dispatch_handler_init_packet_handler
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
mip_interface::_recv_callback
mip_recv_callback _recv_callback
Optional function which is called to receive raw bytes from the device.
Definition: mip_interface.h:51
mip_update_callback
bool(* mip_update_callback)(struct mip_interface *device, mip_timeout timeout)
Definition: mip_interface.h:38
mip_interface_run_command
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.
Definition: mip_interface.c:568
mip_interface::_max_update_pkts
unsigned int _max_update_pkts
Max number of MIP packets to parse at once.
Definition: mip_interface.h:49
mip_interface_register_extractor
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.
Definition: mip_interface.c:725
mip_packet_total_length
uint_least16_t mip_packet_total_length(const mip_packet *packet)
Returns the total length of the packet, in bytes.
Definition: mip_packet.c:105
mip_parser
MIP Parser state.
Definition: mip_parser.h:55
mip_packet_create
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
mip_dispatch_packet_callback
void(* mip_dispatch_packet_callback)(void *context, const mip_packet *packet, mip_timestamp timestamp)
Signature for packet-level callbacks.
Definition: mip_dispatch.h:38
mip_cmd_queue_init
void mip_cmd_queue_init(mip_cmd_queue *queue, mip_timeout base_reply_timeout)
Initializes a command queue.
Definition: mip_cmdqueue.c:200
MIPPARSER_UNLIMITED_PACKETS
#define MIPPARSER_UNLIMITED_PACKETS
Specifies no limit when used as the max_packets argument to mip_parser_parse.
Definition: mip_parser.h:78
mip_parser_init
void mip_parser_init(mip_parser *parser, uint8_t *buffer, size_t buffer_size, mip_packet_callback callback, void *callback_object, mip_timestamp timeout)
Initializes the MIP parser.
Definition: mip_parser.c:32
mip_interface_send_function
mip_send_callback mip_interface_send_function(const mip_interface *device)
Gets the send function pointer.
Definition: mip_interface.c:192
mip_interface_wait_for_reply
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.
Definition: mip_interface.c:524
mip_dispatch_handler_init_field_handler
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
mip_dispatcher_dispatch_packet
void mip_dispatcher_dispatch_packet(mip_dispatcher *self, const mip_packet *packet, mip_timestamp timestamp)
Called to dispatch the callbacks for a given packet.
Definition: mip_dispatch.c:351
mip_dispatch_extractor
bool(* mip_dispatch_extractor)(const mip_field *field, void *ptr)
Signature for extraction callbacks.
Definition: mip_dispatch.h:55
mip_send_callback
bool(* mip_send_callback)(struct mip_interface *device, const uint8_t *data, size_t length)
Definition: mip_interface.h:36
mip_interface_register_field_callback
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.
Definition: mip_interface.c:703
mip_interface_set_update_function
void mip_interface_set_update_function(mip_interface *device, mip_update_callback callback)
Sets the update function.
Definition: mip_interface.c:240
mip_parser_process_written
void mip_parser_process_written(mip_parser *parser, size_t count, mip_timestamp 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:381
mip_parser_get_write_ptr
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:362
mip_interface_user_pointer
void * mip_interface_user_pointer(const mip_interface *device)
Retrieves the pointer set by mip_interface_set_user_pointer().
Definition: mip_interface.c:276
MIP_STATUS_ERROR
@ MIP_STATUS_ERROR
Command could not be executed (error sending/receiving)
Definition: mip_result.h:30
mip_cmd_result
mip_cmd_result
Represents the status of a MIP command.
Definition: mip_result.h:25
data
data
mip_dispatcher_add_handler
void mip_dispatcher_add_handler(mip_dispatcher *self, mip_dispatch_handler *handler)
Registers a handler in the dispatch system.
Definition: mip_dispatch.c:187
mip_interface_set_send_function
void mip_interface_set_send_function(mip_interface *device, mip_send_callback callback)
Sets the send callback function.
Definition: mip_interface.c:180
mip_parser_parse
size_t mip_parser_parse(mip_parser *parser, const uint8_t *input_buffer, size_t input_count, mip_timestamp timestamp, unsigned int max_packets)
Parses packets from the input data buffer.
Definition: mip_parser.c:115
mip_interface::_send_callback
mip_send_callback _send_callback
Optional function which is called to send raw bytes to the device.
Definition: mip_interface.h:50
parse_buffer
uint8_t parse_buffer[1024]
Definition: CV7_example.c:46
mip_interface::_queue
mip_cmd_queue _queue
Queue for checking command replies.
Definition: mip_interface.h:47
mip_interface_send_to_device
bool mip_interface_send_to_device(mip_interface *device, const uint8_t *data, size_t length)
Sends data to the port (i.e.
Definition: mip_interface.c:348
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
device
mip_interface device
Definition: CV7_example.c:47
mip_timestamp
uint64_t mip_timestamp
Type used for packet timestamps and timeouts.
Definition: mip_types.h:32
mip_pending_cmd
Represents a command awaiting a reply from the device.
Definition: mip_cmdqueue.h:41
mip_cmd_result_is_finished
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:45
mip_interface_register_packet_callback
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.
Definition: mip_interface.c:680
mip_interface_default_update
bool mip_interface_default_update(struct mip_interface *device, mip_timeout wait_time)
Polls the port for new data or command replies.
Definition: mip_interface.c:415
mip_interface_update
bool mip_interface_update(struct mip_interface *device, mip_timeout wait_time)
Call to process data from the device.
Definition: mip_interface.c:392
mip_interface_set_recv_function
void mip_interface_set_recv_function(mip_interface *device, mip_recv_callback callback)
Sets the receive callback function.
Definition: mip_interface.c:207
mip_interface::_user_pointer
void * _user_pointer
Optional user-specified data pointer.
Definition: mip_interface.h:53
mip_pending_cmd_response_length
uint8_t mip_pending_cmd_response_length(const mip_pending_cmd *cmd)
Returns the length of the response data.
Definition: mip_cmdqueue.c:136
mip_interface_process_unparsed_packets
void mip_interface_process_unparsed_packets(mip_interface *device)
Process more packets from the internal buffer.
Definition: mip_interface.c:471
mip_interface::_dispatcher
mip_dispatcher _dispatcher
Dispatcher for data callbacks.
Definition: mip_interface.h:48
mip_interface_receive_packet
void mip_interface_receive_packet(mip_interface *device, const mip_packet *packet, mip_timestamp timestamp)
Processes a pre-parsed packet for command replies and data.
Definition: mip_interface.c:486
mip_cmd_queue
Holds a list of pending commands.
Definition: mip_cmdqueue.h:93
mip_field.h
mip_dispatch_handler_init_extractor
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
mip_recv_callback
bool(* mip_recv_callback)(struct mip_interface *device, uint8_t *buffer, size_t max_length, mip_timeout wait_time, size_t *length_out, mip_timestamp *timestamp_out)
Definition: mip_interface.h:37
mip_dispatch_handler
Handler information for MIP Packet or Field callbacks.
Definition: mip_dispatch.h:87
mip_interface.h
MIP_PACKET_LENGTH_MAX
@ MIP_PACKET_LENGTH_MAX
Definition: mip_offsets.h:28
mip_cmd_queue_update
void mip_cmd_queue_update(mip_cmd_queue *queue, mip_timestamp now)
Call periodically to make sure commands time out if no packets are received.
Definition: mip_cmdqueue.c:440
mip_packet_pointer
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
mip_interface_set_max_packets_per_update
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...
Definition: mip_interface.c:305
mip_interface_update_function
mip_update_callback mip_interface_update_function(const mip_interface *device)
Gets the update function pointer.
Definition: mip_interface.c:252
mip_parser_last_packet_timestamp
mip_timestamp mip_parser_last_packet_timestamp(const mip_parser *parser)
Gets the timestamp of the last parsed packet.
Definition: mip_parser.c:330
mip_interface_start_command_packet
bool mip_interface_start_command_packet(mip_interface *device, const mip_packet *packet, mip_pending_cmd *cmd)
Queues the command and sends the packet.
Definition: mip_interface.c:653
mip_packet_finalize
void mip_packet_finalize(mip_packet *packet)
Prepares the packet for transmission by adding the checksum.
Definition: mip_packet.c:443
descriptors.h
mip_cmd_queue_dequeue
void mip_cmd_queue_dequeue(mip_cmd_queue *queue, mip_pending_cmd *cmd)
Removes a pending command from the queue.
Definition: mip_cmdqueue.c:244
mip_interface_receive_bytes
size_t mip_interface_receive_bytes(mip_interface *device, const uint8_t *data, size_t length, mip_timestamp timestamp)
Passes data from the device into the parser.
Definition: mip_interface.c:454
mip_pending_cmd_status
enum mip_cmd_result mip_pending_cmd_status(const mip_pending_cmd *cmd)
Returns the status of the pending command.
Definition: mip_cmdqueue.c:104
mip_packet_add_field
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:289
mip_timeout
mip_timestamp mip_timeout
Definition: mip_types.h:35
mip_interface_cmd_queue
mip_cmd_queue * mip_interface_cmd_queue(mip_interface *device)
Returns the commmand queue for the device.
Definition: mip_interface.c:322
mip_interface_recv_from_device
bool mip_interface_recv_from_device(mip_interface *device, uint8_t *buffer, size_t max_length, mip_timeout wait_time, size_t *length_out, mip_timestamp *timestamp_out)
Checks for data at the port and reads it into buffer.
Definition: mip_interface.c:367
mip_interface_max_packets_per_update
unsigned int mip_interface_max_packets_per_update(const mip_interface *device)
Returns the maximum number of packets to parser per update call.
Definition: mip_interface.c:285
mip_packet
Structure representing a MIP Packet.
Definition: mip_packet.h:41
mip_dispatch_field_callback
void(* mip_dispatch_field_callback)(void *context, const mip_field *field, mip_timestamp timestamp)
Signature for field-level callbacks.
Definition: mip_dispatch.h:47
mip_interface
State of the interface for communicating with a MIP device.
Definition: mip_interface.h:44
length
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
mip_cmd_queue_process_packet
void mip_cmd_queue_process_packet(mip_cmd_queue *queue, const mip_packet *packet, mip_timestamp timestamp)
Process an incoming packet and check for replies to pending commands.
Definition: mip_cmdqueue.c:375
mip_interface_init
void mip_interface_init(mip_interface *device, uint8_t *parse_buffer, size_t parse_buffer_size, mip_timeout parse_timeout, mip_timeout 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:144
MIP_INVALID_FIELD_DESCRIPTOR
@ MIP_INVALID_FIELD_DESCRIPTOR
Definition: descriptors.h:25
cmd
string cmd
mip_interface_run_command_packet
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.
Definition: mip_interface.c:632
assert.h
mip_interface_parser
mip_parser * mip_interface_parser(mip_interface *device)
Returns the MIP parser for the device.
Definition: mip_interface.c:314
mip_dispatcher_init
void mip_dispatcher_init(mip_dispatcher *self)
Initializes the mip_dispatcher object.
Definition: mip_dispatch.c:176
mip_cmd_queue_enqueue
void mip_cmd_queue_enqueue(mip_cmd_queue *queue, mip_pending_cmd *cmd)
Queue a command to wait for replies.
Definition: mip_cmdqueue.c:221
mip_pending_cmd_init_with_response
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:62
status
status
mip_interface_run_command_with_response
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.
Definition: mip_interface.c:597
mip_interface_recv_function
mip_recv_callback mip_interface_recv_function(const mip_interface *device)
Gets the receive function pointer.
Definition: mip_interface.c:219


microstrain_inertial_driver
Author(s): Brian Bingham, Parker Hannifin Corp
autogenerated on Fri May 24 2024 06:48:21