Merge remote-tracking branch 'upstream/edge' into feature/correct-rotarydelta-homing
[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
85 // unknown command
86 {NULL, NULL}
87 };
88
89 int SimpleShell::reset_delay_secs = 0;
90
91 // Adam Greens heap walk from http://mbed.org/forum/mbed/topic/2701/?page=4#comment-22556
92 static uint32_t heapWalk(StreamOutput *stream, bool verbose)
93 {
94 uint32_t chunkNumber = 1;
95 // The __end__ linker symbol points to the beginning of the heap.
96 uint32_t chunkCurr = (uint32_t)&__end__;
97 // __malloc_free_list is the head pointer to newlib-nano's link list of free chunks.
98 uint32_t freeCurr = __malloc_free_list;
99 // Calling _sbrk() with 0 reserves no more memory but it returns the current top of heap.
100 uint32_t heapEnd = _sbrk(0);
101 // accumulate totals
102 uint32_t freeSize = 0;
103 uint32_t usedSize = 0;
104
105 stream->printf("Used Heap Size: %lu\n", heapEnd - chunkCurr);
106
107 // Walk through the chunks until we hit the end of the heap.
108 while (chunkCurr < heapEnd) {
109 // Assume the chunk is in use. Will update later.
110 int isChunkFree = 0;
111 // The first 32-bit word in a chunk is the size of the allocation. newlib-nano over allocates by 8 bytes.
112 // 4 bytes for this 32-bit chunk size and another 4 bytes to allow for 8 byte-alignment of returned pointer.
113 uint32_t chunkSize = *(uint32_t *)chunkCurr;
114 // The start of the next chunk is right after the end of this one.
115 uint32_t chunkNext = chunkCurr + chunkSize;
116
117 // The free list is sorted by address.
118 // Check to see if we have found the next free chunk in the heap.
119 if (chunkCurr == freeCurr) {
120 // Chunk is free so flag it as such.
121 isChunkFree = 1;
122 // The second 32-bit word in a free chunk is a pointer to the next free chunk (again sorted by address).
123 freeCurr = *(uint32_t *)(freeCurr + 4);
124 }
125
126 // Skip past the 32-bit size field in the chunk header.
127 chunkCurr += 4;
128 // 8-byte align the data pointer.
129 chunkCurr = (chunkCurr + 7) & ~7;
130 // newlib-nano over allocates by 8 bytes, 4 bytes for the 32-bit chunk size and another 4 bytes to allow for 8
131 // byte-alignment of the returned pointer.
132 chunkSize -= 8;
133 if (verbose)
134 stream->printf(" Chunk: %lu Address: 0x%08lX Size: %lu %s\n", chunkNumber, chunkCurr, chunkSize, isChunkFree ? "CHUNK FREE" : "");
135
136 if (isChunkFree) freeSize += chunkSize;
137 else usedSize += chunkSize;
138
139 chunkCurr = chunkNext;
140 chunkNumber++;
141 }
142 stream->printf("Allocated: %lu, Free: %lu\r\n", usedSize, freeSize);
143 return freeSize;
144 }
145
146
147 void SimpleShell::on_module_loaded()
148 {
149 this->register_for_event(ON_CONSOLE_LINE_RECEIVED);
150 this->register_for_event(ON_GCODE_RECEIVED);
151 this->register_for_event(ON_SECOND_TICK);
152
153 reset_delay_secs = 0;
154 }
155
156 void SimpleShell::on_second_tick(void *)
157 {
158 // we are timing out for the reset
159 if (reset_delay_secs > 0) {
160 if (--reset_delay_secs == 0) {
161 system_reset(false);
162 }
163 }
164 }
165
166 void SimpleShell::on_gcode_received(void *argument)
167 {
168 Gcode *gcode = static_cast<Gcode *>(argument);
169 string args = get_arguments(gcode->get_command());
170
171 if (gcode->has_m) {
172 if (gcode->m == 20) { // list sd card
173 gcode->stream->printf("Begin file list\r\n");
174 ls_command("/sd", gcode->stream);
175 gcode->stream->printf("End file list\r\n");
176
177 } else if (gcode->m == 30) { // remove file
178 rm_command("/sd/" + args, gcode->stream);
179
180 } else if(gcode->m == 501) { // load config override
181 if(args.empty()) {
182 load_command("/sd/config-override", gcode->stream);
183 } else {
184 load_command("/sd/config-override." + args, gcode->stream);
185 }
186
187 } else if(gcode->m == 504) { // save to specific config override file
188 if(args.empty()) {
189 save_command("/sd/config-override", gcode->stream);
190 } else {
191 save_command("/sd/config-override." + args, gcode->stream);
192 }
193 }
194 }
195 }
196
197 bool SimpleShell::parse_command(const char *cmd, string args, StreamOutput *stream)
198 {
199 for (const ptentry_t *p = commands_table; p->command != NULL; ++p) {
200 if (strncasecmp(cmd, p->command, strlen(p->command)) == 0) {
201 p->func(args, stream);
202 return true;
203 }
204 }
205
206 return false;
207 }
208
209 // When a new line is received, check if it is a command, and if it is, act upon it
210 void SimpleShell::on_console_line_received( void *argument )
211 {
212 SerialMessage new_message = *static_cast<SerialMessage *>(argument);
213 string possible_command = new_message.message;
214
215 // ignore anything that is not lowercase or a $ as it is not a command
216 if(possible_command.size() == 0 || (!islower(possible_command[0]) && possible_command[0] != '$')) {
217 return;
218 }
219
220 // it is a grbl compatible command
221 if(possible_command[0] == '$' && possible_command.size() >= 2) {
222 switch(possible_command[1]) {
223 case 'G':
224 // issue get state
225 get_command("state", new_message.stream);
226 break;
227
228 case 'X':
229 THEKERNEL->call_event(ON_HALT, (void *)1); // clears on_halt
230 new_message.stream->printf("[Caution: Unlocked]\n");
231 break;
232
233 case '#':
234 grblDP_command("", new_message.stream);
235 break;
236
237 case 'H':
238 if(THEKERNEL->is_grbl_mode()) {
239 // issue G28.2 which is force homing cycle
240 Gcode gcode("G28.2", new_message.stream);
241 THEKERNEL->call_event(ON_GCODE_RECEIVED, &gcode);
242 }else{
243 new_message.stream->printf("error:only supported in GRBL mode\n");
244 }
245 break;
246
247 default:
248 new_message.stream->printf("error:Invalid statement\n");
249 break;
250 }
251
252 }else{
253
254 //new_message.stream->printf("Received %s\r\n", possible_command.c_str());
255 string cmd = shift_parameter(possible_command);
256
257 // Configurator commands
258 if (cmd == "config-get"){
259 THEKERNEL->configurator->config_get_command( possible_command, new_message.stream );
260
261 } else if (cmd == "config-set"){
262 THEKERNEL->configurator->config_set_command( possible_command, new_message.stream );
263
264 } else if (cmd == "config-load"){
265 THEKERNEL->configurator->config_load_command( possible_command, new_message.stream );
266
267 } else if (cmd == "play" || cmd == "progress" || cmd == "abort" || cmd == "suspend" || cmd == "resume") {
268 // handled in the Player.cpp module
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(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(!THEKERNEL->conveyor->is_queue_empty()) {
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 struct SerialMessage message = {&(StreamOutput::NullStream), buf};
513 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message);
514 }
515 stream->printf("config override file executed\n");
516 fclose(fp);
517
518 } else {
519 stream->printf("File not found: %s\n", filename.c_str());
520 }
521 }
522
523 // saves the specified config-override file
524 void SimpleShell::save_command( string parameters, StreamOutput *stream )
525 {
526 // Get parameters ( filename )
527 string filename = absolute_from_relative(parameters);
528 if(filename == "/") {
529 filename = THEKERNEL->config_override_filename();
530 }
531
532 THEKERNEL->conveyor->wait_for_empty_queue(); //just to be safe as it can take a while to run
533
534 //remove(filename.c_str()); // seems to cause a hang every now and then
535 {
536 FileStream fs(filename.c_str());
537 fs.printf("; DO NOT EDIT THIS FILE\n");
538 // this also will truncate the existing file instead of deleting it
539 }
540
541 // stream that appends to file
542 AppendFileStream *gs = new AppendFileStream(filename.c_str());
543 // if(!gs->is_open()) {
544 // stream->printf("Unable to open File %s for write\n", filename.c_str());
545 // return;
546 // }
547
548 __disable_irq();
549 // issue a M500 which will store values in the file stream
550 Gcode *gcode = new Gcode("M500", gs);
551 THEKERNEL->call_event(ON_GCODE_RECEIVED, gcode );
552 delete gs;
553 delete gcode;
554 __enable_irq();
555
556 stream->printf("Settings Stored to %s\r\n", filename.c_str());
557 }
558
559 // show free memory
560 void SimpleShell::mem_command( string parameters, StreamOutput *stream)
561 {
562 bool verbose = shift_parameter( parameters ).find_first_of("Vv") != string::npos ;
563 unsigned long heap = (unsigned long)_sbrk(0);
564 unsigned long m = g_maximumHeapAddress - heap;
565 stream->printf("Unused Heap: %lu bytes\r\n", m);
566
567 uint32_t f = heapWalk(stream, verbose);
568 stream->printf("Total Free RAM: %lu bytes\r\n", m + f);
569
570 stream->printf("Free AHB0: %lu, AHB1: %lu\r\n", AHB0.free(), AHB1.free());
571 if (verbose) {
572 AHB0.debug(stream);
573 AHB1.debug(stream);
574 }
575 }
576
577 static uint32_t getDeviceType()
578 {
579 #define IAP_LOCATION 0x1FFF1FF1
580 uint32_t command[1];
581 uint32_t result[5];
582 typedef void (*IAP)(uint32_t *, uint32_t *);
583 IAP iap = (IAP) IAP_LOCATION;
584
585 __disable_irq();
586
587 command[0] = 54;
588 iap(command, result);
589
590 __enable_irq();
591
592 return result[1];
593 }
594
595 // get network config
596 void SimpleShell::net_command( string parameters, StreamOutput *stream)
597 {
598 void *returned_data;
599 bool ok = PublicData::get_value( network_checksum, get_ipconfig_checksum, &returned_data );
600 if(ok) {
601 char *str = (char *)returned_data;
602 stream->printf("%s\r\n", str);
603 free(str);
604
605 } else {
606 stream->printf("No network detected\n");
607 }
608 }
609
610 // print out build version
611 void SimpleShell::version_command( string parameters, StreamOutput *stream)
612 {
613 Version vers;
614 uint32_t dev = getDeviceType();
615 const char *mcu = (dev & 0x00100000) ? "LPC1769" : "LPC1768";
616 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);
617 }
618
619 // Reset the system
620 void SimpleShell::reset_command( string parameters, StreamOutput *stream)
621 {
622 stream->printf("Smoothie out. Peace. Rebooting in 5 seconds...\r\n");
623 reset_delay_secs = 5; // reboot in 5 seconds
624 }
625
626 // go into dfu boot mode
627 void SimpleShell::dfu_command( string parameters, StreamOutput *stream)
628 {
629 stream->printf("Entering boot mode...\r\n");
630 system_reset(true);
631 }
632
633 // Break out into the MRI debugging system
634 void SimpleShell::break_command( string parameters, StreamOutput *stream)
635 {
636 stream->printf("Entering MRI debug mode...\r\n");
637 __debugbreak();
638 }
639
640 static int get_active_tool()
641 {
642 void *returned_data;
643 bool ok = PublicData::get_value(tool_manager_checksum, get_active_tool_checksum, &returned_data);
644 if (ok) {
645 int active_tool= *static_cast<int *>(returned_data);
646 return active_tool;
647 } else {
648 return 0;
649 }
650 }
651
652 void SimpleShell::grblDP_command( string parameters, StreamOutput *stream)
653 {
654 /*
655 [G54:95.000,40.000,-23.600]
656 [G55:0.000,0.000,0.000]
657 [G56:0.000,0.000,0.000]
658 [G57:0.000,0.000,0.000]
659 [G58:0.000,0.000,0.000]
660 [G59:0.000,0.000,0.000]
661 [G28:0.000,0.000,0.000]
662 [G30:0.000,0.000,0.000]
663 [G92:0.000,0.000,0.000]
664 [TLO:0.000]
665 [PRB:0.000,0.000,0.000:0]
666 */
667 std::vector<Robot::wcs_t> v= THEKERNEL->robot->get_wcs_state();
668 int n= std::get<1>(v[0]);
669 for (int i = 1; i <= n; ++i) {
670 stream->printf("[%s:%1.3f,%1.3f,%1.3f]\n", wcs2gcode(i-1).c_str(), std::get<0>(v[i]), std::get<1>(v[i]), std::get<2>(v[i]));
671 }
672
673 float *rd;
674 PublicData::get_value( endstops_checksum, saved_position_checksum, &rd );
675 stream->printf("[G28:%1.3f,%1.3f,%1.3f]\n", rd[0], rd[1], rd[2]);
676 stream->printf("[G30:%1.3f,%1.3f,%1.3f]\n", 0.0F, 0.0F, 0.0F); // not implemented
677
678 stream->printf("[G92:%1.3f,%1.3f,%1.3f]\n", std::get<0>(v[n+1]), std::get<1>(v[n+1]), std::get<2>(v[n+1]));
679 stream->printf("[TL0:%1.3f]\n", std::get<2>(v[n+2]));
680
681 // this is the last probe position, updated when a probe completes, also stores the number of steps moved after a homing cycle
682 float px, py, pz;
683 uint8_t ps;
684 std::tie(px, py, pz, ps) = THEKERNEL->robot->get_last_probe_position();
685 stream->printf("[PRB:%1.3f,%1.3f,%1.3f:%d]\n", px, py, pz, ps);
686 }
687
688 void SimpleShell::get_command( string parameters, StreamOutput *stream)
689 {
690 string what = shift_parameter( parameters );
691
692 if (what == "temp") {
693 struct pad_temperature temp;
694 string type = shift_parameter( parameters );
695 if(type.empty()) {
696 // scan all temperature controls
697 std::vector<struct pad_temperature> controllers;
698 bool ok = PublicData::get_value(temperature_control_checksum, poll_controls_checksum, &controllers);
699 if (ok) {
700 for (auto &c : controllers) {
701 stream->printf("%s (%d) temp: %f/%f @%d\r\n", c.designator.c_str(), c.id, c.current_temperature, c.target_temperature, c.pwm);
702 }
703
704 } else {
705 stream->printf("no heaters found\r\n");
706 }
707
708 }else{
709 bool ok = PublicData::get_value( temperature_control_checksum, current_temperature_checksum, get_checksum(type), &temp );
710
711 if (ok) {
712 stream->printf("%s temp: %f/%f @%d\r\n", type.c_str(), temp.current_temperature, temp.target_temperature, temp.pwm);
713 } else {
714 stream->printf("%s is not a known temperature device\r\n", type.c_str());
715 }
716 }
717
718 } else if (what == "fk" || what == "ik") {
719 string p= shift_parameter( parameters );
720 bool move= false;
721 if(p == "-m") {
722 move= true;
723 p= shift_parameter( parameters );
724 }
725
726 std::vector<float> v= parse_number_list(p.c_str());
727 if(p.empty() || v.size() < 1) {
728 stream->printf("error:usage: get [fk|ik] [-m] x[,y,z]\n");
729 return;
730 }
731
732 float x= v[0];
733 float y= (v.size() > 1) ? v[1] : x;
734 float z= (v.size() > 2) ? v[2] : y;
735
736 if(what == "fk") {
737 // do forward kinematics on the given actuator position and display the cartesian coordinates
738 ActuatorCoordinates apos{x, y, z};
739 float pos[3];
740 THEKERNEL->robot->arm_solution->actuator_to_cartesian(apos, pos);
741 stream->printf("cartesian= X %f, Y %f, Z %f, Steps= A %lu, B %lu, C %lu\n",
742 pos[0], pos[1], pos[2],
743 lroundf(x*THEKERNEL->robot->actuators[0]->get_steps_per_mm()),
744 lroundf(y*THEKERNEL->robot->actuators[1]->get_steps_per_mm()),
745 lroundf(z*THEKERNEL->robot->actuators[2]->get_steps_per_mm()));
746 x= pos[0];
747 y= pos[1];
748 z= pos[2];
749
750 }else{
751 // do inverse kinematics on the given cartesian position and display the actuator coordinates
752 float pos[3]{x, y, z};
753 ActuatorCoordinates apos;
754 THEKERNEL->robot->arm_solution->cartesian_to_actuator(pos, apos);
755 stream->printf("actuator= A %f, B %f, C %f\n", apos[0], apos[1], apos[2]);
756 }
757
758 if(move) {
759 // move to the calculated, or given, XYZ
760 char cmd[64];
761 snprintf(cmd, sizeof(cmd), "G53 G0 X%f Y%f Z%f", x, y, z);
762 struct SerialMessage message;
763 message.message = cmd;
764 message.stream = &(StreamOutput::NullStream);
765 THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
766 THEKERNEL->conveyor->wait_for_empty_queue();
767 }
768
769 } else if (what == "pos") {
770 // convenience to call all the various M114 variants
771 char buf[64];
772 THEKERNEL->robot->print_position(0, buf, sizeof buf); stream->printf("last %s\n", buf);
773 THEKERNEL->robot->print_position(1, buf, sizeof buf); stream->printf("realtime %s\n", buf);
774 THEKERNEL->robot->print_position(2, buf, sizeof buf); stream->printf("%s\n", buf);
775 THEKERNEL->robot->print_position(3, buf, sizeof buf); stream->printf("%s\n", buf);
776 THEKERNEL->robot->print_position(4, buf, sizeof buf); stream->printf("%s\n", buf);
777 THEKERNEL->robot->print_position(5, buf, sizeof buf); stream->printf("%s\n", buf);
778
779 } else if (what == "wcs") {
780 // print the wcs state
781 std::vector<Robot::wcs_t> v= THEKERNEL->robot->get_wcs_state();
782 char current_wcs= std::get<0>(v[0]);
783 stream->printf("current WCS: %s\n", wcs2gcode(current_wcs).c_str());
784 int n= std::get<1>(v[0]);
785 for (int i = 1; i <= n; ++i) {
786 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]));
787 }
788
789 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]));
790 stream->printf("ToolOffset: %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]));
791
792 } else if (what == "state") {
793 // also $G
794 // [G0 G54 G17 G21 G90 G94 M0 M5 M9 T0 F0.]
795 stream->printf("[G%d %s G%d G%d G%d G94 M0 M5 M9 T%d F%1.1f]\n",
796 THEKERNEL->gcode_dispatch->get_modal_command(),
797 wcs2gcode(THEKERNEL->robot->get_current_wcs()).c_str(),
798 THEKERNEL->robot->plane_axis_0 == X_AXIS && THEKERNEL->robot->plane_axis_1 == Y_AXIS && THEKERNEL->robot->plane_axis_2 == Z_AXIS ? 17 :
799 THEKERNEL->robot->plane_axis_0 == X_AXIS && THEKERNEL->robot->plane_axis_1 == Z_AXIS && THEKERNEL->robot->plane_axis_2 == Y_AXIS ? 18 :
800 THEKERNEL->robot->plane_axis_0 == Y_AXIS && THEKERNEL->robot->plane_axis_1 == Z_AXIS && THEKERNEL->robot->plane_axis_2 == X_AXIS ? 19 : 17,
801 THEKERNEL->robot->inch_mode ? 20 : 21,
802 THEKERNEL->robot->absolute_mode ? 90 : 91,
803 get_active_tool(),
804 THEKERNEL->robot->get_feed_rate());
805
806 } else {
807 stream->printf("error:unknown option %s\n", what.c_str());
808 }
809 }
810
811 // used to test out the get public data events
812 void SimpleShell::set_temp_command( string parameters, StreamOutput *stream)
813 {
814 string type = shift_parameter( parameters );
815 string temp = shift_parameter( parameters );
816 float t = temp.empty() ? 0.0 : strtof(temp.c_str(), NULL);
817 bool ok = PublicData::set_value( temperature_control_checksum, get_checksum(type), &t );
818
819 if (ok) {
820 stream->printf("%s temp set to: %3.1f\r\n", type.c_str(), t);
821 } else {
822 stream->printf("%s is not a known temperature device\r\n", type.c_str());
823 }
824 }
825
826 void SimpleShell::print_thermistors_command( string parameters, StreamOutput *stream)
827 {
828 Thermistor::print_predefined_thermistors(stream);
829 }
830
831 void SimpleShell::calc_thermistor_command( string parameters, StreamOutput *stream)
832 {
833 string s = shift_parameter( parameters );
834 int saveto= -1;
835 // see if we have -sn as first argument
836 if(s.find("-s", 0, 2) != string::npos) {
837 // save the results to thermistor n
838 saveto= strtol(s.substr(2).c_str(), nullptr, 10);
839 }else{
840 parameters= s;
841 }
842
843 std::vector<float> trl= parse_number_list(parameters.c_str());
844 if(trl.size() == 6) {
845 // calculate the coefficients
846 float c1, c2, c3;
847 std::tie(c1, c2, c3) = Thermistor::calculate_steinhart_hart_coefficients(trl[0], trl[1], trl[2], trl[3], trl[4], trl[5]);
848 stream->printf("Steinhart Hart coefficients: I%1.18f J%1.18f K%1.18f\n", c1, c2, c3);
849 if(saveto == -1) {
850 stream->printf(" Paste the above in the M305 S0 command, then save with M500\n");
851 }else{
852 char buf[80];
853 int n = snprintf(buf, sizeof(buf), "M305 S%d I%1.18f J%1.18f K%1.18f", saveto, c1, c2, c3);
854 string g(buf, n);
855 Gcode gcode(g, &(StreamOutput::NullStream));
856 THEKERNEL->call_event(ON_GCODE_RECEIVED, &gcode );
857 stream->printf(" Setting Thermistor %d to those settings, save with M500\n", saveto);
858 }
859
860 }else{
861 // give help
862 stream->printf("Usage: calc_thermistor T1,R1,T2,R2,T3,R3\n");
863 }
864 }
865
866 // used to test out the get public data events for switch
867 void SimpleShell::switch_command( string parameters, StreamOutput *stream)
868 {
869 string type = shift_parameter( parameters );
870 string value = shift_parameter( parameters );
871 bool ok = false;
872 if(value == "on" || value == "off") {
873 bool b = value == "on";
874 ok = PublicData::set_value( switch_checksum, get_checksum(type), state_checksum, &b );
875 } else {
876 float v = strtof(value.c_str(), NULL);
877 ok = PublicData::set_value( switch_checksum, get_checksum(type), value_checksum, &v );
878 }
879 if (ok) {
880 stream->printf("switch %s set to: %s\r\n", type.c_str(), value.c_str());
881 } else {
882 stream->printf("%s is not a known switch device\r\n", type.c_str());
883 }
884 }
885
886 void SimpleShell::md5sum_command( string parameters, StreamOutput *stream )
887 {
888 string filename = absolute_from_relative(parameters);
889
890 // Open file
891 FILE *lp = fopen(filename.c_str(), "r");
892 if (lp == NULL) {
893 stream->printf("File not found: %s\r\n", filename.c_str());
894 return;
895 }
896 MD5 md5;
897 uint8_t buf[64];
898 do {
899 size_t n= fread(buf, 1, sizeof buf, lp);
900 if(n > 0) md5.update(buf, n);
901 THEKERNEL->call_event(ON_IDLE);
902 } while(!feof(lp));
903
904 stream->printf("%s %s\n", md5.finalize().hexdigest().c_str(), filename.c_str());
905 fclose(lp);
906 }
907
908
909
910 void SimpleShell::help_command( string parameters, StreamOutput *stream )
911 {
912 stream->printf("Commands:\r\n");
913 stream->printf("version\r\n");
914 stream->printf("mem [-v]\r\n");
915 stream->printf("ls [-s] [folder]\r\n");
916 stream->printf("cd folder\r\n");
917 stream->printf("pwd\r\n");
918 stream->printf("cat file [limit] [-d 10]\r\n");
919 stream->printf("rm file\r\n");
920 stream->printf("mv file newfile\r\n");
921 stream->printf("remount\r\n");
922 stream->printf("play file [-v]\r\n");
923 stream->printf("progress - shows progress of current play\r\n");
924 stream->printf("abort - abort currently playing file\r\n");
925 stream->printf("reset - reset smoothie\r\n");
926 stream->printf("dfu - enter dfu boot loader\r\n");
927 stream->printf("break - break into debugger\r\n");
928 stream->printf("config-get [<configuration_source>] <configuration_setting>\r\n");
929 stream->printf("config-set [<configuration_source>] <configuration_setting> <value>\r\n");
930 stream->printf("get [pos|wcs|state|fk|ik]\r\n");
931 stream->printf("get temp [bed|hotend]\r\n");
932 stream->printf("set_temp bed|hotend 185\r\n");
933 stream->printf("net\r\n");
934 stream->printf("load [file] - loads a configuration override file from soecified name or config-override\r\n");
935 stream->printf("save [file] - saves a configuration override file as specified filename or as config-override\r\n");
936 stream->printf("upload filename - saves a stream of text to the named file\r\n");
937 stream->printf("calc_thermistor [-s0] T1,R1,T2,R2,T3,R3 - calculate the Steinhart Hart coefficients for a thermistor\r\n");
938 stream->printf("thermistors - print out the predefined thermistors\r\n");
939 stream->printf("md5sum file - prints md5 sum of the given file\r\n");
940 }
941