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