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