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