Skip to content

Commit

Permalink
release
Browse files Browse the repository at this point in the history
  • Loading branch information
cfry committed Mar 25, 2024
1 parent 7b00090 commit 0fdb47e
Show file tree
Hide file tree
Showing 19 changed files with 1,309 additions and 63 deletions.
23 changes: 22 additions & 1 deletion core/dexter_defaults.js
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,31 @@ Dexter.prototype.defaults_read = function(callback = null){
let the_url = this.defaults_url()
let the_dex_inst = this
let normal_defaults_read_cb = (function(err, content){
if(err) { dde_error("Dexter." + the_dex_inst.name + ".defaults_read errored with url: " +
if(err) { //Often becuse Defaults.make_ins isn't on the Dexter.
//so print a warning and use Dexter.defaults instead
//and let the Job proceed
if (typeof(err) !== "string"){
err = err.toString()
}
let extra_error_message = ""
if(err.includes("404")){
extra_error_message = "<br/>/serve_samba/share/Defaults.make_ins does not exist on Dexter." + the_dex_inst.name
}
let defaults_copy = JSON.parse(JSON.stringify(Dexter.defaults))
the_dex_inst.defaults = defaults_copy
warning("Could not read : " + the_url + " + due to:<br/>" +
err + extra_error_message +
"<br/>so Dexter." + the_dex_inst.name +
".defaults has been set to a copy of Dexter.defaults."
)
if (callback) {
callback.call(the_dex_inst, null)
}
/*dde_error("Dexter." + the_dex_inst.name + ".defaults_read errored with url: " +
the_url + "<br/>and error message: " +
err.message +
"<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.")
*/
}
else {
try {
Expand Down
33 changes: 32 additions & 1 deletion core/dextersim.js
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ DexterSim = class DexterSim{
if(str.endsWith(";")) {
str = str.substring(0, str.length - 1) //cut off the semicolon on the end
}
let split_str = str.split(" ")
let split_str = str.split(/[ ,]+/)//separator can be space, comma, or any combination of them, was: " " which didn't handle commas
//if its a var length instruction, then an integer is in place of the oplet and the oplet is one later
let orig_oplet_maybe = split_str[Instruction.INSTRUCTION_TYPE]
if(!Robot.is_oplet(orig_oplet_maybe)) { //assume its an integer for a variable-length instruction
Expand Down Expand Up @@ -209,6 +209,37 @@ DexterSim = class DexterSim{
case "h": //doesn't go on instruction queue, just immediate ack
ds_instance.ack_reply(instruction_array)
break;
case "j":
console.log("DexterSim.send passed 'j' oplet: " + instruction_array)
ds_instance.queuej_instance.add_to_queue(instruction_array)
ds_instance.ack_reply_maybe(instruction_array) //send back the original
break;
case "M": //move to. convert to an "a" array and use that.
//note: doesn't encode j6 and j7.
//see: https://github.com/HaddingtonDynamics/OCADO/wiki/Command-oplet-instruction
let ins_arr_a = instruction_array.slice(0, Instruction.INSTRUCTION_ARG0)
ins_arr_a[Instruction.INSTRUCTION_TYPE] = "a"
let xyz_meters = [instruction_array[Instruction.INSTRUCTION_ARG0] / 1000000, //x
instruction_array[Instruction.INSTRUCTION_ARG1] / 1000000, //y
instruction_array[Instruction.INSTRUCTION_ARG2] / 1000000] //z

let direction = [instruction_array[Instruction.INSTRUCTION_ARG3],
instruction_array[Instruction.INSTRUCTION_ARG4],
instruction_array[Instruction.INSTRUCTION_ARG5]]

let config = [instruction_array[Instruction.INSTRUCTION_ARG6],
instruction_array[Instruction.INSTRUCTION_ARG7],
instruction_array[Instruction.INSTRUCTION_ARG8]]

let new_angles_deg = Kin.xyz_to_J_angles(xyz_meters, direction, config)
for(let i = 0; i < 5; i++) {
let deg = new_angles_deg[i]
let arcsec = deg * 3600
ins_arr_a.push(arcsec)
}
ds_instance.queue_instance.add_to_queue(ins_arr_a)
ds_instance.ack_reply_maybe(instruction_array) //return the orig "M" array
break;
case "P": //does not go on queue //ds_instance.queue_instance.add_to_queue(instruction_array)
//pid_move_all_joints for j6 and 7 are handled diffrently than J1 thru 5.
//IF we get a pid_maj for j6 and/or j7, just treat it like
Expand Down
6 changes: 4 additions & 2 deletions core/index.js
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
global.dde_version = "3.9.0" //require("../package.json").version
global.dde_release_date = "Feb 9, 2024" //require("../package.json").release_dat9
global.dde_version = "3.9.1" //require("../package.json").version
global.dde_release_date = "Mar 23, 2024" //require("../package.json").release_dat9
console.log("dde_version: " + global.dde_version + " dde_release_date: " + global.dde_release_date +
"\nRead electron_dde/core/job_engine_doc.txt for how to use the Job Engine.\n")

Expand Down Expand Up @@ -173,6 +173,8 @@ var {convertArrayBufferToString, convertStringToArrayBuffer,
serial_disconnect, serial_disconnect_all, serial_flush,
serial_get_or_make_port, serial_path_to_port_map,
serial_port_path_to_info_map, serial_port_init, serial_send, serial_send_low_level} = require("./serial.js")
require("./servo.js") //defines globalThis.Servo


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

Expand Down
4 changes: 3 additions & 1 deletion core/je_and_browser_code.js
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,9 @@ function out(val="", color="black", temp=false, code=null){
}
if(window["document"]){
let orig_focus_elt = document.activeElement
orig_focus_elt.focus()
if(orig_focus_elt) {
orig_focus_elt.focus()
}
}
if (temp){
return "dont_print"
Expand Down
88 changes: 62 additions & 26 deletions core/job.js
Original file line number Diff line number Diff line change
Expand Up @@ -1582,25 +1582,31 @@ Job.prototype.if_robot_status_error_default = function(){
let sim_actual = Robot.get_simulate_actual(rob.simulate)
if((sim_actual === false) || (sim_actual === "both")){
try{ let path = "Dexter." + rob.name + ":/srv/samba/share/errors.log"
read_file_async(path, undefined, function(err, content){
if(err) {warning("Could not find: " + path)}
else {
if((typeof(content) != "string") ||
(content.length == 0)){
content == "<i>errors.log is empty</i>"
}
else {
content = replace_substrings(content, "\n", "<br/>")
content = "Content of " + path + "<br/><code>" + content + "</code>"
setTimeout(function(){write_file_async(path, "")},
400) //give the read_file job a chance to finish properly
read_file_async(path, undefined,function(err, content){
if(err) {warning("Could not find: " + path + " with error: " + err.message)}
else {
let msg = ""
if((typeof(content) != "string") ||
(content.length == 0)){
msg = "<i>errors.log is empty</i>"
}
else {
let content_arr = content.split("\n")
let last_line = content_arr.pop()
if(last_line.trim().length === 0){ //if the last line is empty, this gets 2nd to last line.
last_line = content_arr.pop()
}
out(content)
last_line = last_line.replaceAll(",", ",<br/>")
msg += "<details><summary>Last error in " + path + "</summary><code>" + last_line + "</code></details>"
//setTimeout(function(){DDEFile.write_file_async(path, "")},
// 400) //give the read_file job a chance to finish properly
}
})
}
out(msg)
}
})
}
catch(err) {warning("In Job.prototype.if_robot_status_error_default, could not get the errors.log file<br/>" +
" for " + "Dexter." + rob.name) }
" for " + "Dexter." + rob.name + " with error: " + err.message) }
}
}
return Control.error(msg)
Expand Down Expand Up @@ -1635,22 +1641,52 @@ Job.prototype.if_dexter_connect_error_default = function(robot_name){
Job.prototype.rs_to_error_message = function(robot_status){
let error_code = robot_status[Dexter.ERROR_CODE]
let oplet_error_code = error_code & 0xFF //lower 8 bits
let msg = "error_code: " + error_code
let oplet = robot_status[Dexter.INSTRUCTION_TYPE]
let msg = "oplet: " + oplet + " oplet_error_code: " + oplet_error_code
if (error_code > 0) {
if((oplet == "r") || (oplet == "w")) {
let linux_msg = linux_error_message(oplet_error_code)
msg += "Error on oplet 'r' (read_file) with Linux error of: " + linux_msg
if((oplet === "r") || (oplet === "w")) {
let linux_msg = globalThis.linux_error_message(oplet_error_code)
msg += " Linux error: " + linux_msg
}
else if((oplet_error_code === 8) && ((oplet === "a") || (oplet === "P") || (oplet === "j"))) {
msg += " Goal position outside joint boundries."
}
else if(oplet === "j") {
msg += " j_move error: "
if(oplet_error_code === 4){
msg += " Ruckig compute error. Check JointHardwareMax??? configuration."
}
else if(oplet_error_code === 5){
msg += " Ruckig cannot meet specified duration."
}
else if(oplet_error_code === 6){
msg += " Replay error. Under-run or over-speed."
}
else if(oplet_error_code === 7){
msg += " j_move system in an error state."
}
msg += " Clear using 'j' oplet without args."
}
else {
if (oplet_error_code == 1) {msg += " oplet:" + oplet + " is unknown to Dexter. Please upgrade Dexter firmware and gateware.<br/>"}
else if (oplet_error_code == 2) {msg += " on oplet:" + oplet + " communication error.<br/>"}
else {msg += " on oplet:" + oplet + " Unknown error.<br/>"}
if (oplet_error_code == 0) { } //don't add an extra message
else if (oplet_error_code == 1) {msg += " oplet is unknown to Dexter. Please upgrade Dexter firmware and gateware.<br/>"}
else if (oplet_error_code == 2) {msg += " communication error. No semicolon at end of instruction.<br/>"}
else if (oplet_error_code == 3) {msg += " invalid parameter.<br/>"}
else {msg += " Unknown error.<br/>"}
}
//error flags
if(error_code & (1 << 10)) {msg+=" Firmware - Gateware Mismatch. Update system. Fatal error.<br/>"}
if(error_code & (1 << 27)) {msg+=" SPAN Servo, Joint 7. r 0 errors.log <br/>"}
if(error_code & (1 << 28)) {msg+=" ROLL Servo, Joint 6. r 0 errors.log <br/>"}
if(error_code & (1 << 30)) {msg+=" Joint Monitor. r 0 errors.log <br/>"}
if(error_code & (1 << 24)) {msg+=" P-Stop error code.<br/>"}
if(error_code & (1 << 25)) {msg+=" Encoder error.<br/>"}
if(error_code & (1 << 26)) {msg+=" Kinematics error.<br/>"}
if(error_code & (1 << 27)) {msg+=" SPAN Servo, Joint 7.<br/>"}
if(error_code & (1 << 28)) {msg+=" ROLL Servo, Joint 6.<br/>"}
if(error_code & (1 << 30)) {msg+=" Joint Monitor.<br/>"}
for(let i = 11; i < 24; i++){
if(error_code & (1 << i)) {
msg+=" Unknown error flag on bit: " + i + ".<br/>"
}
}
}
return msg
}
Expand Down
40 changes: 26 additions & 14 deletions core/robot.js
Original file line number Diff line number Diff line change
Expand Up @@ -1050,6 +1050,9 @@ Dexter = class Dexter extends Robot {
this.pid_angles = [0, 0, 0, 0, 0, 0, 0]
//this.processing_flush = false //primarily used as a check. a_robot.send shouldn't get called while this var is true
this.busy_job_array = []

this.servos = Servo.make_servos_for_dexter()

Robot.set_robot_name(this.name, this)
//ensures the last name on the list is the latest with no redundancy
let i = Dexter.all_names.indexOf(this.name)
Expand Down Expand Up @@ -2341,14 +2344,30 @@ Dexter.prototype.turn_on_j6_and_j7_torque = function(){
this.set_parameter("ServoSet", 1, 24, 1)] //J7, for XL-320 motors
}

Dexter.set_follow_me = function(){
return [make_ins("S", "RunFile", "setFollowMeMode.make_ins"),
Dexter.turn_off_j6_and_j7_torque(),
Dexter.set_parameter("MotorEnable", 0)
]
}

Dexter.prototype.set_follow_me = function(){
return [make_ins("S", "RunFile", "setFollowMeMode.make_ins", this),
this.turn_off_j6_and_j7_torque(),
this.set_parameter("MotorEnable", 0)]}



//from Dexter_Modes.js (these are instructions. The fns return an array of instructions
Dexter.set_follow_me = function(){ return make_ins("S", "RunFile", "setFollowMeMode.make_ins")
//Dexter.turn_off_j6_and_j7_torque()]
}
Dexter.prototype.set_follow_me = function(){ return make_ins("S", "RunFile", "setFollowMeMode.make_ins", this)
//this.turn_off_j6_and_j7_torque()]
}
Dexter.set_keep_position = function(){
return [make_ins("S", "RunFile", "setKeepPositionMode.make_ins"),
Dexter.turn_on_j6_and_j7_torque(),
Dexter.set_parameter("MotorEnable", 1)]}

Dexter.prototype.set_keep_position = function(){
return [make_ins("S", "RunFile", "setKeepPositionMode.make_ins", this),
this.turn_on_j6_and_j7_torque(),
this.set_parameter("MotorEnable", 1)]}

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

Dexter.set_keep_position = function(){ return make_ins("S", "RunFile", "setKeepPositionMode.make_ins")
//Dexter.turn_on_j6_and_j7_torque()]
}
Dexter.prototype.set_keep_position = function(){ return make_ins("S", "RunFile", "setKeepPositionMode.make_ins", this)
//this.turn_on_j6_and_j7_torque()]
}

Dexter.set_open_loop = function(){ return make_ins("S", "RunFile", "setOpenLoopMode.make_ins")
// Dexter.turn_on_j6_and_j7_torque()] //use to be in before Nov 3, 2022 but James N says shouldn't be there
}
Expand Down Expand Up @@ -2772,7 +2784,7 @@ Dexter.prototype.set_link_lengths_using_dde_db = function(job_to_start){
this.J3_angle_min = Dexter.J3_ANGLE_MIN
this.J4_angle_min = Dexter.J4_ANGLE_MIN
this.J5_angle_min = Dexter.J5_ANGLE_MIN
this.J6_angle_min = Dexter.J6_ANGLE_MIN
this.J6_angle_min = ƒ
this.J7_angle_min = Dexter.J7_ANGLE_MIN
this.J1_angle_max = Dexter.J1_ANGLE_MAX
Expand Down
Loading

0 comments on commit 0fdb47e

Please sign in to comment.