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/>.
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"
19 #include "PublicDataRequest.h"
20 #include "AppendFileStream.h"
21 #include "FileStream.h"
22 #include "checksumm.h"
23 #include "PublicData.h"
26 #include "ToolManagerPublicAccess.h"
27 #include "GcodeDispatch.h"
28 #include "BaseSolution.h"
29 #include "StepperMotor.h"
30 #include "Configurator.h"
32 #include "TemperatureControlPublicAccess.h"
33 #include "EndstopsPublicAccess.h"
34 #include "NetworkPublicAccess.h"
35 #include "platform_memory.h"
36 #include "SwitchPublicAccess.h"
38 #include "Thermistor.h"
42 #include "system_LPC17xx.h"
45 #include "mbed.h" // for wait_ms()
47 extern unsigned int g_maximumHeapAddress
;
54 extern "C" uint32_t __end__
;
55 extern "C" uint32_t __malloc_free_list
;
56 extern "C" uint32_t _sbrk(int size
);
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
},
89 int SimpleShell::reset_delay_secs
= 0;
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
)
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);
102 uint32_t freeSize
= 0;
103 uint32_t usedSize
= 0;
105 stream
->printf("Used Heap Size: %lu\n", heapEnd
- chunkCurr
);
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.
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
;
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.
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);
126 // Skip past the 32-bit size field in the chunk header.
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.
134 stream
->printf(" Chunk: %lu Address: 0x%08lX Size: %lu %s\n", chunkNumber
, chunkCurr
, chunkSize
, isChunkFree
? "CHUNK FREE" : "");
136 if (isChunkFree
) freeSize
+= chunkSize
;
137 else usedSize
+= chunkSize
;
139 chunkCurr
= chunkNext
;
142 stream
->printf("Allocated: %lu, Free: %lu\r\n", usedSize
, freeSize
);
147 void SimpleShell::on_module_loaded()
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
);
153 reset_delay_secs
= 0;
156 void SimpleShell::on_second_tick(void *)
158 // we are timing out for the reset
159 if (reset_delay_secs
> 0) {
160 if (--reset_delay_secs
== 0) {
166 void SimpleShell::on_gcode_received(void *argument
)
168 Gcode
*gcode
= static_cast<Gcode
*>(argument
);
169 string args
= get_arguments(gcode
->get_command());
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");
177 } else if (gcode
->m
== 30) { // remove file
178 rm_command("/sd/" + args
, gcode
->stream
);
180 } else if(gcode
->m
== 501) { // load config override
182 load_command("/sd/config-override", gcode
->stream
);
184 load_command("/sd/config-override." + args
, gcode
->stream
);
187 } else if(gcode
->m
== 504) { // save to specific config override file
189 save_command("/sd/config-override", gcode
->stream
);
191 save_command("/sd/config-override." + args
, gcode
->stream
);
197 bool SimpleShell::parse_command(const char *cmd
, string args
, StreamOutput
*stream
)
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
);
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
)
212 SerialMessage new_message
= *static_cast<SerialMessage
*>(argument
);
213 string possible_command
= new_message
.message
;
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] != '$')) {
220 // it is a grbl compatible command
221 if(possible_command
[0] == '$' && possible_command
.size() >= 2) {
222 switch(possible_command
[1]) {
225 get_command("state", new_message
.stream
);
226 new_message
.stream
->printf("ok\n");
230 THEKERNEL
->call_event(ON_HALT
, (void *)1); // clears on_halt
231 new_message
.stream
->printf("[Caution: Unlocked]\nok\n");
235 grblDP_command("", new_message
.stream
);
236 new_message
.stream
->printf("ok\n");
240 if(THEKERNEL
->is_grbl_mode()) {
241 THEKERNEL
->call_event(ON_HALT
, (void *)1); // clears on_halt
242 // issue G28.2 which is force homing cycle
243 Gcode
gcode("G28.2", new_message
.stream
);
244 THEKERNEL
->call_event(ON_GCODE_RECEIVED
, &gcode
);
246 new_message
.stream
->printf("error:only supported in GRBL mode\n");
251 new_message
.stream
->printf("error:Invalid statement\n");
257 //new_message.stream->printf("Received %s\r\n", possible_command.c_str());
258 string cmd
= shift_parameter(possible_command
);
260 // Configurator commands
261 if (cmd
== "config-get"){
262 THEKERNEL
->configurator
->config_get_command( possible_command
, new_message
.stream
);
264 } else if (cmd
== "config-set"){
265 THEKERNEL
->configurator
->config_set_command( possible_command
, new_message
.stream
);
267 } else if (cmd
== "config-load"){
268 THEKERNEL
->configurator
->config_load_command( possible_command
, new_message
.stream
);
270 } else if (cmd
== "play" || cmd
== "progress" || cmd
== "abort" || cmd
== "suspend" || cmd
== "resume") {
272 } else if (cmd
== "ok") {
273 // probably an echo so reply ok
274 new_message
.stream
->printf("ok\n");
276 }else if(!parse_command(cmd
.c_str(), possible_command
, new_message
.stream
)) {
277 new_message
.stream
->printf("error:Unsupported command - %s\n", cmd
.c_str());
282 // Act upon an ls command
283 // Convert the first parameter into an absolute path, then list the files in that path
284 void SimpleShell::ls_command( string parameters
, StreamOutput
*stream
)
287 while(!parameters
.empty()) {
288 string s
= shift_parameter( parameters
);
289 if(s
.front() == '-') {
293 if(!parameters
.empty()) {
295 path
.append(parameters
);
301 path
= absolute_from_relative(path
);
305 d
= opendir(path
.c_str());
307 while ((p
= readdir(d
)) != NULL
) {
308 stream
->printf("%s", lc(string(p
->d_name
)).c_str());
311 } else if(opts
.find("-s", 0, 2) != string::npos
) {
312 stream
->printf(" %d", p
->d_fsize
);
314 stream
->printf("\r\n");
318 stream
->printf("Could not open directory %s\r\n", path
.c_str());
322 extern SDFAT mounter
;
324 void SimpleShell::remount_command( string parameters
, StreamOutput
*stream
)
327 stream
->printf("remounted\r\n");
331 void SimpleShell::rm_command( string parameters
, StreamOutput
*stream
)
333 const char *fn
= absolute_from_relative(shift_parameter( parameters
)).c_str();
335 if (s
!= 0) stream
->printf("Could not delete %s \r\n", fn
);
339 void SimpleShell::mv_command( string parameters
, StreamOutput
*stream
)
341 string from
= absolute_from_relative(shift_parameter( parameters
));
342 string to
= absolute_from_relative(shift_parameter(parameters
));
343 int s
= rename(from
.c_str(), to
.c_str());
344 if (s
!= 0) stream
->printf("Could not rename %s to %s\r\n", from
.c_str(), to
.c_str());
345 else stream
->printf("renamed %s to %s\r\n", from
.c_str(), to
.c_str());
348 // Change current absolute path to provided path
349 void SimpleShell::cd_command( string parameters
, StreamOutput
*stream
)
351 string folder
= absolute_from_relative( parameters
);
354 d
= opendir(folder
.c_str());
356 stream
->printf("Could not open directory %s \r\n", folder
.c_str() );
358 THEKERNEL
->current_path
= folder
;
363 // Responds with the present working directory
364 void SimpleShell::pwd_command( string parameters
, StreamOutput
*stream
)
366 stream
->printf("%s\r\n", THEKERNEL
->current_path
.c_str());
369 // Output the contents of a file, first parameter is the filename, second is the limit ( in number of lines to output )
370 void SimpleShell::cat_command( string parameters
, StreamOutput
*stream
)
372 // Get parameters ( filename and line limit )
373 string filename
= absolute_from_relative(shift_parameter( parameters
));
374 string limit_parameter
= shift_parameter( parameters
);
377 bool send_eof
= false;
378 if ( limit_parameter
== "-d" ) {
379 string d
= shift_parameter( parameters
);
381 delay
= strtol(d
.c_str(), &e
, 10);
382 if (e
<= d
.c_str()) {
386 send_eof
= true; // we need to terminate file send with an eof
389 }else if ( limit_parameter
!= "" ) {
391 limit
= strtol(limit_parameter
.c_str(), &e
, 10);
392 if (e
<= limit_parameter
.c_str())
396 // we have been asked to delay before cat, probably to allow time to issue upload command
398 safe_delay(delay
*1000);
402 FILE *lp
= fopen(filename
.c_str(), "r");
404 stream
->printf("File not found: %s\r\n", filename
.c_str());
411 // Print each line of the file
412 while ((c
= fgetc (lp
)) != EOF
) {
413 buffer
.append((char *)&c
, 1);
414 if ( c
== '\n' || ++linecnt
> 80) {
415 if(c
== '\n') newlines
++;
416 stream
->puts(buffer
.c_str());
418 if(linecnt
> 80) linecnt
= 0;
419 // we need to kick things or they die
420 THEKERNEL
->call_event(ON_IDLE
);
422 if ( newlines
== limit
) {
429 stream
->puts("\032"); // ^Z terminates the upload
433 void SimpleShell::upload_command( string parameters
, StreamOutput
*stream
)
435 // this needs to be a hack. it needs to read direct from serial and not allow on_main_loop run until done
436 // NOTE this will block all operation until the upload is complete, so do not do while printing
437 if(!THEKERNEL
->conveyor
->is_queue_empty()) {
438 stream
->printf("upload not allowed while printing or busy\n");
442 // open file to upload to
443 string upload_filename
= absolute_from_relative( parameters
);
444 FILE *fd
= fopen(upload_filename
.c_str(), "w");
446 stream
->printf("uploading to file: %s, send control-D or control-Z to finish\r\n", upload_filename
.c_str());
448 stream
->printf("failed to open file: %s.\r\n", upload_filename
.c_str());
453 bool uploading
= true;
455 if(!stream
->ready()) {
456 // we need to kick things or they die
457 THEKERNEL
->call_event(ON_IDLE
);
461 char c
= stream
->_getc();
462 if( c
== 4 || c
== 26) { // ctrl-D or ctrl-Z
466 stream
->printf("uploaded %d bytes\n", cnt
);
470 // write character to file
472 if(fputc(c
, fd
) != c
) {
473 // error writing to file
474 stream
->printf("error writing to file. ignoring all characters until EOF\r\n");
480 if ((cnt
%400) == 0) {
481 // HACK ALERT to get around fwrite corruption close and re open for append
483 fd
= fopen(upload_filename
.c_str(), "a");
484 // we need to kick things or they die
485 THEKERNEL
->call_event(ON_IDLE
);
490 // we got an error so ignore everything until EOF
493 if(stream
->ready()) {
496 THEKERNEL
->call_event(ON_IDLE
);
499 } while(c
!= 4 && c
!= 26);
502 // loads the specified config-override file
503 void SimpleShell::load_command( string parameters
, StreamOutput
*stream
)
505 // Get parameters ( filename )
506 string filename
= absolute_from_relative(parameters
);
507 if(filename
== "/") {
508 filename
= THEKERNEL
->config_override_filename();
511 FILE *fp
= fopen(filename
.c_str(), "r");
514 stream
->printf("Loading config override file: %s...\n", filename
.c_str());
515 while(fgets(buf
, sizeof buf
, fp
) != NULL
) {
516 stream
->printf(" %s", buf
);
517 if(buf
[0] == ';') continue; // skip the comments
518 struct SerialMessage message
= {&(StreamOutput::NullStream
), buf
};
519 THEKERNEL
->call_event(ON_CONSOLE_LINE_RECEIVED
, &message
);
521 stream
->printf("config override file executed\n");
525 stream
->printf("File not found: %s\n", filename
.c_str());
529 // saves the specified config-override file
530 void SimpleShell::save_command( string parameters
, StreamOutput
*stream
)
532 // Get parameters ( filename )
533 string filename
= absolute_from_relative(parameters
);
534 if(filename
== "/") {
535 filename
= THEKERNEL
->config_override_filename();
538 THEKERNEL
->conveyor
->wait_for_empty_queue(); //just to be safe as it can take a while to run
540 //remove(filename.c_str()); // seems to cause a hang every now and then
542 FileStream
fs(filename
.c_str());
543 fs
.printf("; DO NOT EDIT THIS FILE\n");
544 // this also will truncate the existing file instead of deleting it
547 // stream that appends to file
548 AppendFileStream
*gs
= new AppendFileStream(filename
.c_str());
549 // if(!gs->is_open()) {
550 // stream->printf("Unable to open File %s for write\n", filename.c_str());
555 // issue a M500 which will store values in the file stream
556 Gcode
*gcode
= new Gcode("M500", gs
);
557 THEKERNEL
->call_event(ON_GCODE_RECEIVED
, gcode
);
562 stream
->printf("Settings Stored to %s\r\n", filename
.c_str());
566 void SimpleShell::mem_command( string parameters
, StreamOutput
*stream
)
568 bool verbose
= shift_parameter( parameters
).find_first_of("Vv") != string::npos
;
569 unsigned long heap
= (unsigned long)_sbrk(0);
570 unsigned long m
= g_maximumHeapAddress
- heap
;
571 stream
->printf("Unused Heap: %lu bytes\r\n", m
);
573 uint32_t f
= heapWalk(stream
, verbose
);
574 stream
->printf("Total Free RAM: %lu bytes\r\n", m
+ f
);
576 stream
->printf("Free AHB0: %lu, AHB1: %lu\r\n", AHB0
.free(), AHB1
.free());
583 static uint32_t getDeviceType()
585 #define IAP_LOCATION 0x1FFF1FF1
588 typedef void (*IAP
)(uint32_t *, uint32_t *);
589 IAP iap
= (IAP
) IAP_LOCATION
;
594 iap(command
, result
);
601 // get network config
602 void SimpleShell::net_command( string parameters
, StreamOutput
*stream
)
605 bool ok
= PublicData::get_value( network_checksum
, get_ipconfig_checksum
, &returned_data
);
607 char *str
= (char *)returned_data
;
608 stream
->printf("%s\r\n", str
);
612 stream
->printf("No network detected\n");
616 // print out build version
617 void SimpleShell::version_command( string parameters
, StreamOutput
*stream
)
620 uint32_t dev
= getDeviceType();
621 const char *mcu
= (dev
& 0x00100000) ? "LPC1769" : "LPC1768";
622 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);
626 void SimpleShell::reset_command( string parameters
, StreamOutput
*stream
)
628 stream
->printf("Smoothie out. Peace. Rebooting in 5 seconds...\r\n");
629 reset_delay_secs
= 5; // reboot in 5 seconds
632 // go into dfu boot mode
633 void SimpleShell::dfu_command( string parameters
, StreamOutput
*stream
)
635 stream
->printf("Entering boot mode...\r\n");
639 // Break out into the MRI debugging system
640 void SimpleShell::break_command( string parameters
, StreamOutput
*stream
)
642 stream
->printf("Entering MRI debug mode...\r\n");
646 static int get_active_tool()
649 bool ok
= PublicData::get_value(tool_manager_checksum
, get_active_tool_checksum
, &returned_data
);
651 int active_tool
= *static_cast<int *>(returned_data
);
658 void SimpleShell::grblDP_command( string parameters
, StreamOutput
*stream
)
661 [G54:95.000,40.000,-23.600]
662 [G55:0.000,0.000,0.000]
663 [G56:0.000,0.000,0.000]
664 [G57:0.000,0.000,0.000]
665 [G58:0.000,0.000,0.000]
666 [G59:0.000,0.000,0.000]
667 [G28:0.000,0.000,0.000]
668 [G30:0.000,0.000,0.000]
669 [G92:0.000,0.000,0.000]
671 [PRB:0.000,0.000,0.000:0]
674 bool verbose
= shift_parameter( parameters
).find_first_of("Vv") != string::npos
;
676 std::vector
<Robot::wcs_t
> v
= THEKERNEL
->robot
->get_wcs_state();
678 char current_wcs
= std::get
<0>(v
[0]);
679 stream
->printf("[current WCS: %s]\n", wcs2gcode(current_wcs
).c_str());
682 int n
= std::get
<1>(v
[0]);
683 for (int i
= 1; i
<= n
; ++i
) {
684 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
]));
688 PublicData::get_value( endstops_checksum
, saved_position_checksum
, &rd
);
689 stream
->printf("[G28:%1.4f,%1.4f,%1.4f]\n", rd
[0], rd
[1], rd
[2]);
690 stream
->printf("[G30:%1.4f,%1.4f,%1.4f]\n", 0.0F
, 0.0F
, 0.0F
); // not implemented
692 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]));
694 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]));
696 stream
->printf("[TL0:%1.4f]\n", std::get
<2>(v
[n
+2]));
699 // this is the last probe position, updated when a probe completes, also stores the number of steps moved after a homing cycle
702 std::tie(px
, py
, pz
, ps
) = THEKERNEL
->robot
->get_last_probe_position();
703 stream
->printf("[PRB:%1.4f,%1.4f,%1.4f:%d]\n", px
, py
, pz
, ps
);
706 void SimpleShell::get_command( string parameters
, StreamOutput
*stream
)
708 string what
= shift_parameter( parameters
);
710 if (what
== "temp") {
711 struct pad_temperature temp
;
712 string type
= shift_parameter( parameters
);
714 // scan all temperature controls
715 std::vector
<struct pad_temperature
> controllers
;
716 bool ok
= PublicData::get_value(temperature_control_checksum
, poll_controls_checksum
, &controllers
);
718 for (auto &c
: controllers
) {
719 stream
->printf("%s (%d) temp: %f/%f @%d\r\n", c
.designator
.c_str(), c
.id
, c
.current_temperature
, c
.target_temperature
, c
.pwm
);
723 stream
->printf("no heaters found\r\n");
727 bool ok
= PublicData::get_value( temperature_control_checksum
, current_temperature_checksum
, get_checksum(type
), &temp
);
730 stream
->printf("%s temp: %f/%f @%d\r\n", type
.c_str(), temp
.current_temperature
, temp
.target_temperature
, temp
.pwm
);
732 stream
->printf("%s is not a known temperature device\r\n", type
.c_str());
736 } else if (what
== "fk" || what
== "ik") {
737 string p
= shift_parameter( parameters
);
741 p
= shift_parameter( parameters
);
744 std::vector
<float> v
= parse_number_list(p
.c_str());
745 if(p
.empty() || v
.size() < 1) {
746 stream
->printf("error:usage: get [fk|ik] [-m] x[,y,z]\n");
751 float y
= (v
.size() > 1) ? v
[1] : x
;
752 float z
= (v
.size() > 2) ? v
[2] : y
;
755 // do forward kinematics on the given actuator position and display the cartesian coordinates
756 ActuatorCoordinates apos
{x
, y
, z
};
758 THEKERNEL
->robot
->arm_solution
->actuator_to_cartesian(apos
, pos
);
759 stream
->printf("cartesian= X %f, Y %f, Z %f, Steps= A %lu, B %lu, C %lu\n",
760 pos
[0], pos
[1], pos
[2],
761 lroundf(x
*THEKERNEL
->robot
->actuators
[0]->get_steps_per_mm()),
762 lroundf(y
*THEKERNEL
->robot
->actuators
[1]->get_steps_per_mm()),
763 lroundf(z
*THEKERNEL
->robot
->actuators
[2]->get_steps_per_mm()));
769 // do inverse kinematics on the given cartesian position and display the actuator coordinates
770 float pos
[3]{x
, y
, z
};
771 ActuatorCoordinates apos
;
772 THEKERNEL
->robot
->arm_solution
->cartesian_to_actuator(pos
, apos
);
773 stream
->printf("actuator= A %f, B %f, C %f\n", apos
[0], apos
[1], apos
[2]);
777 // move to the calculated, or given, XYZ
779 snprintf(cmd
, sizeof(cmd
), "G53 G0 X%f Y%f Z%f", x
, y
, z
);
780 struct SerialMessage message
;
781 message
.message
= cmd
;
782 message
.stream
= &(StreamOutput::NullStream
);
783 THEKERNEL
->call_event(ON_CONSOLE_LINE_RECEIVED
, &message
);
784 THEKERNEL
->conveyor
->wait_for_empty_queue();
787 } else if (what
== "pos") {
788 // convenience to call all the various M114 variants
790 THEKERNEL
->robot
->print_position(0, buf
, sizeof buf
); stream
->printf("last %s\n", buf
);
791 THEKERNEL
->robot
->print_position(1, buf
, sizeof buf
); stream
->printf("realtime %s\n", buf
);
792 THEKERNEL
->robot
->print_position(2, buf
, sizeof buf
); stream
->printf("%s\n", buf
);
793 THEKERNEL
->robot
->print_position(3, buf
, sizeof buf
); stream
->printf("%s\n", buf
);
794 THEKERNEL
->robot
->print_position(4, buf
, sizeof buf
); stream
->printf("%s\n", buf
);
795 THEKERNEL
->robot
->print_position(5, buf
, sizeof buf
); stream
->printf("%s\n", buf
);
797 } else if (what
== "wcs") {
798 // print the wcs state
799 grblDP_command("-v", stream
);
801 } else if (what
== "state") {
803 // [G0 G54 G17 G21 G90 G94 M0 M5 M9 T0 F0.]
804 stream
->printf("[G%d %s G%d G%d G%d G94 M0 M5 M9 T%d F%1.4f]\n",
805 THEKERNEL
->gcode_dispatch
->get_modal_command(),
806 wcs2gcode(THEKERNEL
->robot
->get_current_wcs()).c_str(),
807 THEKERNEL
->robot
->plane_axis_0
== X_AXIS
&& THEKERNEL
->robot
->plane_axis_1
== Y_AXIS
&& THEKERNEL
->robot
->plane_axis_2
== Z_AXIS
? 17 :
808 THEKERNEL
->robot
->plane_axis_0
== X_AXIS
&& THEKERNEL
->robot
->plane_axis_1
== Z_AXIS
&& THEKERNEL
->robot
->plane_axis_2
== Y_AXIS
? 18 :
809 THEKERNEL
->robot
->plane_axis_0
== Y_AXIS
&& THEKERNEL
->robot
->plane_axis_1
== Z_AXIS
&& THEKERNEL
->robot
->plane_axis_2
== X_AXIS
? 19 : 17,
810 THEKERNEL
->robot
->inch_mode
? 20 : 21,
811 THEKERNEL
->robot
->absolute_mode
? 90 : 91,
813 THEKERNEL
->robot
->get_feed_rate());
816 stream
->printf("error:unknown option %s\n", what
.c_str());
820 // used to test out the get public data events
821 void SimpleShell::set_temp_command( string parameters
, StreamOutput
*stream
)
823 string type
= shift_parameter( parameters
);
824 string temp
= shift_parameter( parameters
);
825 float t
= temp
.empty() ? 0.0 : strtof(temp
.c_str(), NULL
);
826 bool ok
= PublicData::set_value( temperature_control_checksum
, get_checksum(type
), &t
);
829 stream
->printf("%s temp set to: %3.1f\r\n", type
.c_str(), t
);
831 stream
->printf("%s is not a known temperature device\r\n", type
.c_str());
835 void SimpleShell::print_thermistors_command( string parameters
, StreamOutput
*stream
)
837 Thermistor::print_predefined_thermistors(stream
);
840 void SimpleShell::calc_thermistor_command( string parameters
, StreamOutput
*stream
)
842 string s
= shift_parameter( parameters
);
844 // see if we have -sn as first argument
845 if(s
.find("-s", 0, 2) != string::npos
) {
846 // save the results to thermistor n
847 saveto
= strtol(s
.substr(2).c_str(), nullptr, 10);
852 std::vector
<float> trl
= parse_number_list(parameters
.c_str());
853 if(trl
.size() == 6) {
854 // calculate the coefficients
856 std::tie(c1
, c2
, c3
) = Thermistor::calculate_steinhart_hart_coefficients(trl
[0], trl
[1], trl
[2], trl
[3], trl
[4], trl
[5]);
857 stream
->printf("Steinhart Hart coefficients: I%1.18f J%1.18f K%1.18f\n", c1
, c2
, c3
);
859 stream
->printf(" Paste the above in the M305 S0 command, then save with M500\n");
862 int n
= snprintf(buf
, sizeof(buf
), "M305 S%d I%1.18f J%1.18f K%1.18f", saveto
, c1
, c2
, c3
);
864 Gcode
gcode(g
, &(StreamOutput::NullStream
));
865 THEKERNEL
->call_event(ON_GCODE_RECEIVED
, &gcode
);
866 stream
->printf(" Setting Thermistor %d to those settings, save with M500\n", saveto
);
871 stream
->printf("Usage: calc_thermistor T1,R1,T2,R2,T3,R3\n");
875 // used to test out the get public data events for switch
876 void SimpleShell::switch_command( string parameters
, StreamOutput
*stream
)
878 string type
= shift_parameter( parameters
);
879 string value
= shift_parameter( parameters
);
881 if(value
== "on" || value
== "off") {
882 bool b
= value
== "on";
883 ok
= PublicData::set_value( switch_checksum
, get_checksum(type
), state_checksum
, &b
);
885 float v
= strtof(value
.c_str(), NULL
);
886 ok
= PublicData::set_value( switch_checksum
, get_checksum(type
), value_checksum
, &v
);
889 stream
->printf("switch %s set to: %s\r\n", type
.c_str(), value
.c_str());
891 stream
->printf("%s is not a known switch device\r\n", type
.c_str());
895 void SimpleShell::md5sum_command( string parameters
, StreamOutput
*stream
)
897 string filename
= absolute_from_relative(parameters
);
900 FILE *lp
= fopen(filename
.c_str(), "r");
902 stream
->printf("File not found: %s\r\n", filename
.c_str());
908 size_t n
= fread(buf
, 1, sizeof buf
, lp
);
909 if(n
> 0) md5
.update(buf
, n
);
910 THEKERNEL
->call_event(ON_IDLE
);
913 stream
->printf("%s %s\n", md5
.finalize().hexdigest().c_str(), filename
.c_str());
919 void SimpleShell::help_command( string parameters
, StreamOutput
*stream
)
921 stream
->printf("Commands:\r\n");
922 stream
->printf("version\r\n");
923 stream
->printf("mem [-v]\r\n");
924 stream
->printf("ls [-s] [folder]\r\n");
925 stream
->printf("cd folder\r\n");
926 stream
->printf("pwd\r\n");
927 stream
->printf("cat file [limit] [-d 10]\r\n");
928 stream
->printf("rm file\r\n");
929 stream
->printf("mv file newfile\r\n");
930 stream
->printf("remount\r\n");
931 stream
->printf("play file [-v]\r\n");
932 stream
->printf("progress - shows progress of current play\r\n");
933 stream
->printf("abort - abort currently playing file\r\n");
934 stream
->printf("reset - reset smoothie\r\n");
935 stream
->printf("dfu - enter dfu boot loader\r\n");
936 stream
->printf("break - break into debugger\r\n");
937 stream
->printf("config-get [<configuration_source>] <configuration_setting>\r\n");
938 stream
->printf("config-set [<configuration_source>] <configuration_setting> <value>\r\n");
939 stream
->printf("get [pos|wcs|state|fk|ik]\r\n");
940 stream
->printf("get temp [bed|hotend]\r\n");
941 stream
->printf("set_temp bed|hotend 185\r\n");
942 stream
->printf("net\r\n");
943 stream
->printf("load [file] - loads a configuration override file from soecified name or config-override\r\n");
944 stream
->printf("save [file] - saves a configuration override file as specified filename or as config-override\r\n");
945 stream
->printf("upload filename - saves a stream of text to the named file\r\n");
946 stream
->printf("calc_thermistor [-s0] T1,R1,T2,R2,T3,R3 - calculate the Steinhart Hart coefficients for a thermistor\r\n");
947 stream
->printf("thermistors - print out the predefined thermistors\r\n");
948 stream
->printf("md5sum file - prints md5 sum of the given file\r\n");