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