Basic 3D printing support working, a gigaton of bugfixes
[clinton/Smoothieware.git] / src / modules / robot / Robot.cpp
CommitLineData
4cff3ded 1/*
aab6cbba 2 This file is part of Smoothie (http://smoothieware.org/). The motion control part is heavily based on Grbl (https://github.com/simen/grbl) with additions from Sungeun K. Jeon (https://github.com/chamnit/grbl)
4cff3ded
AW
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#include "libs/Module.h"
9#include "libs/Kernel.h"
10#include <string>
11using std::string;
12#include "mbed.h"
13#include <math.h>
14#include "Planner.h"
3a4fa0c1 15#include "Player.h"
4cff3ded
AW
16#include "Robot.h"
17#include "libs/nuts_bolts.h"
18#include "../communication/utils/Gcode.h"
19#include "arm_solutions/BaseSolution.h"
20#include "arm_solutions/CartesianSolution.h"
21
22Robot::Robot(){
a1b7e9f0
AW
23 this->inch_mode = false;
24 this->absolute_mode = false;
4cff3ded
AW
25 this->motion_mode = MOTION_MODE_SEEK;
26 this->select_plane(X_AXIS, Y_AXIS, Z_AXIS);
27 clear_vector(this->current_position);
28 clear_vector(this->last_milestone);
29}
30
31//Called when the module has just been loaded
32void Robot::on_module_loaded() {
33 this->arm_solution = new CartesianSolution(this->kernel->config);
34 this->register_for_event(ON_GCODE_RECEIVED);
35
36 // Configuration
da24d6ae
AW
37 this->on_config_reload(this);
38}
39
40void Robot::on_config_reload(void* argument){
b66fb830
AW
41 this->feed_rate = this->kernel->config->value(default_feed_rate_checksum )->by_default(100)->as_number()/60;
42 this->seek_rate = this->kernel->config->value(default_seek_rate_checksum )->by_default(100)->as_number()/60;
43 this->mm_per_line_segment = this->kernel->config->value(mm_per_line_segment_checksum)->by_default(0.1)->as_number();
44 this->mm_per_arc_segment = this->kernel->config->value(mm_per_arc_segment_checksum )->by_default(10 )->as_number();
7b470506
AW
45 this->arc_correction = this->kernel->config->value(arc_correction_checksum )->by_default(5 )->as_number();
46 this->max_speeds[X_AXIS] = this->kernel->config->value(x_axis_max_speed_checksum )->by_default(0 )->as_number();
47 this->max_speeds[Y_AXIS] = this->kernel->config->value(y_axis_max_speed_checksum )->by_default(0 )->as_number();
48 this->max_speeds[Z_AXIS] = this->kernel->config->value(z_axis_max_speed_checksum )->by_default(0 )->as_number();
4cff3ded
AW
49}
50
51//A GCode has been received
52void Robot::on_gcode_received(void * argument){
53 Gcode* gcode = static_cast<Gcode*>(argument);
436a2cd1
AW
54 gcode->call_on_gcode_execute_event_immediatly = false;
55 gcode->on_gcode_execute_event_called = false;
436a2cd1 56 //If the queue is empty, execute immediatly, otherwise attach to the last added block
3a4fa0c1 57 if( this->kernel->player->queue.size() == 0 ){
436a2cd1
AW
58 gcode->call_on_gcode_execute_event_immediatly = true;
59 this->execute_gcode(gcode);
60 if( gcode->on_gcode_execute_event_called == false ){
61 this->kernel->call_event(ON_GCODE_EXECUTE, gcode );
62 }
63 }else{
3a4fa0c1 64 Block* block = this->kernel->player->queue.get_ref( this->kernel->player->queue.size() - 1 );
436a2cd1 65 this->execute_gcode(gcode);
e0aa02f6 66 block->append_gcode(gcode);
436a2cd1
AW
67 }
68
4cff3ded
AW
69}
70
436a2cd1 71
4cff3ded
AW
72//See if the current Gcode line has some orders for us
73void Robot::execute_gcode(Gcode* gcode){
74
75 //Temp variables, constant properties are stored in the object
76 uint8_t next_action = NEXT_ACTION_DEFAULT;
23c90ba6 77 this->motion_mode = -1;
4cff3ded
AW
78
79 //G-letter Gcodes are mostly what the Robot module is interrested in, other modules also catch the gcode event and do stuff accordingly
80 if( gcode->has_letter('G')){
81 switch( (int) gcode->get_value('G') ){
82 case 0: this->motion_mode = MOTION_MODE_SEEK; break;
83 case 1: this->motion_mode = MOTION_MODE_LINEAR; break;
84 case 2: this->motion_mode = MOTION_MODE_CW_ARC; break;
85 case 3: this->motion_mode = MOTION_MODE_CCW_ARC; break;
86 case 17: this->select_plane(X_AXIS, Y_AXIS, Z_AXIS); break;
87 case 18: this->select_plane(X_AXIS, Z_AXIS, Y_AXIS); break;
88 case 19: this->select_plane(Y_AXIS, Z_AXIS, X_AXIS); break;
89 case 20:this->inch_mode = true; break;
90 case 21:this->inch_mode = false; break;
91 case 90:this->absolute_mode = true; break;
92 case 91:this->absolute_mode = false; break;
93 }
23c90ba6 94 }else{ return; }
4cff3ded
AW
95
96 //Get parameters
97 double target[3], offset[3];
98 clear_vector(target); clear_vector(offset);
99
100 memcpy(target, this->current_position, sizeof(target)); //default to last target
101
102 for(char letter = 'I'; letter <= 'K'; letter++){ if( gcode->has_letter(letter) ){ offset[letter-'I'] = this->to_millimeters(gcode->get_value(letter)); } }
103 for(char letter = 'X'; letter <= 'Z'; letter++){ if( gcode->has_letter(letter) ){ target[letter-'X'] = this->to_millimeters(gcode->get_value(letter)) + ( this->absolute_mode ? 0 : target[letter-'X']); } }
104
105 if( gcode->has_letter('F') ){ if( this->motion_mode == MOTION_MODE_SEEK ){ this->seek_rate = this->to_millimeters( gcode->get_value('F') ) / 60; }else{ this->feed_rate = this->to_millimeters( gcode->get_value('F') ) / 60; } }
106
107 //Perform any physical actions
108 switch( next_action ){
109 case NEXT_ACTION_DEFAULT:
110 switch(this->motion_mode){
111 case MOTION_MODE_CANCEL: break;
436a2cd1
AW
112 case MOTION_MODE_SEEK : this->append_line(gcode, target, this->seek_rate ); break;
113 case MOTION_MODE_LINEAR: this->append_line(gcode, target, this->feed_rate ); break;
114 case MOTION_MODE_CW_ARC: case MOTION_MODE_CCW_ARC: this->compute_arc(gcode, offset, target ); break;
4cff3ded
AW
115 }
116 break;
117 }
13e4a3f9 118
4cff3ded
AW
119 // As far as the parser is concerned, the position is now == target. In reality the
120 // motion control system might still be processing the action and the real tool position
121 // in any intermediate location.
122 memcpy(this->current_position, target, sizeof(double)*3); // this->position[] = target[];
123
124}
125
126// Convert target from millimeters to steps, and append this to the planner
127void Robot::append_milestone( double target[], double rate ){
128 int steps[3]; //Holds the result of the conversion
129
130 this->arm_solution->millimeters_to_steps( target, steps );
131
aab6cbba
AW
132 double deltas[3];
133 for(int axis=X_AXIS;axis<=Z_AXIS;axis++){deltas[axis]=target[axis]-this->last_milestone[axis];}
134
a1b7e9f0 135
aab6cbba 136 double millimeters_of_travel = sqrt( pow( deltas[X_AXIS], 2 ) + pow( deltas[Y_AXIS], 2 ) + pow( deltas[Z_AXIS], 2 ) );
436a2cd1
AW
137 //if( millimeters_of_travel < 0.001 ){ return; }
138 //double duration = millimeters_of_travel / rate;
139 double duration = 0;
140 if( rate > 0 ){ duration = millimeters_of_travel / rate; }
7b470506
AW
141
142 for(int axis=X_AXIS;axis<=Z_AXIS;axis++){
143 if( this->max_speeds[axis] > 0 ){
144 double axis_speed = ( fabs(deltas[axis]) / ( millimeters_of_travel / rate )) * 60;
436a2cd1
AW
145 if( axis_speed > this->max_speeds[axis] ){
146 rate = rate * ( this->max_speeds[axis] / axis_speed );
147 }
7b470506
AW
148 }
149 }
b66fb830 150 //this->kernel->serial->printf("dur: %f mm: %f rate: %f target_z: %f steps_z: %d deltas_z: %f \r\n", duration, millimeters_of_travel, rate, target[2], steps[2], deltas[2] );
4cff3ded 151
aab6cbba 152 this->kernel->planner->append_block( steps, rate*60, millimeters_of_travel, deltas );
4cff3ded 153
b66fb830 154 memcpy(this->last_milestone, target, sizeof(double)*3); // this->last_milestone[] = target[];
4cff3ded
AW
155
156}
157
436a2cd1 158void Robot::append_line(Gcode* gcode, double target[], double rate ){
4cff3ded 159
a1b7e9f0 160
4cff3ded
AW
161 // We cut the line into smaller segments. This is not usefull in a cartesian robot, but necessary for robots with rotational axes.
162 // In cartesian robot, a high "mm_per_line_segment" setting will prevent waste.
436a2cd1 163 gcode->millimeters_of_travel = sqrt( pow( target[X_AXIS]-this->current_position[X_AXIS], 2 ) + pow( target[Y_AXIS]-this->current_position[Y_AXIS], 2 ) + pow( target[Z_AXIS]-this->current_position[Z_AXIS], 2 ) );
4cff3ded 164
436a2cd1
AW
165 if( gcode->call_on_gcode_execute_event_immediatly == true ){
166 this->kernel->call_event(ON_GCODE_EXECUTE, gcode );
167 gcode->on_gcode_execute_event_called = true;
168 }
169
170 if (gcode->millimeters_of_travel == 0.0) {
171 this->append_milestone(this->current_position, 0.0);
172 return;
173 }
174
175 uint16_t segments = ceil( gcode->millimeters_of_travel/ this->mm_per_line_segment);
4cff3ded
AW
176 // A vector to keep track of the endpoint of each segment
177 double temp_target[3];
178 //Initialize axes
179 memcpy( temp_target, this->current_position, sizeof(double)*3); // temp_target[] = this->current_position[];
180
181 //For each segment
182 for( int i=0; i<segments-1; i++ ){
183 for(int axis=X_AXIS; axis <= Z_AXIS; axis++ ){ temp_target[axis] += ( target[axis]-this->current_position[axis] )/segments; }
184 this->append_milestone(temp_target, rate);
185 }
186 this->append_milestone(target, rate);
187}
188
4cff3ded 189
436a2cd1 190void Robot::append_arc(Gcode* gcode, double target[], double offset[], double radius, bool is_clockwise ){
aab6cbba
AW
191
192 double center_axis0 = this->current_position[this->plane_axis_0] + offset[this->plane_axis_0];
193 double center_axis1 = this->current_position[this->plane_axis_1] + offset[this->plane_axis_1];
194 double linear_travel = target[this->plane_axis_2] - this->current_position[this->plane_axis_2];
195 double r_axis0 = -offset[this->plane_axis_0]; // Radius vector from center to current location
196 double r_axis1 = -offset[this->plane_axis_1];
197 double rt_axis0 = target[this->plane_axis_0] - center_axis0;
198 double rt_axis1 = target[this->plane_axis_1] - center_axis1;
199
200 // CCW angle between position and target from circle center. Only one atan2() trig computation required.
201 double angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1);
202 if (angular_travel < 0) { angular_travel += 2*M_PI; }
203 if (is_clockwise) { angular_travel -= 2*M_PI; }
204
436a2cd1
AW
205 gcode->millimeters_of_travel = hypot(angular_travel*radius, fabs(linear_travel));
206
207 if( gcode->call_on_gcode_execute_event_immediatly == true ){
208 this->kernel->call_event(ON_GCODE_EXECUTE, gcode );
209 gcode->on_gcode_execute_event_called = true;
210 }
211
212 if (gcode->millimeters_of_travel == 0.0) {
213 this->append_milestone(this->current_position, 0.0);
214 return;
215 }
216
217 uint16_t segments = floor(gcode->millimeters_of_travel/this->mm_per_arc_segment);
aab6cbba
AW
218
219 double theta_per_segment = angular_travel/segments;
220 double linear_per_segment = linear_travel/segments;
221
222 /* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
223 and phi is the angle of rotation. Based on the solution approach by Jens Geisler.
224 r_T = [cos(phi) -sin(phi);
225 sin(phi) cos(phi] * r ;
226 For arc generation, the center of the circle is the axis of rotation and the radius vector is
227 defined from the circle center to the initial position. Each line segment is formed by successive
228 vector rotations. This requires only two cos() and sin() computations to form the rotation
229 matrix for the duration of the entire arc. Error may accumulate from numerical round-off, since
230 all double numbers are single precision on the Arduino. (True double precision will not have
231 round off issues for CNC applications.) Single precision error can accumulate to be greater than
232 tool precision in some cases. Therefore, arc path correction is implemented.
233
234 Small angle approximation may be used to reduce computation overhead further. This approximation
235 holds for everything, but very small circles and large mm_per_arc_segment values. In other words,
236 theta_per_segment would need to be greater than 0.1 rad and N_ARC_CORRECTION would need to be large
237 to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for
238 numerical drift error. N_ARC_CORRECTION may be on the order a hundred(s) before error becomes an
239 issue for CNC machines with the single precision Arduino calculations.
240 This approximation also allows mc_arc to immediately insert a line segment into the planner
241 without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied
242 a correction, the planner should have caught up to the lag caused by the initial mc_arc overhead.
243 This is important when there are successive arc motions.
244 */
245 // Vector rotation matrix values
246 double cos_T = 1-0.5*theta_per_segment*theta_per_segment; // Small angle approximation
247 double sin_T = theta_per_segment;
248
249 double arc_target[3];
250 double sin_Ti;
251 double cos_Ti;
252 double r_axisi;
253 uint16_t i;
254 int8_t count = 0;
255
256 // Initialize the linear axis
257 arc_target[this->plane_axis_2] = this->current_position[this->plane_axis_2];
258
259 for (i = 1; i<segments; i++) { // Increment (segments-1)
260
b66fb830 261 if (count < this->arc_correction ) {
aab6cbba
AW
262 // Apply vector rotation matrix
263 r_axisi = r_axis0*sin_T + r_axis1*cos_T;
264 r_axis0 = r_axis0*cos_T - r_axis1*sin_T;
265 r_axis1 = r_axisi;
266 count++;
267 } else {
268 // Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments.
269 // Compute exact location by applying transformation matrix from initial radius vector(=-offset).
270 cos_Ti = cos(i*theta_per_segment);
271 sin_Ti = sin(i*theta_per_segment);
272 r_axis0 = -offset[this->plane_axis_0]*cos_Ti + offset[this->plane_axis_1]*sin_Ti;
273 r_axis1 = -offset[this->plane_axis_0]*sin_Ti - offset[this->plane_axis_1]*cos_Ti;
274 count = 0;
275 }
276
277 // Update arc_target location
278 arc_target[this->plane_axis_0] = center_axis0 + r_axis0;
279 arc_target[this->plane_axis_1] = center_axis1 + r_axis1;
280 arc_target[this->plane_axis_2] += linear_per_segment;
281 this->append_milestone(arc_target, this->feed_rate);
282
283 }
284 // Ensure last segment arrives at target location.
285 this->append_milestone(target, this->feed_rate);
286}
287
4cff3ded 288
436a2cd1 289void Robot::compute_arc(Gcode* gcode, double offset[], double target[]){
aab6cbba
AW
290
291 // Find the radius
292 double radius = hypot(offset[this->plane_axis_0], offset[this->plane_axis_1]);
293
294 // Set clockwise/counter-clockwise sign for mc_arc computations
295 bool is_clockwise = false;
296 if( this->motion_mode == MOTION_MODE_CW_ARC ){ is_clockwise = true; }
297
298 // Append arc
436a2cd1 299 this->append_arc(gcode, target, offset, radius, is_clockwise );
aab6cbba
AW
300
301}
302
303
4cff3ded
AW
304// Convert from inches to millimeters ( our internal storage unit ) if needed
305inline double Robot::to_millimeters( double value ){
306 return this->inch_mode ? value/25.4 : value;
307}
308
309double Robot::theta(double x, double y){
310 double t = atan(x/fabs(y));
311 if (y>0) {return(t);} else {if (t>0){return(M_PI-t);} else {return(-M_PI-t);}}
312}
313
314void Robot::select_plane(uint8_t axis_0, uint8_t axis_1, uint8_t axis_2){
315 this->plane_axis_0 = axis_0;
316 this->plane_axis_1 = axis_1;
317 this->plane_axis_2 = axis_2;
318}
319
320