//Saves data from text boxes back into a joint public void saveJointDataFromPropertyBoxes(joint Joint) { Joint.update(textBox_joint_name, comboBox_joint_type); Joint.Parent.update(label_parent); Joint.Child.update(label_child); Joint.CoordinateSystemName = comboBox_origin.Text; Joint.AxisName = comboBox_axis.Text; Joint.Origin.update(textBox_joint_x, textBox_joint_y, textBox_joint_z, textBox_joint_roll, textBox_joint_pitch, textBox_joint_yaw); Joint.Axis.update(textBox_axis_x, textBox_axis_y, textBox_axis_z); if (textBox_limit_lower.Text == "" && textBox_limit_upper.Text == "" && textBox_limit_effort.Text == "" && textBox_limit_velocity.Text == "") { if (Joint.type == "prismatic" || Joint.type == "revolute") { if (Joint.Limit == null) { Joint.Limit = new limit(); } else { Joint.Limit.effort = 0; Joint.Limit.velocity = 0; } } else { Joint.Limit = null; } } else { if (Joint.Limit == null) { Joint.Limit = new limit(); } Joint.Limit.setValues(textBox_limit_lower, textBox_limit_upper, textBox_limit_effort, textBox_limit_velocity); } if (textBox_calibration_rising.Text == "" && textBox_calibration_falling.Text == "") { Joint.Calibration = null; } else { if (Joint.Calibration == null) { Joint.Calibration = new calibration(); } Joint.Calibration.setValues(textBox_calibration_rising, textBox_calibration_falling); } if (textBox_friction.Text == "" && textBox_damping.Text == "") { Joint.Dynamics = null; } else { if (Joint.Dynamics == null) { Joint.Dynamics = new dynamics(); } Joint.Dynamics.setValues(textBox_damping, textBox_friction); } if (textBox_soft_lower.Text == "" && textBox_soft_upper.Text == "" && textBox_k_position.Text == "" && textBox_k_velocity.Text == "") { Joint.Safety = null; } else { if (Joint.Safety == null) { Joint.Safety = new safety_controller(); } Joint.Safety.setValues(textBox_soft_lower, textBox_soft_upper, textBox_k_position, textBox_k_velocity); } }