Merge remote-tracking branch 'upstream/edge' into feature/5-axis
[clinton/Smoothieware.git] / src / modules / utils / simpleshell / SimpleShell.cpp
CommitLineData
58baeec1
MM
1/*
2 This file is part of Smoothie (http://smoothieware.org/). The motion control part is heavily based on Grbl (https://github.com/simen/grbl).
3 Smoothie is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.
4 Smoothie is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
5 You should have received a copy of the GNU General Public License along with Smoothie. If not, see <http://www.gnu.org/licenses/>.
cd011f58
AW
6*/
7
8
0325af12 9#include "SimpleShell.h"
ba8da804 10#include "libs/Kernel.h"
0325af12
AW
11#include "libs/nuts_bolts.h"
12#include "libs/utils.h"
423df6df 13#include "libs/SerialMessage.h"
838b33b4 14#include "libs/StreamOutput.h"
3fceb8eb 15#include "modules/robot/Conveyor.h"
172d42d9 16#include "DirHandle.h"
0f0b1656 17#include "mri.h"
582559c6 18#include "version.h"
8293d443 19#include "PublicDataRequest.h"
4fed9ba1 20#include "AppendFileStream.h"
618c9b0f 21#include "FileStream.h"
61134a65
JM
22#include "checksumm.h"
23#include "PublicData.h"
24#include "Gcode.h"
564cf1f0 25#include "Robot.h"
40843ebc
JM
26#include "ToolManagerPublicAccess.h"
27#include "GcodeDispatch.h"
2577a122 28#include "BaseSolution.h"
586cc733 29#include "StepperMotor.h"
3e54c9fc 30#include "Configurator.h"
8a9f9313 31#include "Block.h"
61134a65 32
40843ebc 33#include "TemperatureControlPublicAccess.h"
9339253b 34#include "EndstopsPublicAccess.h"
d4ee6ee2 35#include "NetworkPublicAccess.h"
a200fc31 36#include "platform_memory.h"
ae91dea4 37#include "SwitchPublicAccess.h"
3704585b 38#include "SDFAT.h"
1f8dab1a 39#include "Thermistor.h"
d55d551b 40#include "md5.h"
1aa3d42f 41#include "utils.h"
47339e4a 42
61134a65
JM
43#include "system_LPC17xx.h"
44#include "LPC17xx.h"
45
23eb804b
JM
46#include "mbed.h" // for wait_ms()
47
6187a020
JM
48extern unsigned int g_maximumHeapAddress;
49
ecc610a4
JM
50#include <malloc.h>
51#include <mri.h>
52#include <stdio.h>
53#include <stdint.h>
54
55extern "C" uint32_t __end__;
56extern "C" uint32_t __malloc_free_list;
57extern "C" uint32_t _sbrk(int size);
58
9e403697 59// command lookup table
7e81f138
JM
60const SimpleShell::ptentry_t SimpleShell::commands_table[] = {
61 {"ls", SimpleShell::ls_command},
62 {"cd", SimpleShell::cd_command},
63 {"pwd", SimpleShell::pwd_command},
64 {"cat", SimpleShell::cat_command},
65 {"rm", SimpleShell::rm_command},
6d877d9b
JM
66 {"mv", SimpleShell::mv_command},
67 {"upload", SimpleShell::upload_command},
7e81f138
JM
68 {"reset", SimpleShell::reset_command},
69 {"dfu", SimpleShell::dfu_command},
70 {"break", SimpleShell::break_command},
71 {"help", SimpleShell::help_command},
72 {"?", SimpleShell::help_command},
73 {"version", SimpleShell::version_command},
74 {"mem", SimpleShell::mem_command},
75 {"get", SimpleShell::get_command},
76 {"set_temp", SimpleShell::set_temp_command},
ae91dea4 77 {"switch", SimpleShell::switch_command},
7e81f138
JM
78 {"net", SimpleShell::net_command},
79 {"load", SimpleShell::load_command},
80 {"save", SimpleShell::save_command},
6d877d9b 81 {"remount", SimpleShell::remount_command},
1f8dab1a 82 {"calc_thermistor", SimpleShell::calc_thermistor_command},
4c8f5447 83 {"thermistors", SimpleShell::print_thermistors_command},
d55d551b 84 {"md5sum", SimpleShell::md5sum_command},
b03317ea 85#ifdef CNC
518b5c4c 86 {"test", SimpleShell::test_command},
b03317ea 87#endif
9e403697 88 // unknown command
7e81f138 89 {NULL, NULL}
9e403697 90};
ecc610a4 91
6d877d9b 92int SimpleShell::reset_delay_secs = 0;
7e81f138 93
ecc610a4 94// Adam Greens heap walk from http://mbed.org/forum/mbed/topic/2701/?page=4#comment-22556
0c683b26 95static uint32_t heapWalk(StreamOutput *stream, bool verbose)
ecc610a4
JM
96{
97 uint32_t chunkNumber = 1;
98 // The __end__ linker symbol points to the beginning of the heap.
99 uint32_t chunkCurr = (uint32_t)&__end__;
100 // __malloc_free_list is the head pointer to newlib-nano's link list of free chunks.
101 uint32_t freeCurr = __malloc_free_list;
102 // Calling _sbrk() with 0 reserves no more memory but it returns the current top of heap.
103 uint32_t heapEnd = _sbrk(0);
104 // accumulate totals
9e403697
JM
105 uint32_t freeSize = 0;
106 uint32_t usedSize = 0;
ecc610a4
JM
107
108 stream->printf("Used Heap Size: %lu\n", heapEnd - chunkCurr);
109
110 // Walk through the chunks until we hit the end of the heap.
9e403697 111 while (chunkCurr < heapEnd) {
ecc610a4
JM
112 // Assume the chunk is in use. Will update later.
113 int isChunkFree = 0;
114 // The first 32-bit word in a chunk is the size of the allocation. newlib-nano over allocates by 8 bytes.
115 // 4 bytes for this 32-bit chunk size and another 4 bytes to allow for 8 byte-alignment of returned pointer.
9e403697 116 uint32_t chunkSize = *(uint32_t *)chunkCurr;
ecc610a4
JM
117 // The start of the next chunk is right after the end of this one.
118 uint32_t chunkNext = chunkCurr + chunkSize;
119
120 // The free list is sorted by address.
121 // Check to see if we have found the next free chunk in the heap.
9e403697 122 if (chunkCurr == freeCurr) {
ecc610a4
JM
123 // Chunk is free so flag it as such.
124 isChunkFree = 1;
125 // The second 32-bit word in a free chunk is a pointer to the next free chunk (again sorted by address).
9e403697 126 freeCurr = *(uint32_t *)(freeCurr + 4);
ecc610a4
JM
127 }
128
129 // Skip past the 32-bit size field in the chunk header.
130 chunkCurr += 4;
131 // 8-byte align the data pointer.
132 chunkCurr = (chunkCurr + 7) & ~7;
133 // newlib-nano over allocates by 8 bytes, 4 bytes for the 32-bit chunk size and another 4 bytes to allow for 8
134 // byte-alignment of the returned pointer.
135 chunkSize -= 8;
9e403697 136 if (verbose)
ecc610a4
JM
137 stream->printf(" Chunk: %lu Address: 0x%08lX Size: %lu %s\n", chunkNumber, chunkCurr, chunkSize, isChunkFree ? "CHUNK FREE" : "");
138
9e403697 139 if (isChunkFree) freeSize += chunkSize;
ecc610a4
JM
140 else usedSize += chunkSize;
141
142 chunkCurr = chunkNext;
143 chunkNumber++;
144 }
145 stream->printf("Allocated: %lu, Free: %lu\r\n", usedSize, freeSize);
0c683b26 146 return freeSize;
ecc610a4
JM
147}
148
149
9e403697
JM
150void SimpleShell::on_module_loaded()
151{
0325af12 152 this->register_for_event(ON_CONSOLE_LINE_RECEIVED);
48afc62a 153 this->register_for_event(ON_GCODE_RECEIVED);
154 this->register_for_event(ON_SECOND_TICK);
c4e56997 155
7e81f138 156 reset_delay_secs = 0;
ead17727
JM
157}
158
9e403697
JM
159void SimpleShell::on_second_tick(void *)
160{
ead17727 161 // we are timing out for the reset
7e81f138
JM
162 if (reset_delay_secs > 0) {
163 if (--reset_delay_secs == 0) {
ead17727
JM
164 system_reset(false);
165 }
166 }
0325af12
AW
167}
168
9e403697
JM
169void SimpleShell::on_gcode_received(void *argument)
170{
171 Gcode *gcode = static_cast<Gcode *>(argument);
6d877d9b 172 string args = get_arguments(gcode->get_command());
c4e56997
JM
173
174 if (gcode->has_m) {
175 if (gcode->m == 20) { // list sd card
c4e56997
JM
176 gcode->stream->printf("Begin file list\r\n");
177 ls_command("/sd", gcode->stream);
178 gcode->stream->printf("End file list\r\n");
d4ee6ee2
JM
179
180 } else if (gcode->m == 30) { // remove file
01a8d21a
JM
181 if(!args.empty() && !THEKERNEL->is_grbl_mode())
182 rm_command("/sd/" + args, gcode->stream);
3a238fdc 183 }
c4e56997
JM
184 }
185}
186
7e81f138 187bool SimpleShell::parse_command(const char *cmd, string args, StreamOutput *stream)
9e403697 188{
7e81f138
JM
189 for (const ptentry_t *p = commands_table; p->command != NULL; ++p) {
190 if (strncasecmp(cmd, p->command, strlen(p->command)) == 0) {
191 p->func(args, stream);
9e403697
JM
192 return true;
193 }
194 }
195
196 return false;
197}
198
0325af12 199// When a new line is received, check if it is a command, and if it is, act upon it
9e403697
JM
200void SimpleShell::on_console_line_received( void *argument )
201{
202 SerialMessage new_message = *static_cast<SerialMessage *>(argument);
6c0193b3 203 string possible_command = new_message.message;
7f613782 204
6c0193b3
JM
205 // ignore anything that is not lowercase or a $ as it is not a command
206 if(possible_command.size() == 0 || (!islower(possible_command[0]) && possible_command[0] != '$')) {
207 return;
208 }
7f613782 209
6c0193b3
JM
210 // it is a grbl compatible command
211 if(possible_command[0] == '$' && possible_command.size() >= 2) {
212 switch(possible_command[1]) {
213 case 'G':
214 // issue get state
215 get_command("state", new_message.stream);
543c4b6d 216 new_message.stream->printf("ok\n");
6c0193b3
JM
217 break;
218
219 case 'X':
220 THEKERNEL->call_event(ON_HALT, (void *)1); // clears on_halt
543c4b6d 221 new_message.stream->printf("[Caution: Unlocked]\nok\n");
6c0193b3
JM
222 break;
223
224 case '#':
225 grblDP_command("", new_message.stream);
543c4b6d 226 new_message.stream->printf("ok\n");
6c0193b3
JM
227 break;
228
229 case 'H':
07186543 230 if(THEKERNEL->is_grbl_mode()) {
31c6c2c2 231 THEKERNEL->call_event(ON_HALT, (void *)1); // clears on_halt
8ad60a4c 232 // issue G28.2 which is force homing cycle
53ece53b 233 Gcode gcode("G28.2", new_message.stream);
6c0193b3 234 THEKERNEL->call_event(ON_GCODE_RECEIVED, &gcode);
07186543
JM
235 }else{
236 new_message.stream->printf("error:only supported in GRBL mode\n");
6c0193b3
JM
237 }
238 break;
0325af12 239
6c0193b3 240 default:
07186543 241 new_message.stream->printf("error:Invalid statement\n");
6c0193b3
JM
242 break;
243 }
244
245 }else{
6187a020 246
6c0193b3
JM
247 //new_message.stream->printf("Received %s\r\n", possible_command.c_str());
248 string cmd = shift_parameter(possible_command);
249
3e54c9fc
JM
250 // Configurator commands
251 if (cmd == "config-get"){
252 THEKERNEL->configurator->config_get_command( possible_command, new_message.stream );
253
254 } else if (cmd == "config-set"){
255 THEKERNEL->configurator->config_set_command( possible_command, new_message.stream );
256
257 } else if (cmd == "config-load"){
258 THEKERNEL->configurator->config_load_command( possible_command, new_message.stream );
259
260 } else if (cmd == "play" || cmd == "progress" || cmd == "abort" || cmd == "suspend" || cmd == "resume") {
01a8d21a 261 // these are handled by Player module
93f20a8c
JM
262
263 } else if (cmd == "ok") {
264 // probably an echo so reply ok
265 new_message.stream->printf("ok\n");
3e54c9fc
JM
266
267 }else if(!parse_command(cmd.c_str(), possible_command, new_message.stream)) {
42bbc035 268 new_message.stream->printf("error:Unsupported command - %s\n", cmd.c_str());
6c0193b3
JM
269 }
270 }
0325af12
AW
271}
272
0325af12
AW
273// Act upon an ls command
274// Convert the first parameter into an absolute path, then list the files in that path
9e403697
JM
275void SimpleShell::ls_command( string parameters, StreamOutput *stream )
276{
3579deea
JM
277 string path, opts;
278 while(!parameters.empty()) {
6d877d9b 279 string s = shift_parameter( parameters );
3579deea
JM
280 if(s.front() == '-') {
281 opts.append(s);
282 } else {
6d877d9b
JM
283 path = s;
284 if(!parameters.empty()) {
3579deea
JM
285 path.append(" ");
286 path.append(parameters);
287 }
288 break;
289 }
290 }
b557a801 291
6d877d9b 292 path = absolute_from_relative(path);
3579deea 293
9e403697
JM
294 DIR *d;
295 struct dirent *p;
3579deea 296 d = opendir(path.c_str());
9e403697
JM
297 if (d != NULL) {
298 while ((p = readdir(d)) != NULL) {
3579deea 299 stream->printf("%s", lc(string(p->d_name)).c_str());
6d877d9b 300 if(p->d_isdir) {
3579deea 301 stream->printf("/");
6d877d9b 302 } else if(opts.find("-s", 0, 2) != string::npos) {
3579deea
JM
303 stream->printf(" %d", p->d_fsize);
304 }
305 stream->printf("\r\n");
9e403697 306 }
ed7c5844 307 closedir(d);
0325af12 308 } else {
3579deea 309 stream->printf("Could not open directory %s\r\n", path.c_str());
0325af12
AW
310 }
311}
312
3704585b 313extern SDFAT mounter;
314
315void SimpleShell::remount_command( string parameters, StreamOutput *stream )
316{
317 mounter.remount();
48afc62a 318 stream->printf("remounted\r\n");
12fb447a 319}
3704585b 320
9e403697
JM
321// Delete a file
322void SimpleShell::rm_command( string parameters, StreamOutput *stream )
323{
6d877d9b 324 const char *fn = absolute_from_relative(shift_parameter( parameters )).c_str();
9e403697
JM
325 int s = remove(fn);
326 if (s != 0) stream->printf("Could not delete %s \r\n", fn);
327}
328
6d877d9b
JM
329// Rename a file
330void SimpleShell::mv_command( string parameters, StreamOutput *stream )
331{
332 string from = absolute_from_relative(shift_parameter( parameters ));
a940483b 333 string to = absolute_from_relative(shift_parameter(parameters));
6d877d9b
JM
334 int s = rename(from.c_str(), to.c_str());
335 if (s != 0) stream->printf("Could not rename %s to %s\r\n", from.c_str(), to.c_str());
336 else stream->printf("renamed %s to %s\r\n", from.c_str(), to.c_str());
337}
338
0325af12 339// Change current absolute path to provided path
9e403697
JM
340void SimpleShell::cd_command( string parameters, StreamOutput *stream )
341{
75f4581c 342 string folder = absolute_from_relative( parameters );
6bcd4886 343
0325af12 344 DIR *d;
0325af12 345 d = opendir(folder.c_str());
9e403697 346 if (d == NULL) {
58baeec1 347 stream->printf("Could not open directory %s \r\n", folder.c_str() );
9e403697 348 } else {
75f4581c 349 THEKERNEL->current_path = folder;
ed7c5844 350 closedir(d);
0325af12
AW
351 }
352}
353
b7250484 354// Responds with the present working directory
9e403697
JM
355void SimpleShell::pwd_command( string parameters, StreamOutput *stream )
356{
75f4581c 357 stream->printf("%s\r\n", THEKERNEL->current_path.c_str());
b7250484
L
358}
359
0325af12 360// Output the contents of a file, first parameter is the filename, second is the limit ( in number of lines to output )
9e403697
JM
361void SimpleShell::cat_command( string parameters, StreamOutput *stream )
362{
58baeec1 363 // Get parameters ( filename and line limit )
75f4581c 364 string filename = absolute_from_relative(shift_parameter( parameters ));
1f61f177 365 string limit_parameter = shift_parameter( parameters );
0325af12 366 int limit = -1;
1f61f177 367 int delay= 0;
2ab3fca6 368 bool send_eof= false;
1f61f177
JM
369 if ( limit_parameter == "-d" ) {
370 string d= shift_parameter( parameters );
9e403697 371 char *e = NULL;
1f61f177 372 delay = strtol(d.c_str(), &e, 10);
01e97c58 373 if (e <= d.c_str()) {
1f61f177
JM
374 delay = 0;
375
01e97c58
JM
376 } else {
377 send_eof= true; // we need to terminate file send with an eof
378 }
379
1f61f177
JM
380 }else if ( limit_parameter != "" ) {
381 char *e = NULL;
382 limit = strtol(limit_parameter.c_str(), &e, 10);
383 if (e <= limit_parameter.c_str())
f7e6f459
MM
384 limit = -1;
385 }
58baeec1 386
1f61f177 387 // we have been asked to delay before cat, probably to allow time to issue upload command
1aa3d42f
JM
388 if(delay > 0) {
389 safe_delay(delay*1000);
1f61f177
JM
390 }
391
58baeec1 392 // Open file
0325af12 393 FILE *lp = fopen(filename.c_str(), "r");
9e403697 394 if (lp == NULL) {
58baeec1
MM
395 stream->printf("File not found: %s\r\n", filename.c_str());
396 return;
9ed670c5 397 }
0325af12
AW
398 string buffer;
399 int c;
58baeec1 400 int newlines = 0;
6d877d9b 401 int linecnt = 0;
0325af12 402 // Print each line of the file
9e403697 403 while ((c = fgetc (lp)) != EOF) {
58baeec1 404 buffer.append((char *)&c, 1);
2ab3fca6
JM
405 if ( c == '\n' || ++linecnt > 80) {
406 if(c == '\n') newlines++;
d728799b 407 stream->puts(buffer.c_str());
58baeec1 408 buffer.clear();
6d877d9b 409 if(linecnt > 80) linecnt = 0;
6757ce1a
JM
410 // we need to kick things or they die
411 THEKERNEL->call_event(ON_IDLE);
68b7afb4 412 }
9e403697
JM
413 if ( newlines == limit ) {
414 break;
415 }
58baeec1 416 };
0325af12 417 fclose(lp);
2ab3fca6
JM
418
419 if(send_eof) {
420 stream->puts("\032"); // ^Z terminates the upload
421 }
6d877d9b
JM
422}
423
424void SimpleShell::upload_command( string parameters, StreamOutput *stream )
425{
426 // this needs to be a hack. it needs to read direct from serial and not allow on_main_loop run until done
427 // NOTE this will block all operation until the upload is complete, so do not do while printing
7baa50df 428 if(!THECONVEYOR->is_idle()) {
6d877d9b
JM
429 stream->printf("upload not allowed while printing or busy\n");
430 return;
431 }
432
433 // open file to upload to
434 string upload_filename = absolute_from_relative( parameters );
435 FILE *fd = fopen(upload_filename.c_str(), "w");
436 if(fd != NULL) {
437 stream->printf("uploading to file: %s, send control-D or control-Z to finish\r\n", upload_filename.c_str());
438 } else {
439 stream->printf("failed to open file: %s.\r\n", upload_filename.c_str());
440 return;
441 }
0325af12 442
6d877d9b
JM
443 int cnt = 0;
444 bool uploading = true;
445 while(uploading) {
446 if(!stream->ready()) {
447 // we need to kick things or they die
448 THEKERNEL->call_event(ON_IDLE);
449 continue;
450 }
451
452 char c = stream->_getc();
453 if( c == 4 || c == 26) { // ctrl-D or ctrl-Z
454 uploading = false;
455 // close file
456 fclose(fd);
457 stream->printf("uploaded %d bytes\n", cnt);
458 return;
459
460 } else {
461 // write character to file
462 cnt++;
463 if(fputc(c, fd) != c) {
464 // error writing to file
465 stream->printf("error writing to file. ignoring all characters until EOF\r\n");
466 fclose(fd);
467 fd = NULL;
468 uploading= false;
469
470 } else {
471 if ((cnt%400) == 0) {
472 // HACK ALERT to get around fwrite corruption close and re open for append
473 fclose(fd);
474 fd = fopen(upload_filename.c_str(), "a");
6757ce1a
JM
475 // we need to kick things or they die
476 THEKERNEL->call_event(ON_IDLE);
6d877d9b
JM
477 }
478 }
479 }
480 }
481 // we got an error so ignore everything until EOF
482 char c;
483 do {
484 if(stream->ready()) {
485 c= stream->_getc();
486 }else{
487 THEKERNEL->call_event(ON_IDLE);
488 c= 0;
489 }
490 } while(c != 4 && c != 26);
0325af12
AW
491}
492
618c9b0f
JM
493// loads the specified config-override file
494void SimpleShell::load_command( string parameters, StreamOutput *stream )
495{
496 // Get parameters ( filename )
75f4581c 497 string filename = absolute_from_relative(parameters);
618c9b0f
JM
498 if(filename == "/") {
499 filename = THEKERNEL->config_override_filename();
500 }
501
6d877d9b 502 FILE *fp = fopen(filename.c_str(), "r");
618c9b0f
JM
503 if(fp != NULL) {
504 char buf[132];
505 stream->printf("Loading config override file: %s...\n", filename.c_str());
506 while(fgets(buf, sizeof buf, fp) != NULL) {
507 stream->printf(" %s", buf);
508 if(buf[0] == ';') continue; // skip the comments
c0b50fa8
JM
509 // NOTE only Gcodes and Mcodes can be in the config-override
510 Gcode *gcode = new Gcode(buf, &StreamOutput::NullStream);
511 THEKERNEL->call_event(ON_GCODE_RECEIVED, gcode);
512 delete gcode;
513 THEKERNEL->call_event(ON_IDLE);
618c9b0f
JM
514 }
515 stream->printf("config override file executed\n");
516 fclose(fp);
517
6d877d9b 518 } else {
618c9b0f
JM
519 stream->printf("File not found: %s\n", filename.c_str());
520 }
521}
522
523// saves the specified config-override file
524void SimpleShell::save_command( string parameters, StreamOutput *stream )
525{
526 // Get parameters ( filename )
75f4581c 527 string filename = absolute_from_relative(parameters);
618c9b0f
JM
528 if(filename == "/") {
529 filename = THEKERNEL->config_override_filename();
530 }
531
23eb804b
JM
532 THEKERNEL->conveyor->wait_for_empty_queue(); //just to be safe as it can take a while to run
533
06afe68b
JM
534 //remove(filename.c_str()); // seems to cause a hang every now and then
535 {
536 FileStream fs(filename.c_str());
537 fs.printf("; DO NOT EDIT THIS FILE\n");
538 // this also will truncate the existing file instead of deleting it
539 }
540
23eb804b 541 // stream that appends to file
4fed9ba1
JM
542 AppendFileStream *gs = new AppendFileStream(filename.c_str());
543 // if(!gs->is_open()) {
544 // stream->printf("Unable to open File %s for write\n", filename.c_str());
545 // return;
546 // }
618c9b0f 547
7acfedab 548 __disable_irq();
618c9b0f
JM
549 // issue a M500 which will store values in the file stream
550 Gcode *gcode = new Gcode("M500", gs);
551 THEKERNEL->call_event(ON_GCODE_RECEIVED, gcode );
552 delete gs;
553 delete gcode;
7acfedab 554 __enable_irq();
618c9b0f
JM
555
556 stream->printf("Settings Stored to %s\r\n", filename.c_str());
557}
558
6187a020 559// show free memory
9e403697
JM
560void SimpleShell::mem_command( string parameters, StreamOutput *stream)
561{
078f76e0 562 bool verbose = shift_parameter( parameters ).find_first_of("Vv") != string::npos;
9e403697
JM
563 unsigned long heap = (unsigned long)_sbrk(0);
564 unsigned long m = g_maximumHeapAddress - heap;
ecc610a4
JM
565 stream->printf("Unused Heap: %lu bytes\r\n", m);
566
6d877d9b 567 uint32_t f = heapWalk(stream, verbose);
0c683b26 568 stream->printf("Total Free RAM: %lu bytes\r\n", m + f);
a200fc31 569
0c683b26 570 stream->printf("Free AHB0: %lu, AHB1: %lu\r\n", AHB0.free(), AHB1.free());
6d877d9b 571 if (verbose) {
1803076a
MM
572 AHB0.debug(stream);
573 AHB1.debug(stream);
574 }
8a9f9313
JM
575
576 stream->printf("Block size: %u bytes\n", sizeof(Block));
6187a020
JM
577}
578
9e403697
JM
579static uint32_t getDeviceType()
580{
581#define IAP_LOCATION 0x1FFF1FF1
01f35bcc
JM
582 uint32_t command[1];
583 uint32_t result[5];
9e403697 584 typedef void (*IAP)(uint32_t *, uint32_t *);
01f35bcc
JM
585 IAP iap = (IAP) IAP_LOCATION;
586
587 __disable_irq();
588
589 command[0] = 54;
590 iap(command, result);
591
592 __enable_irq();
593
594 return result[1];
595}
596
d4ee6ee2
JM
597// get network config
598void SimpleShell::net_command( string parameters, StreamOutput *stream)
599{
600 void *returned_data;
6d877d9b 601 bool ok = PublicData::get_value( network_checksum, get_ipconfig_checksum, &returned_data );
d4ee6ee2 602 if(ok) {
6d877d9b 603 char *str = (char *)returned_data;
d4ee6ee2
JM
604 stream->printf("%s\r\n", str);
605 free(str);
606
6d877d9b 607 } else {
d4ee6ee2
JM
608 stream->printf("No network detected\n");
609 }
610}
611
582559c6 612// print out build version
9e403697
JM
613void SimpleShell::version_command( string parameters, StreamOutput *stream)
614{
582559c6 615 Version vers;
9e403697
JM
616 uint32_t dev = getDeviceType();
617 const char *mcu = (dev & 0x00100000) ? "LPC1769" : "LPC1768";
01f35bcc 618 stream->printf("Build version: %s, Build date: %s, MCU: %s, System Clock: %ldMHz\r\n", vers.get_build(), vers.get_build_date(), mcu, SystemCoreClock / 1000000);
599cb4bd
JM
619 #ifdef CNC
620 stream->printf(" CNC Build\r\n");
621 #endif
582559c6
JM
622}
623
77983aa1 624// Reset the system
9e403697
JM
625void SimpleShell::reset_command( string parameters, StreamOutput *stream)
626{
ead17727 627 stream->printf("Smoothie out. Peace. Rebooting in 5 seconds...\r\n");
7e81f138 628 reset_delay_secs = 5; // reboot in 5 seconds
2742fca9
JM
629}
630
631// go into dfu boot mode
9e403697
JM
632void SimpleShell::dfu_command( string parameters, StreamOutput *stream)
633{
ed7c5844
JM
634 stream->printf("Entering boot mode...\r\n");
635 system_reset(true);
77983aa1
L
636}
637
0f0b1656 638// Break out into the MRI debugging system
9e403697
JM
639void SimpleShell::break_command( string parameters, StreamOutput *stream)
640{
0f0b1656
L
641 stream->printf("Entering MRI debug mode...\r\n");
642 __debugbreak();
643}
644
40843ebc
JM
645static int get_active_tool()
646{
335957f5 647 void *returned_data;
40843ebc
JM
648 bool ok = PublicData::get_value(tool_manager_checksum, get_active_tool_checksum, &returned_data);
649 if (ok) {
335957f5
JM
650 int active_tool= *static_cast<int *>(returned_data);
651 return active_tool;
40843ebc
JM
652 } else {
653 return 0;
654 }
655}
656
6c0193b3
JM
657void SimpleShell::grblDP_command( string parameters, StreamOutput *stream)
658{
659 /*
660 [G54:95.000,40.000,-23.600]
661 [G55:0.000,0.000,0.000]
662 [G56:0.000,0.000,0.000]
663 [G57:0.000,0.000,0.000]
664 [G58:0.000,0.000,0.000]
665 [G59:0.000,0.000,0.000]
666 [G28:0.000,0.000,0.000]
667 [G30:0.000,0.000,0.000]
668 [G92:0.000,0.000,0.000]
669 [TLO:0.000]
670 [PRB:0.000,0.000,0.000:0]
671 */
078f76e0
JM
672
673 bool verbose = shift_parameter( parameters ).find_first_of("Vv") != string::npos;
674
c8bac202 675 std::vector<Robot::wcs_t> v= THEROBOT->get_wcs_state();
078f76e0
JM
676 if(verbose) {
677 char current_wcs= std::get<0>(v[0]);
678 stream->printf("[current WCS: %s]\n", wcs2gcode(current_wcs).c_str());
679 }
680
6c0193b3
JM
681 int n= std::get<1>(v[0]);
682 for (int i = 1; i <= n; ++i) {
32bc8b54 683 stream->printf("[%s:%1.4f,%1.4f,%1.4f]\n", wcs2gcode(i-1).c_str(),
c8bac202
JM
684 THEROBOT->from_millimeters(std::get<0>(v[i])),
685 THEROBOT->from_millimeters(std::get<1>(v[i])),
686 THEROBOT->from_millimeters(std::get<2>(v[i])));
6c0193b3
JM
687 }
688
9339253b
JM
689 float *rd;
690 PublicData::get_value( endstops_checksum, saved_position_checksum, &rd );
32bc8b54 691 stream->printf("[G28:%1.4f,%1.4f,%1.4f]\n",
c8bac202
JM
692 THEROBOT->from_millimeters(rd[0]),
693 THEROBOT->from_millimeters(rd[1]),
694 THEROBOT->from_millimeters(rd[2]));
32bc8b54 695
31c6c2c2 696 stream->printf("[G30:%1.4f,%1.4f,%1.4f]\n", 0.0F, 0.0F, 0.0F); // not implemented
9339253b 697
32bc8b54 698 stream->printf("[G92:%1.4f,%1.4f,%1.4f]\n",
c8bac202
JM
699 THEROBOT->from_millimeters(std::get<0>(v[n+1])),
700 THEROBOT->from_millimeters(std::get<1>(v[n+1])),
701 THEROBOT->from_millimeters(std::get<2>(v[n+1])));
32bc8b54 702
078f76e0 703 if(verbose) {
32bc8b54 704 stream->printf("[Tool Offset:%1.4f,%1.4f,%1.4f]\n",
c8bac202
JM
705 THEROBOT->from_millimeters(std::get<0>(v[n+2])),
706 THEROBOT->from_millimeters(std::get<1>(v[n+2])),
707 THEROBOT->from_millimeters(std::get<2>(v[n+2])));
078f76e0 708 }else{
c8bac202 709 stream->printf("[TL0:%1.4f]\n", THEROBOT->from_millimeters(std::get<2>(v[n+2])));
078f76e0 710 }
6c0193b3 711
4440e123
JM
712 // this is the last probe position, updated when a probe completes, also stores the number of steps moved after a homing cycle
713 float px, py, pz;
714 uint8_t ps;
c8bac202
JM
715 std::tie(px, py, pz, ps) = THEROBOT->get_last_probe_position();
716 stream->printf("[PRB:%1.4f,%1.4f,%1.4f:%d]\n", THEROBOT->from_millimeters(px), THEROBOT->from_millimeters(py), THEROBOT->from_millimeters(pz), ps);
6c0193b3
JM
717}
718
9e403697
JM
719void SimpleShell::get_command( string parameters, StreamOutput *stream)
720{
7e81f138 721 string what = shift_parameter( parameters );
c4e56997 722
7e81f138 723 if (what == "temp") {
3bfb2639 724 struct pad_temperature temp;
9e403697 725 string type = shift_parameter( parameters );
56a6c8c1
JM
726 if(type.empty()) {
727 // scan all temperature controls
728 std::vector<struct pad_temperature> controllers;
729 bool ok = PublicData::get_value(temperature_control_checksum, poll_controls_checksum, &controllers);
730 if (ok) {
731 for (auto &c : controllers) {
732 stream->printf("%s (%d) temp: %f/%f @%d\r\n", c.designator.c_str(), c.id, c.current_temperature, c.target_temperature, c.pwm);
733 }
b55cfff1 734
56a6c8c1
JM
735 } else {
736 stream->printf("no heaters found\r\n");
737 }
738
739 }else{
740 bool ok = PublicData::get_value( temperature_control_checksum, current_temperature_checksum, get_checksum(type), &temp );
741
742 if (ok) {
743 stream->printf("%s temp: %f/%f @%d\r\n", type.c_str(), temp.current_temperature, temp.target_temperature, temp.pwm);
744 } else {
745 stream->printf("%s is not a known temperature device\r\n", type.c_str());
746 }
b55cfff1 747 }
c4e56997 748
70021ec9 749 } else if (what == "fk" || what == "ik") {
2577a122 750 string p= shift_parameter( parameters );
70021ec9 751 bool move= false;
8ff7a960 752 if(p == "-m") {
70021ec9
JM
753 move= true;
754 p= shift_parameter( parameters );
755 }
756
757 std::vector<float> v= parse_number_list(p.c_str());
586cc733
JM
758 if(p.empty() || v.size() < 1) {
759 stream->printf("error:usage: get [fk|ik] [-m] x[,y,z]\n");
70021ec9
JM
760 return;
761 }
2577a122 762
70021ec9 763 float x= v[0];
586cc733
JM
764 float y= (v.size() > 1) ? v[1] : x;
765 float z= (v.size() > 2) ? v[2] : y;
70021ec9
JM
766
767 if(what == "fk") {
8ff7a960 768 // do forward kinematics on the given actuator position and display the cartesian coordinates
70021ec9
JM
769 ActuatorCoordinates apos{x, y, z};
770 float pos[3];
c8bac202 771 THEROBOT->arm_solution->actuator_to_cartesian(apos, pos);
586cc733
JM
772 stream->printf("cartesian= X %f, Y %f, Z %f, Steps= A %lu, B %lu, C %lu\n",
773 pos[0], pos[1], pos[2],
c8bac202
JM
774 lroundf(x*THEROBOT->actuators[0]->get_steps_per_mm()),
775 lroundf(y*THEROBOT->actuators[1]->get_steps_per_mm()),
776 lroundf(z*THEROBOT->actuators[2]->get_steps_per_mm()));
70021ec9
JM
777 x= pos[0];
778 y= pos[1];
779 z= pos[2];
8ff7a960 780
70021ec9 781 }else{
8ff7a960 782 // do inverse kinematics on the given cartesian position and display the actuator coordinates
70021ec9
JM
783 float pos[3]{x, y, z};
784 ActuatorCoordinates apos;
c8bac202 785 THEROBOT->arm_solution->cartesian_to_actuator(pos, apos);
70021ec9
JM
786 stream->printf("actuator= A %f, B %f, C %f\n", apos[0], apos[1], apos[2]);
787 }
788
789 if(move) {
8ff7a960 790 // move to the calculated, or given, XYZ
70021ec9
JM
791 char cmd[64];
792 snprintf(cmd, sizeof(cmd), "G53 G0 X%f Y%f Z%f", x, y, z);
793 struct SerialMessage message;
794 message.message = cmd;
795 message.stream = &(StreamOutput::NullStream);
796 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
797 THEKERNEL->conveyor->wait_for_empty_queue();
798 }
2577a122
JM
799
800 } else if (what == "pos") {
e03f2747
JM
801 // convenience to call all the various M114 variants
802 char buf[64];
c8bac202
JM
803 THEROBOT->print_position(0, buf, sizeof buf); stream->printf("last %s\n", buf);
804 THEROBOT->print_position(1, buf, sizeof buf); stream->printf("realtime %s\n", buf);
805 THEROBOT->print_position(2, buf, sizeof buf); stream->printf("%s\n", buf);
806 THEROBOT->print_position(3, buf, sizeof buf); stream->printf("%s\n", buf);
807 THEROBOT->print_position(4, buf, sizeof buf); stream->printf("%s\n", buf);
808 THEROBOT->print_position(5, buf, sizeof buf); stream->printf("%s\n", buf);
34210908
JM
809
810 } else if (what == "wcs") {
811 // print the wcs state
078f76e0 812 grblDP_command("-v", stream);
40843ebc
JM
813
814 } else if (what == "state") {
6c0193b3 815 // also $G
40843ebc 816 // [G0 G54 G17 G21 G90 G94 M0 M5 M9 T0 F0.]
31c6c2c2 817 stream->printf("[G%d %s G%d G%d G%d G94 M0 M5 M9 T%d F%1.4f]\n",
40843ebc 818 THEKERNEL->gcode_dispatch->get_modal_command(),
c8bac202
JM
819 wcs2gcode(THEROBOT->get_current_wcs()).c_str(),
820 THEROBOT->plane_axis_0 == X_AXIS && THEROBOT->plane_axis_1 == Y_AXIS && THEROBOT->plane_axis_2 == Z_AXIS ? 17 :
821 THEROBOT->plane_axis_0 == X_AXIS && THEROBOT->plane_axis_1 == Z_AXIS && THEROBOT->plane_axis_2 == Y_AXIS ? 18 :
822 THEROBOT->plane_axis_0 == Y_AXIS && THEROBOT->plane_axis_1 == Z_AXIS && THEROBOT->plane_axis_2 == X_AXIS ? 19 : 17,
823 THEROBOT->inch_mode ? 20 : 21,
824 THEROBOT->absolute_mode ? 90 : 91,
40843ebc 825 get_active_tool(),
c8bac202 826 THEROBOT->from_millimeters(THEROBOT->get_feed_rate()));
6c0193b3 827
a9e8c04b
JM
828 } else if (what == "status") {
829 // also ? on serial and usb
830 stream->printf("%s\n", THEKERNEL->get_query_string().c_str());
831
6c0193b3 832 } else {
07186543 833 stream->printf("error:unknown option %s\n", what.c_str());
b55cfff1 834 }
8293d443
JM
835}
836
77047e76 837// used to test out the get public data events
9e403697
JM
838void SimpleShell::set_temp_command( string parameters, StreamOutput *stream)
839{
840 string type = shift_parameter( parameters );
841 string temp = shift_parameter( parameters );
04211969 842 float t = temp.empty() ? 0.0 : strtof(temp.c_str(), NULL);
75e6428d 843 bool ok = PublicData::set_value( temperature_control_checksum, get_checksum(type), &t );
991d98cc 844
9e403697 845 if (ok) {
991d98cc 846 stream->printf("%s temp set to: %3.1f\r\n", type.c_str(), t);
9e403697 847 } else {
991d98cc
JM
848 stream->printf("%s is not a known temperature device\r\n", type.c_str());
849 }
77047e76
JM
850}
851
4c8f5447
JM
852void SimpleShell::print_thermistors_command( string parameters, StreamOutput *stream)
853{
8b260c2c 854 #ifndef NO_TOOLS_TEMPERATURECONTROL
4c8f5447 855 Thermistor::print_predefined_thermistors(stream);
8b260c2c 856 #endif
4c8f5447
JM
857}
858
1f8dab1a
JM
859void SimpleShell::calc_thermistor_command( string parameters, StreamOutput *stream)
860{
8b260c2c 861 #ifndef NO_TOOLS_TEMPERATURECONTROL
bbb839c1
JM
862 string s = shift_parameter( parameters );
863 int saveto= -1;
864 // see if we have -sn as first argument
865 if(s.find("-s", 0, 2) != string::npos) {
866 // save the results to thermistor n
867 saveto= strtol(s.substr(2).c_str(), nullptr, 10);
868 }else{
869 parameters= s;
870 }
871
1f8dab1a
JM
872 std::vector<float> trl= parse_number_list(parameters.c_str());
873 if(trl.size() == 6) {
874 // calculate the coefficients
875 float c1, c2, c3;
876 std::tie(c1, c2, c3) = Thermistor::calculate_steinhart_hart_coefficients(trl[0], trl[1], trl[2], trl[3], trl[4], trl[5]);
877 stream->printf("Steinhart Hart coefficients: I%1.18f J%1.18f K%1.18f\n", c1, c2, c3);
bbb839c1
JM
878 if(saveto == -1) {
879 stream->printf(" Paste the above in the M305 S0 command, then save with M500\n");
880 }else{
881 char buf[80];
882 int n = snprintf(buf, sizeof(buf), "M305 S%d I%1.18f J%1.18f K%1.18f", saveto, c1, c2, c3);
883 string g(buf, n);
884 Gcode gcode(g, &(StreamOutput::NullStream));
885 THEKERNEL->call_event(ON_GCODE_RECEIVED, &gcode );
886 stream->printf(" Setting Thermistor %d to those settings, save with M500\n", saveto);
887 }
1f8dab1a
JM
888
889 }else{
890 // give help
891 stream->printf("Usage: calc_thermistor T1,R1,T2,R2,T3,R3\n");
892 }
8b260c2c 893 #endif
1f8dab1a
JM
894}
895
ae91dea4
JM
896// used to test out the get public data events for switch
897void SimpleShell::switch_command( string parameters, StreamOutput *stream)
898{
899 string type = shift_parameter( parameters );
900 string value = shift_parameter( parameters );
6d877d9b 901 bool ok = false;
ae91dea4 902 if(value == "on" || value == "off") {
6d877d9b 903 bool b = value == "on";
ae91dea4 904 ok = PublicData::set_value( switch_checksum, get_checksum(type), state_checksum, &b );
6d877d9b 905 } else {
ae91dea4
JM
906 float v = strtof(value.c_str(), NULL);
907 ok = PublicData::set_value( switch_checksum, get_checksum(type), value_checksum, &v );
908 }
909 if (ok) {
910 stream->printf("switch %s set to: %s\r\n", type.c_str(), value.c_str());
911 } else {
912 stream->printf("%s is not a known switch device\r\n", type.c_str());
913 }
914}
915
d55d551b
JM
916void SimpleShell::md5sum_command( string parameters, StreamOutput *stream )
917{
918 string filename = absolute_from_relative(parameters);
919
920 // Open file
921 FILE *lp = fopen(filename.c_str(), "r");
922 if (lp == NULL) {
923 stream->printf("File not found: %s\r\n", filename.c_str());
924 return;
925 }
926 MD5 md5;
927 uint8_t buf[64];
928 do {
929 size_t n= fread(buf, 1, sizeof buf, lp);
930 if(n > 0) md5.update(buf, n);
2a95b07e 931 THEKERNEL->call_event(ON_IDLE);
d55d551b
JM
932 } while(!feof(lp));
933
934 stream->printf("%s %s\n", md5.finalize().hexdigest().c_str(), filename.c_str());
935 fclose(lp);
936}
937
b03317ea 938#ifdef CNC
518b5c4c
JM
939// runs several types of test on the mechanisms
940void SimpleShell::test_command( string parameters, StreamOutput *stream)
941{
942 string what = shift_parameter( parameters );
943
944 if (what == "jog") {
945 // jogs back and forth usage: axis distance iterations [feedrate]
946 string axis = shift_parameter( parameters );
947 string dist = shift_parameter( parameters );
948 string iters = shift_parameter( parameters );
949 string speed = shift_parameter( parameters );
950 if(axis.empty() || dist.empty() || iters.empty()) {
951 stream->printf("error: Need axis distance iterations\n");
952 return;
953 }
954 float d= strtof(dist.c_str(), NULL);
c8bac202 955 float f= speed.empty() ? THEROBOT->get_feed_rate() : strtof(speed.c_str(), NULL);
518b5c4c
JM
956 uint32_t n= strtol(iters.c_str(), NULL, 10);
957
958 bool toggle= false;
959 for (uint32_t i = 0; i < n; ++i) {
960 char cmd[64];
a276de9c
JM
961 snprintf(cmd, sizeof(cmd), "G91 G0 %c%f F%f G90", toupper(axis[0]), toggle ? -d : d, f);
962 stream->printf("%s\n", cmd);
518b5c4c
JM
963 struct SerialMessage message{&StreamOutput::NullStream, cmd};
964 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
a276de9c 965 if(THEKERNEL->is_halted()) break;
e0b7aa0e 966 THEKERNEL->conveyor->wait_for_empty_queue();
518b5c4c
JM
967 toggle= !toggle;
968 }
a276de9c 969 stream->printf("done\n");
518b5c4c
JM
970
971 }else if (what == "circle") {
fb4c9d09 972 // draws a circle around origin. usage: radius iterations [feedrate]
e0b7aa0e 973 string radius = shift_parameter( parameters );
e0b7aa0e
JM
974 string iters = shift_parameter( parameters );
975 string speed = shift_parameter( parameters );
fb4c9d09
JM
976 if(radius.empty() || iters.empty()) {
977 stream->printf("error: Need radius iterations\n");
e0b7aa0e
JM
978 return;
979 }
980
981 float r= strtof(radius.c_str(), NULL);
e0b7aa0e 982 uint32_t n= strtol(iters.c_str(), NULL, 10);
c8bac202 983 float f= speed.empty() ? THEROBOT->get_feed_rate() : strtof(speed.c_str(), NULL);
fb4c9d09 984
ee602f65 985 char cmd[64];
fb4c9d09
JM
986 snprintf(cmd, sizeof(cmd), "G0 X%f Y0 F%f", -r, f);
987 stream->printf("%s\n", cmd);
ee602f65
JM
988 struct SerialMessage message{&StreamOutput::NullStream, cmd};
989 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
e0b7aa0e
JM
990
991 for (uint32_t i = 0; i < n; ++i) {
a276de9c 992 if(THEKERNEL->is_halted()) break;
fb4c9d09
JM
993 snprintf(cmd, sizeof(cmd), "G2 X%f Y0 I%f J0 F%f", -r, r, f);
994 stream->printf("%s\n", cmd);
995 message.message= cmd;
996 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
e0b7aa0e
JM
997 THEKERNEL->conveyor->wait_for_empty_queue();
998 }
a276de9c 999 stream->printf("done\n");
518b5c4c
JM
1000
1001 }else if (what == "square") {
1002 // draws a square usage: size iterations [feedrate]
1003 string size = shift_parameter( parameters );
1004 string iters = shift_parameter( parameters );
1005 string speed = shift_parameter( parameters );
1006 if(size.empty() || iters.empty()) {
1007 stream->printf("error: Need size iterations\n");
1008 return;
1009 }
1010 float d= strtof(size.c_str(), NULL);
c8bac202 1011 float f= speed.empty() ? THEROBOT->get_feed_rate() : strtof(speed.c_str(), NULL);
518b5c4c
JM
1012 uint32_t n= strtol(iters.c_str(), NULL, 10);
1013
1014 for (uint32_t i = 0; i < n; ++i) {
1015 char cmd[64];
1016 {
1017 snprintf(cmd, sizeof(cmd), "G91 G0 X%f F%f", d, f);
a276de9c 1018 stream->printf("%s\n", cmd);
518b5c4c
JM
1019 struct SerialMessage message{&StreamOutput::NullStream, cmd};
1020 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
1021 }
1022 {
e0b7aa0e 1023 snprintf(cmd, sizeof(cmd), "G0 Y%f", d);
a276de9c 1024 stream->printf("%s\n", cmd);
518b5c4c
JM
1025 struct SerialMessage message{&StreamOutput::NullStream, cmd};
1026 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
1027 }
1028 {
e0b7aa0e 1029 snprintf(cmd, sizeof(cmd), "G0 X%f", -d);
a276de9c 1030 stream->printf("%s\n", cmd);
518b5c4c
JM
1031 struct SerialMessage message{&StreamOutput::NullStream, cmd};
1032 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
1033 }
1034 {
e0b7aa0e 1035 snprintf(cmd, sizeof(cmd), "G0 Y%f G90", -d);
a276de9c 1036 stream->printf("%s\n", cmd);
518b5c4c
JM
1037 struct SerialMessage message{&StreamOutput::NullStream, cmd};
1038 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
1039 }
a276de9c 1040 if(THEKERNEL->is_halted()) break;
e0b7aa0e 1041 THEKERNEL->conveyor->wait_for_empty_queue();
518b5c4c 1042 }
a276de9c 1043 stream->printf("done\n");
d55d551b 1044
a276de9c
JM
1045 }else {
1046 stream->printf("usage:\n test jog axis distance iterations [feedrate]\n");
1047 stream->printf(" test square size iterations [feedrate]\n");
fb4c9d09 1048 stream->printf(" test circle radius iterations [feedrate]\n");
518b5c4c
JM
1049 }
1050}
b03317ea 1051#endif
d55d551b 1052
9e403697
JM
1053void SimpleShell::help_command( string parameters, StreamOutput *stream )
1054{
ed7c5844 1055 stream->printf("Commands:\r\n");
582559c6 1056 stream->printf("version\r\n");
ecc610a4 1057 stream->printf("mem [-v]\r\n");
3579deea 1058 stream->printf("ls [-s] [folder]\r\n");
ed7c5844 1059 stream->printf("cd folder\r\n");
c4e56997 1060 stream->printf("pwd\r\n");
6c0193b3 1061 stream->printf("cat file [limit] [-d 10]\r\n");
9e403697 1062 stream->printf("rm file\r\n");
6d877d9b 1063 stream->printf("mv file newfile\r\n");
12fb447a 1064 stream->printf("remount\r\n");
4eb0e279 1065 stream->printf("play file [-v]\r\n");
ed7c5844
JM
1066 stream->printf("progress - shows progress of current play\r\n");
1067 stream->printf("abort - abort currently playing file\r\n");
c4e56997
JM
1068 stream->printf("reset - reset smoothie\r\n");
1069 stream->printf("dfu - enter dfu boot loader\r\n");
1070 stream->printf("break - break into debugger\r\n");
ed7c5844
JM
1071 stream->printf("config-get [<configuration_source>] <configuration_setting>\r\n");
1072 stream->printf("config-set [<configuration_source>] <configuration_setting> <value>\r\n");
a9e8c04b 1073 stream->printf("get [pos|wcs|state|status|fk|ik]\r\n");
5647f709 1074 stream->printf("get temp [bed|hotend]\r\n");
991d98cc 1075 stream->printf("set_temp bed|hotend 185\r\n");
d4ee6ee2 1076 stream->printf("net\r\n");
618c9b0f
JM
1077 stream->printf("load [file] - loads a configuration override file from soecified name or config-override\r\n");
1078 stream->printf("save [file] - saves a configuration override file as specified filename or as config-override\r\n");
bbb839c1
JM
1079 stream->printf("upload filename - saves a stream of text to the named file\r\n");
1080 stream->printf("calc_thermistor [-s0] T1,R1,T2,R2,T3,R3 - calculate the Steinhart Hart coefficients for a thermistor\r\n");
4c8f5447 1081 stream->printf("thermistors - print out the predefined thermistors\r\n");
d55d551b 1082 stream->printf("md5sum file - prints md5 sum of the given file\r\n");
235a7435
JM
1083}
1084