Skip to content

Commit 0fdb47e

Browse files
committed
release
1 parent 7b00090 commit 0fdb47e

19 files changed

+1309
-63
lines changed

core/dexter_defaults.js

Lines changed: 22 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,10 +37,31 @@ Dexter.prototype.defaults_read = function(callback = null){
3737
let the_url = this.defaults_url()
3838
let the_dex_inst = this
3939
let normal_defaults_read_cb = (function(err, content){
40-
if(err) { dde_error("Dexter." + the_dex_inst.name + ".defaults_read errored with url: " +
40+
if(err) { //Often becuse Defaults.make_ins isn't on the Dexter.
41+
//so print a warning and use Dexter.defaults instead
42+
//and let the Job proceed
43+
if (typeof(err) !== "string"){
44+
err = err.toString()
45+
}
46+
let extra_error_message = ""
47+
if(err.includes("404")){
48+
extra_error_message = "<br/>/serve_samba/share/Defaults.make_ins does not exist on Dexter." + the_dex_inst.name
49+
}
50+
let defaults_copy = JSON.parse(JSON.stringify(Dexter.defaults))
51+
the_dex_inst.defaults = defaults_copy
52+
warning("Could not read : " + the_url + " + due to:<br/>" +
53+
err + extra_error_message +
54+
"<br/>so Dexter." + the_dex_inst.name +
55+
".defaults has been set to a copy of Dexter.defaults."
56+
)
57+
if (callback) {
58+
callback.call(the_dex_inst, null)
59+
}
60+
/*dde_error("Dexter." + the_dex_inst.name + ".defaults_read errored with url: " +
4161
the_url + "<br/>and error message: " +
4262
err.message +
4363
"<br/>You can set a Job's robot to the idealized defaults values by<br/>passing in a Job's 'get_dexter_defaults' to true.")
64+
*/
4465
}
4566
else {
4667
try {

core/dextersim.js

Lines changed: 32 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ DexterSim = class DexterSim{
120120
if(str.endsWith(";")) {
121121
str = str.substring(0, str.length - 1) //cut off the semicolon on the end
122122
}
123-
let split_str = str.split(" ")
123+
let split_str = str.split(/[ ,]+/)//separator can be space, comma, or any combination of them, was: " " which didn't handle commas
124124
//if its a var length instruction, then an integer is in place of the oplet and the oplet is one later
125125
let orig_oplet_maybe = split_str[Instruction.INSTRUCTION_TYPE]
126126
if(!Robot.is_oplet(orig_oplet_maybe)) { //assume its an integer for a variable-length instruction
@@ -209,6 +209,37 @@ DexterSim = class DexterSim{
209209
case "h": //doesn't go on instruction queue, just immediate ack
210210
ds_instance.ack_reply(instruction_array)
211211
break;
212+
case "j":
213+
console.log("DexterSim.send passed 'j' oplet: " + instruction_array)
214+
ds_instance.queuej_instance.add_to_queue(instruction_array)
215+
ds_instance.ack_reply_maybe(instruction_array) //send back the original
216+
break;
217+
case "M": //move to. convert to an "a" array and use that.
218+
//note: doesn't encode j6 and j7.
219+
//see: https://github.com/HaddingtonDynamics/OCADO/wiki/Command-oplet-instruction
220+
let ins_arr_a = instruction_array.slice(0, Instruction.INSTRUCTION_ARG0)
221+
ins_arr_a[Instruction.INSTRUCTION_TYPE] = "a"
222+
let xyz_meters = [instruction_array[Instruction.INSTRUCTION_ARG0] / 1000000, //x
223+
instruction_array[Instruction.INSTRUCTION_ARG1] / 1000000, //y
224+
instruction_array[Instruction.INSTRUCTION_ARG2] / 1000000] //z
225+
226+
let direction = [instruction_array[Instruction.INSTRUCTION_ARG3],
227+
instruction_array[Instruction.INSTRUCTION_ARG4],
228+
instruction_array[Instruction.INSTRUCTION_ARG5]]
229+
230+
let config = [instruction_array[Instruction.INSTRUCTION_ARG6],
231+
instruction_array[Instruction.INSTRUCTION_ARG7],
232+
instruction_array[Instruction.INSTRUCTION_ARG8]]
233+
234+
let new_angles_deg = Kin.xyz_to_J_angles(xyz_meters, direction, config)
235+
for(let i = 0; i < 5; i++) {
236+
let deg = new_angles_deg[i]
237+
let arcsec = deg * 3600
238+
ins_arr_a.push(arcsec)
239+
}
240+
ds_instance.queue_instance.add_to_queue(ins_arr_a)
241+
ds_instance.ack_reply_maybe(instruction_array) //return the orig "M" array
242+
break;
212243
case "P": //does not go on queue //ds_instance.queue_instance.add_to_queue(instruction_array)
213244
//pid_move_all_joints for j6 and 7 are handled diffrently than J1 thru 5.
214245
//IF we get a pid_maj for j6 and/or j7, just treat it like

core/index.js

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
1-
global.dde_version = "3.9.0" //require("../package.json").version
2-
global.dde_release_date = "Feb 9, 2024" //require("../package.json").release_dat9
1+
global.dde_version = "3.9.1" //require("../package.json").version
2+
global.dde_release_date = "Mar 23, 2024" //require("../package.json").release_dat9
33
console.log("dde_version: " + global.dde_version + " dde_release_date: " + global.dde_release_date +
44
"\nRead electron_dde/core/job_engine_doc.txt for how to use the Job Engine.\n")
55

@@ -173,6 +173,8 @@ var {convertArrayBufferToString, convertStringToArrayBuffer,
173173
serial_disconnect, serial_disconnect_all, serial_flush,
174174
serial_get_or_make_port, serial_path_to_port_map,
175175
serial_port_path_to_info_map, serial_port_init, serial_send, serial_send_low_level} = require("./serial.js")
176+
require("./servo.js") //defines globalThis.Servo
177+
176178

177179
var {close_readline, set_keep_alive_value, write_to_stdout} = require("./stdio.js")
178180

core/je_and_browser_code.js

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -169,7 +169,9 @@ function out(val="", color="black", temp=false, code=null){
169169
}
170170
if(window["document"]){
171171
let orig_focus_elt = document.activeElement
172-
orig_focus_elt.focus()
172+
if(orig_focus_elt) {
173+
orig_focus_elt.focus()
174+
}
173175
}
174176
if (temp){
175177
return "dont_print"

core/job.js

Lines changed: 62 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -1582,25 +1582,31 @@ Job.prototype.if_robot_status_error_default = function(){
15821582
let sim_actual = Robot.get_simulate_actual(rob.simulate)
15831583
if((sim_actual === false) || (sim_actual === "both")){
15841584
try{ let path = "Dexter." + rob.name + ":/srv/samba/share/errors.log"
1585-
read_file_async(path, undefined, function(err, content){
1586-
if(err) {warning("Could not find: " + path)}
1587-
else {
1588-
if((typeof(content) != "string") ||
1589-
(content.length == 0)){
1590-
content == "<i>errors.log is empty</i>"
1591-
}
1592-
else {
1593-
content = replace_substrings(content, "\n", "<br/>")
1594-
content = "Content of " + path + "<br/><code>" + content + "</code>"
1595-
setTimeout(function(){write_file_async(path, "")},
1596-
400) //give the read_file job a chance to finish properly
1585+
read_file_async(path, undefined,function(err, content){
1586+
if(err) {warning("Could not find: " + path + " with error: " + err.message)}
1587+
else {
1588+
let msg = ""
1589+
if((typeof(content) != "string") ||
1590+
(content.length == 0)){
1591+
msg = "<i>errors.log is empty</i>"
1592+
}
1593+
else {
1594+
let content_arr = content.split("\n")
1595+
let last_line = content_arr.pop()
1596+
if(last_line.trim().length === 0){ //if the last line is empty, this gets 2nd to last line.
1597+
last_line = content_arr.pop()
15971598
}
1598-
out(content)
1599+
last_line = last_line.replaceAll(",", ",<br/>")
1600+
msg += "<details><summary>Last error in " + path + "</summary><code>" + last_line + "</code></details>"
1601+
//setTimeout(function(){DDEFile.write_file_async(path, "")},
1602+
// 400) //give the read_file job a chance to finish properly
15991603
}
1600-
})
1601-
}
1604+
out(msg)
1605+
}
1606+
})
1607+
}
16021608
catch(err) {warning("In Job.prototype.if_robot_status_error_default, could not get the errors.log file<br/>" +
1603-
" for " + "Dexter." + rob.name) }
1609+
" for " + "Dexter." + rob.name + " with error: " + err.message) }
16041610
}
16051611
}
16061612
return Control.error(msg)
@@ -1635,22 +1641,52 @@ Job.prototype.if_dexter_connect_error_default = function(robot_name){
16351641
Job.prototype.rs_to_error_message = function(robot_status){
16361642
let error_code = robot_status[Dexter.ERROR_CODE]
16371643
let oplet_error_code = error_code & 0xFF //lower 8 bits
1638-
let msg = "error_code: " + error_code
16391644
let oplet = robot_status[Dexter.INSTRUCTION_TYPE]
1645+
let msg = "oplet: " + oplet + " oplet_error_code: " + oplet_error_code
16401646
if (error_code > 0) {
1641-
if((oplet == "r") || (oplet == "w")) {
1642-
let linux_msg = linux_error_message(oplet_error_code)
1643-
msg += "Error on oplet 'r' (read_file) with Linux error of: " + linux_msg
1647+
if((oplet === "r") || (oplet === "w")) {
1648+
let linux_msg = globalThis.linux_error_message(oplet_error_code)
1649+
msg += " Linux error: " + linux_msg
1650+
}
1651+
else if((oplet_error_code === 8) && ((oplet === "a") || (oplet === "P") || (oplet === "j"))) {
1652+
msg += " Goal position outside joint boundries."
1653+
}
1654+
else if(oplet === "j") {
1655+
msg += " j_move error: "
1656+
if(oplet_error_code === 4){
1657+
msg += " Ruckig compute error. Check JointHardwareMax??? configuration."
1658+
}
1659+
else if(oplet_error_code === 5){
1660+
msg += " Ruckig cannot meet specified duration."
1661+
}
1662+
else if(oplet_error_code === 6){
1663+
msg += " Replay error. Under-run or over-speed."
1664+
}
1665+
else if(oplet_error_code === 7){
1666+
msg += " j_move system in an error state."
1667+
}
1668+
msg += " Clear using 'j' oplet without args."
16441669
}
16451670
else {
1646-
if (oplet_error_code == 1) {msg += " oplet:" + oplet + " is unknown to Dexter. Please upgrade Dexter firmware and gateware.<br/>"}
1647-
else if (oplet_error_code == 2) {msg += " on oplet:" + oplet + " communication error.<br/>"}
1648-
else {msg += " on oplet:" + oplet + " Unknown error.<br/>"}
1671+
if (oplet_error_code == 0) { } //don't add an extra message
1672+
else if (oplet_error_code == 1) {msg += " oplet is unknown to Dexter. Please upgrade Dexter firmware and gateware.<br/>"}
1673+
else if (oplet_error_code == 2) {msg += " communication error. No semicolon at end of instruction.<br/>"}
1674+
else if (oplet_error_code == 3) {msg += " invalid parameter.<br/>"}
1675+
else {msg += " Unknown error.<br/>"}
16491676
}
1677+
//error flags
16501678
if(error_code & (1 << 10)) {msg+=" Firmware - Gateware Mismatch. Update system. Fatal error.<br/>"}
1651-
if(error_code & (1 << 27)) {msg+=" SPAN Servo, Joint 7. r 0 errors.log <br/>"}
1652-
if(error_code & (1 << 28)) {msg+=" ROLL Servo, Joint 6. r 0 errors.log <br/>"}
1653-
if(error_code & (1 << 30)) {msg+=" Joint Monitor. r 0 errors.log <br/>"}
1679+
if(error_code & (1 << 24)) {msg+=" P-Stop error code.<br/>"}
1680+
if(error_code & (1 << 25)) {msg+=" Encoder error.<br/>"}
1681+
if(error_code & (1 << 26)) {msg+=" Kinematics error.<br/>"}
1682+
if(error_code & (1 << 27)) {msg+=" SPAN Servo, Joint 7.<br/>"}
1683+
if(error_code & (1 << 28)) {msg+=" ROLL Servo, Joint 6.<br/>"}
1684+
if(error_code & (1 << 30)) {msg+=" Joint Monitor.<br/>"}
1685+
for(let i = 11; i < 24; i++){
1686+
if(error_code & (1 << i)) {
1687+
msg+=" Unknown error flag on bit: " + i + ".<br/>"
1688+
}
1689+
}
16541690
}
16551691
return msg
16561692
}

core/robot.js

Lines changed: 26 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1050,6 +1050,9 @@ Dexter = class Dexter extends Robot {
10501050
this.pid_angles = [0, 0, 0, 0, 0, 0, 0]
10511051
//this.processing_flush = false //primarily used as a check. a_robot.send shouldn't get called while this var is true
10521052
this.busy_job_array = []
1053+
1054+
this.servos = Servo.make_servos_for_dexter()
1055+
10531056
Robot.set_robot_name(this.name, this)
10541057
//ensures the last name on the list is the latest with no redundancy
10551058
let i = Dexter.all_names.indexOf(this.name)
@@ -2341,14 +2344,30 @@ Dexter.prototype.turn_on_j6_and_j7_torque = function(){
23412344
this.set_parameter("ServoSet", 1, 24, 1)] //J7, for XL-320 motors
23422345
}
23432346

2347+
Dexter.set_follow_me = function(){
2348+
return [make_ins("S", "RunFile", "setFollowMeMode.make_ins"),
2349+
Dexter.turn_off_j6_and_j7_torque(),
2350+
Dexter.set_parameter("MotorEnable", 0)
2351+
]
2352+
}
2353+
2354+
Dexter.prototype.set_follow_me = function(){
2355+
return [make_ins("S", "RunFile", "setFollowMeMode.make_ins", this),
2356+
this.turn_off_j6_and_j7_torque(),
2357+
this.set_parameter("MotorEnable", 0)]}
2358+
2359+
23442360

23452361
//from Dexter_Modes.js (these are instructions. The fns return an array of instructions
2346-
Dexter.set_follow_me = function(){ return make_ins("S", "RunFile", "setFollowMeMode.make_ins")
2347-
//Dexter.turn_off_j6_and_j7_torque()]
2348-
}
2349-
Dexter.prototype.set_follow_me = function(){ return make_ins("S", "RunFile", "setFollowMeMode.make_ins", this)
2350-
//this.turn_off_j6_and_j7_torque()]
2351-
}
2362+
Dexter.set_keep_position = function(){
2363+
return [make_ins("S", "RunFile", "setKeepPositionMode.make_ins"),
2364+
Dexter.turn_on_j6_and_j7_torque(),
2365+
Dexter.set_parameter("MotorEnable", 1)]}
2366+
2367+
Dexter.prototype.set_keep_position = function(){
2368+
return [make_ins("S", "RunFile", "setKeepPositionMode.make_ins", this),
2369+
this.turn_on_j6_and_j7_torque(),
2370+
this.set_parameter("MotorEnable", 1)]}
23522371

23532372
Dexter.set_force_protect = function(){ return make_ins("S", "RunFile", "setForceProtectMode.make_ins")
23542373
//Dexter.turn_on_j6_and_j7_torque()]
@@ -2357,13 +2376,6 @@ Dexter.prototype.set_force_protect = function(){ return make_ins("S", "RunFile"
23572376
//this.turn_on_j6_and_j7_torque()]
23582377
}
23592378

2360-
Dexter.set_keep_position = function(){ return make_ins("S", "RunFile", "setKeepPositionMode.make_ins")
2361-
//Dexter.turn_on_j6_and_j7_torque()]
2362-
}
2363-
Dexter.prototype.set_keep_position = function(){ return make_ins("S", "RunFile", "setKeepPositionMode.make_ins", this)
2364-
//this.turn_on_j6_and_j7_torque()]
2365-
}
2366-
23672379
Dexter.set_open_loop = function(){ return make_ins("S", "RunFile", "setOpenLoopMode.make_ins")
23682380
// Dexter.turn_on_j6_and_j7_torque()] //use to be in before Nov 3, 2022 but James N says shouldn't be there
23692381
}
@@ -2772,7 +2784,7 @@ Dexter.prototype.set_link_lengths_using_dde_db = function(job_to_start){
27722784
this.J3_angle_min = Dexter.J3_ANGLE_MIN
27732785
this.J4_angle_min = Dexter.J4_ANGLE_MIN
27742786
this.J5_angle_min = Dexter.J5_ANGLE_MIN
2775-
this.J6_angle_min = Dexter.J6_ANGLE_MIN
2787+
this.J6_angle_min = ƒ
27762788
this.J7_angle_min = Dexter.J7_ANGLE_MIN
27772789
27782790
this.J1_angle_max = Dexter.J1_ANGLE_MAX

0 commit comments

Comments
 (0)