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