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