ValveControl Arduino Sketch

This sketch controls four pairs of fill-empty pneumatic valves, eight individual channels in all. These can be used to drive two push-pull pneumatic cylinders or four single-chamber pneumatic actuators.

The full code for the sketch spans several files; all files may be downloaded in a single archive file as ValveControl.zip, browsed in raw form in the source folder, or browsed below.

Main

The main entry points and event loop are in file ValveControl.ino.

  1/// \file ValveControl.ino
  2///
  3/// \brief Hardware I/O driver for controlling pneumatic valves using a simple message protocol.
  4///
  5/// \copyright Copyright (c) 2014-2016, Garth Zeglin.  All rights
  6///            reserved. Licensed under the terms of the BSD 3-clause license.
  7///
  8/// \details This example is intended as a starting point for creating custom
  9///          firmware for driving one or more pneumatic actuators. It includes a
 10///          simple ASCII protocol for sending motion commands to ease
 11///          connecting to dynamic code (e.g. Max or Python) running on a laptop
 12///          or Raspberry Pi.
 13
 14#include "Pneumatic.h"
 15#include "Joint.h"
 16
 17/****************************************************************/
 18/**** ASCII messaging scheme ************************************/
 19/****************************************************************/
 20
 21// The message protocol is based on commands encoded as a sequence of string
 22// tokens and integers in a line of text.  One line is one message.  All the
 23// input message formats begin with a string naming a specific command or
 24// destination followed by one or two argument integers.  The output formats are
 25// similar but include more general debugging output with a variable number of
 26// tokens.
 27
 28// The following message formats are recognized by this program.
 29
 30// Command	Arguments		Meaning
 31// ping                                 query whether the controller is running
 32// version				report the sketch name and build date
 33// led		<value>			controls the built-in LED, value is 0 or non-zero
 34
 35// stop					set all valve channels to a neutral state and joints to idle
 36// empty				set all joints to idle and valve channels to exhaust
 37
 38// pwm	        <channel> <value>	set valve PWM rate and direction; channel is an integer from 1 to NUM_CHANNELS, value ranges over -100 to 100
 39
 40// move         <joint> <value>		sets joint open-loop flow; joint is an integer from 1 to NUM_JOINTS, value ranges over -100 to 100
 41// pos          <joint> <value>		sets joint position target; joint is an integer from 1 to NUM_JOINTS, value is in degrees
 42// offset       <joint> <value>		sets a joint sensor offset
 43// scale        <joint> <value>		sets a joint sensor scale factor
 44
 45// This program generates the following messages:
 46
 47// Command	Arguments		Meaning
 48// awake                                initialization has completed or ping was received
 49// led		<value>			reply with current LED state
 50// id	        <version string>	reply with sketch name and build date
 51// status       <time> <value>...       reply with list of state values (configuration-dependent)
 52
 53/****************************************************************/
 54/**** Global variables and constants ****************************/
 55/****************************************************************/
 56
 57// The baud rate is the number of bits per second transmitted over the serial port.
 58#define BAUD_RATE 115200
 59
 60// Some versions of the Arduino IDE don't correctly define this symbol for an
 61// Arduino Uno.  Note that this pin definition is potentially shared with
 62// SPINDLE_DIR_PIN.
 63#ifndef LED_BUILTIN
 64#define LED_BUILTIN 13
 65#endif
 66
 67/// Identification string.
 68static const char version_string[] = "id ValveControl " __DATE__;
 69
 70/****************************************************************/
 71/// Property specification for each pneumatic axis.  This is used to define an
 72/// initialization table for the specific connected hardware.
 73struct axis_config_t {
 74  int8_t fill, empty;
 75  enum Pneumatic::pneumatic_config_t config;
 76};
 77
 78#if 1
 79
 80// Declare the hardware configuration for a valve card in the valve stack rack.
 81static struct axis_config_t config_table[] = {
 82  { 2, 3, Pneumatic::FILL_EMPTY },
 83  { 4, 5, Pneumatic::FILL_EMPTY },
 84  { 6, 7, Pneumatic::FILL_EMPTY },
 85  { 8, 9, Pneumatic::FILL_EMPTY }
 86};
 87#endif
 88
 89#if 0
 90// Declare the hardware configuration for the 'instructor station'.
 91static struct axis_config_t config_table[] = {
 92  // { 3, 5, Pneumatic::PROP_FILL_PROP_EMPTY },
 93  // { 6, 9, Pneumatic::PROP_FILL_PROP_EMPTY },
 94
 95  { 3, 5, Pneumatic::FILL_EMPTY },
 96  { 6, 9, Pneumatic::FILL_EMPTY },
 97
 98  { 2, 4, Pneumatic::FILL_EMPTY },
 99  { 7, -1, Pneumatic::FILL_THREEWAY },
100  { 8, -1, Pneumatic::FILL_THREEWAY }
101};
102#endif
103
104/// Compute the number of entries in the axis table in use.
105#define NUM_CHANNELS (sizeof(config_table) / sizeof(struct axis_config_t))
106
107/// Control object for each pneumatic channel. The declaration
108/// statically initializes the global state objects for the
109/// channels.  Note that this does not initialize the hardware;
110/// that is performed in setup().
111static Pneumatic channel[NUM_CHANNELS];
112
113/// Define the number of physical axes to control.
114#define NUM_JOINTS 2
115
116/// Control object for each closed-loop joint controller.  These objects manage
117/// the sensor input for each joint and can generate control signals to one or
118/// more Pneumatic objects.  The declaration statically initializes the global
119/// state objects for the axes.  Note that this does not initialize the
120/// hardware; that is performed in setup().
121static Joint controller[NUM_JOINTS];
122
123/****************************************************************/
124/****************************************************************/
125/// Process an input message received from the USB port.
126/// Unrecognized commands are silently ignored.
127
128/// \param argc		number of argument tokens
129/// \param argv		array of pointers to strings, one per token
130
131static void vc_parse_input_message(int argc, char *argv[])
132{
133  // Interpret the first token as a command symbol.
134  char *command = argv[0];
135
136  /* -- process zero-argument commands --------------------------- */
137  if (argc == 1) {
138    if ( string_equal( command, "ping" )) {
139      send_message("awake");
140
141    } else if (string_equal(command, "stop")) {
142      // stop all feedback control and close off all manifolds
143      for (int i = 0; i < NUM_JOINTS; i++)  {
144	controller[i].setMode(Joint::IDLE);
145	controller[i].setPWM(0.0);
146      }
147      for (int i = 0; i < NUM_CHANNELS; i++) {
148	channel[i].setDutyCycle(0.0);
149      }
150
151    } else if (string_equal(command, "empty")) {
152      // stop all feedback control and empty all manifolds
153      for (int i = 0; i < NUM_JOINTS; i++) {
154	controller[i].setMode(Joint::IDLE);
155	controller[i].setPWM(0.0);
156      }
157      for (int i = 0; i < NUM_CHANNELS; i++) {
158	channel[i].setDutyCycle(-1.0);
159      }
160
161    } else if (string_equal(command, "version")) {
162      send_message(version_string);
163    }
164  }
165
166  /* -- process one-argument commands --------------------------- */
167  else if (argc == 2) {
168    long value = atol(argv[1] );
169
170    // Process the 'led' command.
171    if ( string_equal( command, "led" )) {
172#ifdef LED_BUILTIN
173      // turn on the LED if that value is true, then echo it back as a handshake
174      digitalWrite(LED_BUILTIN, (value != 0) ? HIGH : LOW);
175#endif
176      send_message( "led", value );
177    }
178  }
179
180  /* -- process two-argument commands --------------------------- */
181  else if (argc == 3) {
182
183    if ( string_equal( command, "pwm" )) {
184      int axis = atoi(argv[1]);
185      int value = atoi(argv[2]);
186      // takes an integer value between -100 and 100
187      if (axis > 0 && axis <= NUM_CHANNELS) channel[axis-1].setDutyCycle( 0.01 * value );
188    }
189
190    else if ( string_equal( command, "move" )) {
191      int axis = atoi(argv[1]); // joint number starting with 1
192      int value = atoi(argv[2]);  // integer PWM value between -100 and 100
193      if (axis > 0 && axis <= NUM_JOINTS) {
194	controller[axis-1].setMode(Joint::OPENLOOP);
195	controller[axis-1].setPWM(0.01 * value);
196      }
197    }
198
199    else if ( string_equal( command, "pos" )) {
200      int axis = atoi(argv[1]); // joint number starting with 1
201      int value = atoi(argv[2]);  // in degrees
202      if (axis > 0 && axis <= NUM_JOINTS) {
203	controller[axis-1].setMode(Joint::POSITION);
204	controller[axis-1].setTargetPosition((float) value);
205      }
206    }
207
208    else if ( string_equal( command, "offset" )) {
209      int axis = atoi(argv[1]); // joint number starting with 1
210      int value = atoi(argv[2]);  // in raw ADC units
211      if (axis > 0 && axis <= NUM_JOINTS) controller[axis-1].setOffset(value);
212    }
213
214    else if ( string_equal( command, "scale" )) {
215      int axis = atoi(argv[1]); // joint number starting with 1
216      float value = atof(argv[2]);  // in degree/raw ADC units
217      if (axis > 0 && axis <= NUM_JOINTS) controller[axis-1].setScale(value);
218    }
219  }
220}
221
222/****************************************************************/
223/// Polling function to update all background control tasks.
224static void vc_hardware_poll(long interval)
225{
226  for (int i = 0; i < NUM_JOINTS; i++) {
227    controller[i].update(interval);
228  }
229  for (int i = 0; i < NUM_CHANNELS; i++) {
230    channel[i].update(interval);
231  }
232}
233
234/****************************************************************/
235/// Polling function to periodically report state via the serial port.
236void vc_status_output_poll(long interval, unsigned long now)
237{
238  static long timer = 0;
239  const long period = 500000;  // 2 Hz
240
241  // Wait for the next status output event time point.
242  timer -= interval;
243  if (timer <= 0) {
244    timer += period;
245    Serial.print("status ");
246    Serial.print(now);
247
248    for (int c = 0; c < NUM_CHANNELS; c++) {
249      channel[c].send_status();
250    }
251
252    for (int j = 0; j < NUM_JOINTS; j++) {
253      controller[j].send_status();
254    }
255
256    Serial.println();
257  }
258}
259
260/****************************************************************/
261/**** Standard entry points for Arduino system ******************/
262/****************************************************************/
263
264/// Standard Arduino initialization function to configure the system.  This code
265/// will need to be modified to initialize the channel[] array with Pneumatic
266/// objects matching the specific valve and manifold configuration, and the
267/// controller[] array with the physical axis specifications.
268void setup(void)
269{
270  // Initialize the array of axis control objects and valve I/O as soon as possible.
271  for (int i = 0; i < NUM_CHANNELS; i++) {
272    channel[i] = Pneumatic(config_table[i].fill, config_table[i].empty, config_table[i].config);
273    channel[i].begin();
274  }
275
276  // Initialize the joints as open-loop controllers.  No analog feedback is specified.
277#if 1
278  controller[0] = Joint(Joint::DUAL_FILL_EMPTY, &channel[0], &channel[1]);
279  controller[1] = Joint(Joint::DUAL_FILL_EMPTY, &channel[2], &channel[3]);
280#endif
281
282  // Initialize the joints as closed loop controllers. The scale and offset were calculated empirically and
283  // will need to be adjusted for every individual joint.
284#if 0
285  // single-ended test:
286  // controller[0] = Joint(Joint::SINGLE_FILL_EMPTY, &channel[0], NULL, A0, -0.338, 608);
287  // Our default joints are double-ended:
288  controller[0] = Joint(Joint::DUAL_FILL_EMPTY, &channel[0], &channel[1], A0, 0.338, 512);
289  controller[1] = Joint(Joint::DUAL_FILL_EMPTY, &channel[2], &channel[3], A1, 0.338, 512);
290#endif
291
292#ifdef LED_BUILTIN
293  pinMode( LED_BUILTIN, OUTPUT );
294#endif
295
296  // initialize the Serial port
297  Serial.begin(BAUD_RATE);
298
299  // additional hardware configuration can go here
300
301  // send a wakeup message
302  send_message("awake");
303}
304
305/****************************************************************/
306/// Standard Arduino polling function to handle all I/O and periodic processing.
307/// This function is called repeatedly as fast as possible from within the
308/// built-in library to poll program events.  This loop should never be allowed
309/// to stall or block so that all tasks can be constantly serviced.
310void loop()
311{
312  // The timestamp in microseconds for the last polling cycle, used to compute
313  // the exact interval between output updates.
314  static unsigned long last_update_clock = 0;
315
316  // Read the microsecond clock.
317  unsigned long now = micros();
318
319  // Compute the time elapsed since the last poll.  This will correctly handle wrapround of
320  // the 32-bit long time value given the properties of twos-complement arithmetic.
321  unsigned long interval = now - last_update_clock;
322  last_update_clock = now;
323
324  // Begin the polling cycle.
325  vc_hardware_poll(interval);
326  vc_serial_input_poll(interval);
327  vc_status_output_poll(interval, now);
328
329  // other polled tasks can go here
330}
331
332/****************************************************************/