/// Override _all_ time, jacobian etc. updating. /// In detail, it computes jacobians, violations, etc. and stores /// results in inner structures. public override void update(double mytime, bool update_assets = true) { // Inherit time changes of parent class (ChLink), basically doing nothing :) base.update(mytime, update_assets); // compute jacobians ChVector AbsDist = Body1.TransformPointLocalToParent(pos1) - Body2.TransformPointLocalToParent(pos2); curr_dist = AbsDist.Length(); ChVector D2abs = ChVector.Vnorm(AbsDist); ChVector D2relB = Body2.TransformDirectionParentToLocal(D2abs); ChVector D2relA = Body1.TransformDirectionParentToLocal(D2abs); ChVector CqAx = D2abs; ChVector CqBx = -D2abs; ChVector CqAr = -ChVector.Vcross(D2relA, pos1); ChVector CqBr = ChVector.Vcross(D2relB, pos2); Cx.Get_Cq_a().ElementN(0) = CqAx.x; Cx.Get_Cq_a().ElementN(1) = CqAx.y; Cx.Get_Cq_a().ElementN(2) = CqAx.z; Cx.Get_Cq_a().ElementN(3) = CqAr.x; Cx.Get_Cq_a().ElementN(4) = CqAr.y; Cx.Get_Cq_a().ElementN(5) = CqAr.z; Cx.Get_Cq_b().ElementN(0) = CqBx.x; Cx.Get_Cq_b().ElementN(1) = CqBx.y; Cx.Get_Cq_b().ElementN(2) = CqBx.z; Cx.Get_Cq_b().ElementN(3) = CqBr.x; Cx.Get_Cq_b().ElementN(4) = CqBr.y; Cx.Get_Cq_b().ElementN(5) = CqBr.z; //***TO DO*** C_dt? C_dtdt? (may be never used..) }
/// Get the link coordinate system, expressed relative to Body2 (the 'master' /// body). This represents the 'main' reference of the link: reaction forces /// are expressed in this coordinate system. /// (It is the coordinate system of the contact plane relative to Body2) public override ChCoordsys GetLinkRelativeCoords() { //ChVector D2local; ChVector D2temp = (ChVector.Vnorm(Body1.TransformPointLocalToParent(pos1) - Body2.TransformPointLocalToParent(pos2))); ChVector D2rel = Body2.TransformDirectionParentToLocal(D2temp); ChVector Vx = new ChVector(0, 0, 0), Vy = new ChVector(0, 0, 0), Vz = new ChVector(0, 0, 0); //ChMatrix33<double> rel_matrix = new ChMatrix33<double>(); ChVector.XdirToDxDyDz(D2rel, ChVector.VECT_Y, ref Vx, ref Vy, ref Vz); rel_matrix.Set_A_axis(Vx, Vy, Vz); ChQuaternion Ql2 = rel_matrix.Get_A_quaternion(); return(new ChCoordsys(pos2, Ql2)); }
/// Initialize this joint by specifying the two bodies to be connected, a point /// and a direction on body1 defining the revolute joint, and a point on the /// second body defining the spherical joint. If local = true, it is assumed /// that these quantities are specified in the local body frames. Otherwise, /// it is assumed that they are specified in the absolute frame. The imposed /// distance between the two points can be either inferred from the provided /// configuration (auto_distance = true) or specified explicitly. public void Initialize(ChBodyFrame body1, //< first frame (revolute side) ChBodyFrame body2, //< second frame (spherical side) bool local, //< true if data given in body local frames ChVector pos1, //< point on first frame (center of revolute) ChVector dir1, //< direction of revolute on first frame ChVector pos2, //< point on second frame (center of spherical) bool auto_distance = true, //< true if imposed distance equal to |pos1 - po2| double distance = 0 //< imposed distance (used only if auto_distance = false) ) { Body1 = body1; Body2 = body2; m_cnstr_dist.SetVariables(Body1.Variables(), Body2.Variables()); m_cnstr_dot.SetVariables(Body1.Variables(), Body2.Variables()); ChVector pos1_abs; ChVector pos2_abs; ChVector dir1_abs; if (local) { m_pos1 = pos1; m_pos2 = pos2; m_dir1 = ChVector.Vnorm(dir1); pos1_abs = Body1.TransformPointLocalToParent(m_pos1); pos2_abs = Body2.TransformPointLocalToParent(m_pos2); dir1_abs = Body1.TransformDirectionLocalToParent(m_dir1); } else { pos1_abs = pos1; pos2_abs = pos2; dir1_abs = ChVector.Vnorm(dir1); m_pos1 = Body1.TransformPointParentToLocal(pos1_abs); m_pos2 = Body2.TransformPointParentToLocal(pos2_abs); m_dir1 = Body1.TransformDirectionParentToLocal(dir1_abs); } ChVector d12_abs = pos2_abs - pos1_abs; m_cur_dist = d12_abs.Length(); m_dist = auto_distance ? m_cur_dist : distance; m_cur_dot = ChVector.Vdot(d12_abs, dir1_abs); }
/// Inherits, then also adds the spring custom forces to the C_force and C_torque. public override void UpdateForces(double mytime) { // Inherit force computation: // also base class can add its own forces. base.UpdateForces(mytime); spr_react = 0.0; ChVector m_force; double deform = Get_SpringDeform(); spr_react = spr_f * mod_f_time.Get_y(ChTime); spr_react -= (spr_k * mod_k_d.Get_y(deform) * mod_k_speed.Get_y(dist_dt)) * (deform); spr_react -= (spr_r * mod_r_d.Get_y(deform) * mod_r_speed.Get_y(dist_dt)) * (dist_dt); m_force = ChVector.Vmul(ChVector.Vnorm(relM.pos), spr_react); C_force = ChVector.Vadd(C_force, m_force); }
/// Use this function after object creation, to initialize it, given /// the 1D shaft and 3D body to join. /// Each item must belong to the same ChSystem. /// Direction is expressed in the local coordinates of the body. public bool Initialize(ChShaft mshaft, //< shaft to join ChBodyFrame mbody, //< body to join ChVector mdir //< the direction of the shaft on 3D body (applied on COG: pure torque) ) { ChShaft mm1 = mshaft; ChBodyFrame mm2 = mbody; //Debug.Assert(mm1 == null && mm2 == null); shaft = mm1; body.BodyFrame = mm2; shaft_dir = ChVector.Vnorm(mdir); constraint.SetVariables(mm1.Variables(), mm2.Variables()); SetSystem(shaft.GetSystem()); return(true); }
public static void Q_to_AngAxis(ChQuaternion quat, ref double angle, ref ChVector axis) { if (Mathfx.Abs(quat.e0) < 0.99999999) { double arg = Math.Acos(quat.e0); double invsine = 1 / Math.Sin(arg); ChVector vtemp = ChVector.VNULL; //new ChVector(0, 0, 0); vtemp.x = invsine * quat.e1; vtemp.y = invsine * quat.e2; vtemp.z = invsine * quat.e3; angle = 2 * arg; axis = ChVector.Vnorm(vtemp); } else { axis.x = 1; axis.y = 0; axis.z = 0; angle = 0; } }
// ----------------------------------------------------------------------------- // Draw a spring in 3D space, with given color. // ----------------------------------------------------------------------------- public static void drawSpring(double radius, ChVector start, ChVector end, int mresolution, double turns) { ChMatrix33 <double> rel_matrix = new ChMatrix33 <double>(0); ChVector dist = end - start; ChVector Vx = new ChVector(0, 0, 0); ChVector Vy = new ChVector(0, 0, 0); ChVector Vz = new ChVector(0, 0, 0); double length = dist.Length(); ChVector dir = ChVector.Vnorm(dist); ChVector.XdirToDxDyDz(dir, ChVector.VECT_Y, ref Vx, ref Vy, ref Vz); rel_matrix.Set_A_axis(Vx, Vy, Vz); ChQuaternion Q12 = rel_matrix.Get_A_quaternion(); ChCoordsys mpos = new ChCoordsys(start, Q12); double phaseA = 0; double phaseB = 0; double heightA = 0; double heightB = 0; for (int iu = 1; iu <= mresolution; iu++) { phaseB = turns * ChMaths.CH_C_2PI * (double)iu / (double)mresolution; heightB = length * ((double)iu / mresolution); ChVector V1 = new ChVector(heightA, radius * Math.Cos(phaseA), radius * Math.Sin(phaseA)); ChVector V2 = new ChVector(heightB, radius * Math.Cos(phaseB), radius * Math.Sin(phaseB)); Gizmos.color = new Color(255, 255, 0); Gizmos.DrawLine(new Vector3((float)mpos.TransformLocalToParent(V1).x, (float)mpos.TransformLocalToParent(V1).y, (float)mpos.TransformLocalToParent(V1).z), new Vector3((float)mpos.TransformLocalToParent(V2).x, (float)mpos.TransformLocalToParent(V2).y, (float)mpos.TransformLocalToParent(V2).z)); phaseA = phaseB; heightA = heightB; } }
/// Updates motion laws, marker positions, etc. public override void UpdateTime(double mytime) { // First, inherit to parent class base.UpdateTime(mytime); ChFrame <double> abs_shaft1 = ChFrame <double> .FNULL; //new ChFrame<double>(); ChFrame <double> abs_shaft2 = ChFrame <double> .FNULL; //new ChFrame<double>(); ((ChFrame <double>)Body1).TransformLocalToParent(local_shaft1, abs_shaft1); ((ChFrame <double>)Body2).TransformLocalToParent(local_shaft2, abs_shaft2); ChVector dcc_w = ChVector.Vsub(Get_shaft_pos2(), Get_shaft_pos1()); // compute actual rotation of the two wheels (relative to truss). ChVector md1 = abs_shaft1.GetA().MatrT_x_Vect(dcc_w); md1.z = 0; md1 = ChVector.Vnorm(md1); ChVector md2 = abs_shaft2.GetA().MatrT_x_Vect(dcc_w); md2.z = 0; md2 = ChVector.Vnorm(md2); double periodic_a1 = ChMaths.ChAtan2(md1.x, md1.y); double periodic_a2 = ChMaths.ChAtan2(md2.x, md2.y); double old_a1 = a1; double old_a2 = a2; double turns_a1 = Math.Floor(old_a1 / ChMaths.CH_C_2PI); double turns_a2 = Math.Floor(old_a2 / ChMaths.CH_C_2PI); double a1U = turns_a1 * ChMaths.CH_C_2PI + periodic_a1 + ChMaths.CH_C_2PI; double a1M = turns_a1 * ChMaths.CH_C_2PI + periodic_a1; double a1L = turns_a1 * ChMaths.CH_C_2PI + periodic_a1 - ChMaths.CH_C_2PI; a1 = a1M; if (Math.Abs(a1U - old_a1) < Math.Abs(a1M - old_a1)) { a1 = a1U; } if (Math.Abs(a1L - a1) < Math.Abs(a1M - a1)) { a1 = a1L; } double a2U = turns_a2 * ChMaths.CH_C_2PI + periodic_a2 + ChMaths.CH_C_2PI; double a2M = turns_a2 * ChMaths.CH_C_2PI + periodic_a2; double a2L = turns_a2 * ChMaths.CH_C_2PI + periodic_a2 - ChMaths.CH_C_2PI; a2 = a2M; if (Math.Abs(a2U - old_a2) < Math.Abs(a2M - old_a2)) { a2 = a2U; } if (Math.Abs(a2L - a2) < Math.Abs(a2M - a2)) { a2 = a2L; } // correct marker positions if phasing is not correct double m_delta = 0; if (checkphase) { double realtau = tau; m_delta = a1 - phase - (a2 / realtau); if (m_delta > ChMaths.CH_C_PI) { m_delta -= (ChMaths.CH_C_2PI); // range -180..+180 is better than 0...360 } if (m_delta > (ChMaths.CH_C_PI / 4.0)) { m_delta = (ChMaths.CH_C_PI / 4.0); // phase correction only in +/- 45° } if (m_delta < -(ChMaths.CH_C_PI / 4.0)) { m_delta = -(ChMaths.CH_C_PI / 4.0); } //***TODO*** } // Move markers 1 and 2 to align them as pulley ends ChVector d21_w = dcc_w - Get_shaft_dir1() * ChVector.Vdot(Get_shaft_dir1(), dcc_w); ChVector D21_w = ChVector.Vnorm(d21_w); shaft_dist = d21_w.Length(); ChVector U1_w = ChVector.Vcross(Get_shaft_dir1(), D21_w); double gamma1 = Math.Acos((r1 - r2) / shaft_dist); ChVector Ru_w = D21_w * Math.Cos(gamma1) + U1_w * Math.Sin(gamma1); ChVector Rl_w = D21_w * Math.Cos(gamma1) - U1_w * Math.Sin(gamma1); belt_up1 = Get_shaft_pos1() + Ru_w * r1; belt_low1 = Get_shaft_pos1() + Rl_w * r1; belt_up2 = Get_shaft_pos1() + d21_w + Ru_w * r2; belt_low2 = Get_shaft_pos1() + d21_w + Rl_w * r2; // marker alignment ChMatrix33 <double> maU = new ChMatrix33 <double>(0); ChMatrix33 <double> maL = new ChMatrix33 <double>(0); ChVector Dxu = ChVector.Vnorm(belt_up2 - belt_up1); ChVector Dyu = Ru_w; ChVector Dzu = ChVector.Vnorm(ChVector.Vcross(Dxu, Dyu)); Dyu = ChVector.Vnorm(ChVector.Vcross(Dzu, Dxu)); maU.Set_A_axis(Dxu, Dyu, Dzu); // ! Require that the BDF routine of marker won't handle speed and acc.calculus of the moved marker 2! marker2.SetMotionType(ChMarker.eChMarkerMotion.M_MOTION_EXTERNAL); marker1.SetMotionType(ChMarker.eChMarkerMotion.M_MOTION_EXTERNAL); ChCoordsys newmarkpos = new ChCoordsys(); // move marker1 in proper positions newmarkpos.pos = this.belt_up1; newmarkpos.rot = maU.Get_A_quaternion(); marker1.Impose_Abs_Coord(newmarkpos); // move marker1 into teeth position // move marker2 in proper positions newmarkpos.pos = this.belt_up2; newmarkpos.rot = maU.Get_A_quaternion(); marker2.Impose_Abs_Coord(newmarkpos); // move marker2 into teeth position double phase_correction_up = m_delta * r1; double phase_correction_low = -phase_correction_up; double hU = ChVector.Vlength(belt_up2 - belt_up1) + phase_correction_up; double hL = ChVector.Vlength(belt_low2 - belt_low1) + phase_correction_low; // imposed relative positions/speeds deltaC.pos = new ChVector(-hU, 0, 0); deltaC_dt.pos = ChVector.VNULL; deltaC_dtdt.pos = ChVector.VNULL; deltaC.rot = ChQuaternion.QUNIT; // no relative rotations imposed! deltaC_dt.rot = ChQuaternion.QNULL; deltaC_dtdt.rot = ChQuaternion.QNULL; }
// // UPDATING // /// Updates the time.dependant variables (ex: ChFunction objects /// which impose the body-relative motion, etc.) public void UpdateTime(double mytime) { ChCoordsys csys = new ChCoordsys(new ChVector(0, 0, 0), new ChQuaternion(1, 0, 0, 0)); ChCoordsys csys_dt = new ChCoordsys(new ChVector(0, 0, 0), new ChQuaternion(1, 0, 0, 0)); ChCoordsys csys_dtdt = new ChCoordsys(new ChVector(0, 0, 0), new ChQuaternion(1, 0, 0, 0)); ChQuaternion qtemp;// = new ChQuaternion(1, 0, 0, 0); double ang, ang_dt, ang_dtdt; ChTime = mytime; // if a imposed motion (keyframed movement) affects the marker position (example,from R3D animation system), // compute the speed and acceleration values by BDF (example,see the UpdatedExternalTime() function, later) // so the updating via motion laws can be skipped! if (motion_type == eChMarkerMotion.M_MOTION_KEYFRAMED) { return; } // skip relative-position-functions evaluation also if // someone is already handling this from outside.. if (motion_type == eChMarkerMotion.M_MOTION_EXTERNAL) { return; } // positions: // update positions: rel_pos csys.pos.x = motion_X.Get_y(mytime); csys.pos.y = motion_Y.Get_y(mytime); csys.pos.z = motion_Z.Get_y(mytime); if (motion_X.Get_Type() != ChFunction.FunctionType.FUNCT_MOCAP) { csys.pos += rest_coord.pos; } // update speeds: rel_pos_dt csys_dt.pos.x = motion_X.Get_y_dx(mytime); csys_dt.pos.y = motion_Y.Get_y_dx(mytime); csys_dt.pos.z = motion_Z.Get_y_dx(mytime); // update accelerations csys_dtdt.pos.x = motion_X.Get_y_dxdx(mytime); csys_dtdt.pos.y = motion_Y.Get_y_dxdx(mytime); csys_dtdt.pos.z = motion_Z.Get_y_dxdx(mytime); // rotations: ang = motion_ang.Get_y(mytime); ang_dt = motion_ang.Get_y_dx(mytime); ang_dtdt = motion_ang.Get_y_dxdx(mytime); if ((ang != 0) || (ang_dt != 0) || (ang_dtdt != 0)) { // update q ChVector motion_axis_versor = ChVector.Vnorm(motion_axis); qtemp = ChQuaternion.Q_from_AngAxis2(ang, motion_axis_versor); csys.rot = ChQuaternion.Qcross(qtemp, rest_coord.rot); // update q_dt csys_dt.rot = ChQuaternion.Qdt_from_AngAxis(csys.rot, ang_dt, motion_axis_versor); // update q_dtdt csys_dtdt.rot = ChQuaternion.Qdtdt_from_AngAxis(ang_dtdt, motion_axis_versor, csys.rot, csys_dt.rot); } else { csys.rot = FrameMoving.coord.rot; // rel_pos.rot; csys_dt.rot = ChQuaternion.QNULL; csys_dtdt.rot = ChQuaternion.QNULL; } // Set the position, speed and acceleration in relative space, // automatically getting also the absolute values, if (!(csys == this.FrameMoving.coord)) { FrameMoving.SetCoord(csys); } if (!(csys_dt == this.FrameMoving.coord_dt) || !(csys_dt.rot == new ChQuaternion(0, 0, 0, 0))) { FrameMoving.SetCoord_dt(csys_dt); } if (!(csys_dtdt == this.FrameMoving.coord_dtdt) || !(csys_dtdt.rot == new ChQuaternion(0, 0, 0, 0))) { FrameMoving.SetCoord_dtdt(csys_dtdt); } }
/// Updates motion laws, etc. for the impose rotation / impose speed modes public override void UpdateTime(double mytime) { // First, inherit to parent class base.UpdateTime(mytime); if (!IsActive()) { return; } // DEFAULTS compute rotation vars... // by default for torque control.. motion_axis = ChVector.VECT_Z; // motion axis is always the marker2 Z axis (in m2 relative coords) mot_rot = relAngle; mot_rot_dt = ChVector.Vdot(relWvel, motion_axis); mot_rot_dtdt = ChVector.Vdot(relWacc, motion_axis); mot_rerot = mot_rot / mot_tau; mot_rerot_dt = mot_rot_dt / mot_tau; mot_rerot_dtdt = mot_rot_dtdt / mot_tau; // nothing more to do here for torque control if (eng_mode == eCh_eng_mode.ENG_MODE_TORQUE) { return; } // If LEARN MODE, just record motion if (learn) { deltaC.pos = ChVector.VNULL; deltaC_dt.pos = ChVector.VNULL; deltaC_dtdt.pos = ChVector.VNULL; if (!(limit_Rx.Get_active() || limit_Ry.Get_active() || limit_Rz.Get_active())) { deltaC.rot = ChQuaternion.QUNIT; deltaC_dt.rot = ChQuaternion.QNULL; deltaC_dtdt.rot = ChQuaternion.QNULL; } if (eng_mode == eCh_eng_mode.ENG_MODE_ROTATION) { if (rot_funct.Get_Type() != ChFunction.FunctionType.FUNCT_RECORDER) { rot_funct = new ChFunction_Recorder(); } // record point double rec_rot = relAngle; // ***TO DO*** compute also rotations with cardano mode? if (impose_reducer) { rec_rot = rec_rot / mot_tau; } ChFunction_Recorder rec = (ChFunction_Recorder)rot_funct; rec.AddPoint(mytime, rec_rot, 1); // x=t } if (eng_mode == eCh_eng_mode.ENG_MODE_SPEED) { if (spe_funct.Get_Type() != ChFunction.FunctionType.FUNCT_RECORDER) { spe_funct = new ChFunction_Recorder(); } // record point double rec_spe = ChVector.Vlength(relWvel); // ***TO DO*** compute also with cardano mode? if (impose_reducer) { rec_spe = rec_spe / mot_tau; } ChFunction_Recorder rec = (ChFunction_Recorder)spe_funct; rec.AddPoint(mytime, rec_spe, 1); // x=t } } if (learn) { return; // no need to go on further...--.>>> } // Impose relative positions/speeds deltaC.pos = ChVector.VNULL; deltaC_dt.pos = ChVector.VNULL; deltaC_dtdt.pos = ChVector.VNULL; if (eng_mode == eCh_eng_mode.ENG_MODE_ROTATION) { if (impose_reducer) { mot_rerot = rot_funct.Get_y(ChTime); mot_rerot_dt = rot_funct.Get_y_dx(ChTime); mot_rerot_dtdt = rot_funct.Get_y_dxdx(ChTime); mot_rot = mot_rerot * mot_tau; mot_rot_dt = mot_rerot_dt * mot_tau; mot_rot_dtdt = mot_rerot_dtdt * mot_tau; } else { mot_rot = rot_funct.Get_y(ChTime); mot_rot_dt = rot_funct.Get_y_dx(ChTime); mot_rot_dtdt = rot_funct.Get_y_dxdx(ChTime); mot_rerot = mot_rot / mot_tau; mot_rerot_dt = mot_rot_dt / mot_tau; mot_rerot_dtdt = mot_rot_dtdt / mot_tau; } deltaC.rot = ChQuaternion.Q_from_AngAxis2(mot_rot, motion_axis); deltaC_dt.rot = ChQuaternion.Qdt_from_AngAxis(deltaC.rot, mot_rot_dt, motion_axis); deltaC_dtdt.rot = ChQuaternion.Qdtdt_from_AngAxis(mot_rot_dtdt, motion_axis, deltaC.rot, deltaC_dt.rot); } if (eng_mode == eCh_eng_mode.ENG_MODE_SPEED) { if (impose_reducer) { mot_rerot_dt = spe_funct.Get_y(ChTime); mot_rerot_dtdt = spe_funct.Get_y_dx(ChTime); mot_rot_dt = mot_rerot_dt * mot_tau; mot_rot_dtdt = mot_rerot_dtdt * mot_tau; } else { mot_rot_dt = spe_funct.Get_y(ChTime); mot_rot_dtdt = spe_funct.Get_y_dx(ChTime); mot_rerot_dt = mot_rot_dt / mot_tau; mot_rerot_dtdt = mot_rot_dtdt / mot_tau; } deltaC.rot = ChQuaternion.Qnorm(GetRelM().rot); // just keep current position, -assume always good after integration-. ChMatrix33 <double> relA = new ChMatrix33 <double>(0); relA.Set_A_quaternion(GetRelM().rot); // ..but adjust to keep Z axis aligned to shaft, anyway! ChVector displaced_z_axis = relA.Get_A_Zaxis(); ChVector adjustment = ChVector.Vcross(displaced_z_axis, ChVector.VECT_Z); deltaC.rot = ChQuaternion.Q_from_AngAxis2(ChVector.Vlength(adjustment), ChVector.Vnorm(adjustment)) % deltaC.rot; deltaC_dt.rot = ChQuaternion.Qdt_from_AngAxis(deltaC.rot, mot_rot_dt, motion_axis); deltaC_dtdt.rot = ChQuaternion.Qdtdt_from_AngAxis(mot_rot_dtdt, motion_axis, deltaC.rot, deltaC_dt.rot); } }
/// Inherits, and updates the C_force and C_torque 'intuitive' forces, /// adding the effects of the contained ChLinkForce objects. /// (Default: inherits parent UpdateForces(), then C_force and C_torque are /// incremented with the Link::ChLinkForces objects) public override void UpdateForces(double mytime) { base.UpdateForces(mytime); // ** Child class can inherit this method. The parent implementation must // be called _before_ adding further custom forces. ChVector m_force; // = new ChVector(0, 0, 0); // initialize to zero the m1-m2 force/torque ChVector m_torque; // = new ChVector(0, 0, 0); // 'intuitive' vectors (can be transformed&added later into Qf) // COMPUTE THE FORCES IN THE LINK, FOR EXAMPLE // CAUSED BY SPRINGS // NOTE!!!!! C_force and C_torque are considered in the reference coordsystem // of marker2 (the MAIN marker), and their application point is considered the // origin of marker1 (the SLAVE marker) // 1)========== the generic spring-damper if (force_D != null && force_D.Get_active()) { double dfor; dfor = force_D.Get_Force((dist - d_restlength), dist_dt, ChTime); m_force = ChVector.Vmul(ChVector.Vnorm(relM.pos), dfor); C_force = ChVector.Vadd(C_force, m_force); } // 2)========== the generic torsional spring / torsional damper if (force_R != null && force_R.Get_active()) { double tor; // 1) the tors. spring tor = force_R.Get_Force(relAngle, 0, ChTime); m_torque = ChVector.Vmul(relAxis, tor); C_torque = ChVector.Vadd(C_torque, m_torque); // 2) the tors. damper double angle_dt = ChVector.Vlength(relWvel); tor = force_R.Get_Force(0, angle_dt, ChTime); m_torque = ChVector.Vmul(ChVector.Vnorm(relWvel), tor); C_torque = ChVector.Vadd(C_torque, m_torque); } // 3)========== the XYZ forces m_force = ChVector.VNULL; if (force_X != null && force_X.Get_active()) { m_force.x = force_X.Get_Force(relM.pos.x, relM_dt.pos.x, ChTime); } if (force_Y != null && force_Y.Get_active()) { m_force.y = force_Y.Get_Force(relM.pos.y, relM_dt.pos.y, ChTime); } if (force_Z != null && force_Z.Get_active()) { m_force.z = force_Z.Get_Force(relM.pos.z, relM_dt.pos.z, ChTime); } C_force = ChVector.Vadd(C_force, m_force); // 4)========== the RxRyRz forces (torques) m_torque = new ChVector(0, 0, 0); if (force_Rx != null && force_Rx.Get_active()) { m_torque.x = force_Rx.Get_Force(relRotaxis.x, relWvel.x, ChTime); } if (force_Ry != null && force_Ry.Get_active()) { m_torque.y = force_Ry.Get_Force(relRotaxis.y, relWvel.y, ChTime); } if (force_Rz != null && force_Rz.Get_active()) { m_torque.z = force_Rz.Get_Force(relRotaxis.z, relWvel.z, ChTime); } C_torque = ChVector.Vadd(C_torque, m_torque); }
/// Set the direction of the shaft respect to 3D body, as a /// normalized vector expressed in the coordinates of the body. /// The shaft applies only torque, about this axis. public void SetShaftDirection(ChVector md) { shaft_dir = ChVector.Vnorm(md); }
/// Get the master coordinate system for the assets (this will return the /// absolute coordinate system of the 'master' marker2) // public override ChFrame<double> GetAssetsFrame(int nclone = 0) { return marker2.GetAbsFrame(); } // // UPDATING FUNCTIONS // /// Updates auxiliary vars relM, relM_dt, relM_dtdt, /// dist, dist_dt et simila. public virtual void UpdateRelMarkerCoords() { // FOR ALL THE 6(or3) COORDINATES OF RELATIVE MOTION OF THE TWO MARKERS: // COMPUTE THE relM, relM_dt relM_dtdt COORDINATES, AND AUXILIARY DATA (distance,etc.) ChVector PQw = ChVector.Vsub(marker1.GetAbsCoord().pos, marker2.GetAbsCoord().pos); ChVector PQw_dt = ChVector.Vsub(marker1.GetAbsCoord_dt().pos, marker2.GetAbsCoord_dt().pos); ChVector PQw_dtdt = ChVector.Vsub(marker1.GetAbsCoord_dtdt().pos, marker2.GetAbsCoord_dtdt().pos); dist = ChVector.Vlength(PQw); // distance between origins, modulus dist_dt = ChVector.Vdot(ChVector.Vnorm(PQw), PQw_dt); // speed between origins, modulus. ChVector vtemp1; // for intermediate calculus ChVector vtemp2; ChQuaternion qtemp1; // ChMatrixNM<IntInterface.Three, IntInterface.Four> relGw = new ChMatrixNM<IntInterface.Three, IntInterface.Four>(0); /* ChQuaternion q_AD; * ChQuaternion q_BC; * ChQuaternion q_8; * ChVector q_4;*/ ChQuaternion temp1 = marker1.FrameMoving.GetCoord_dt().rot; ChQuaternion temp2 = marker2.FrameMoving.GetCoord_dt().rot; if (ChQuaternion.Qnotnull(temp1) || ChQuaternion.Qnotnull(temp2)) { q_AD = // q'qqq + qqqq' ChQuaternion.Qadd(ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord_dt().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.GetBody().BodyFrame.GetCoord().rot), ChQuaternion.Qcross((marker1.GetBody().BodyFrame.GetCoord().rot), (marker1.FrameMoving.GetCoord().rot)))), ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.GetBody().BodyFrame.GetCoord().rot), ChQuaternion.Qcross((marker1.GetBody().BodyFrame.GetCoord().rot), (marker1.FrameMoving.GetCoord_dt().rot))))); } else { //q_AD = ChQuaternion.QNULL; q_BC = // qq'qq + qqq'q ChQuaternion.Qadd(ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.GetBody().BodyFrame.GetCoord_dt().rot), ChQuaternion.Qcross((marker1.GetBody().BodyFrame.GetCoord().rot), (marker1.FrameMoving.GetCoord().rot)))), ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.GetBody().BodyFrame.GetCoord().rot), ChQuaternion.Qcross((marker1.GetBody().BodyFrame.GetCoord_dt().rot), (marker1.FrameMoving.GetCoord().rot))))); } // q_8 = q''qqq + 2q'q'qq + 2q'qq'q + 2q'qqq' // + 2qq'q'q + 2qq'qq' + 2qqq'q' + qqqq'' temp2 = marker2.FrameMoving.GetCoord_dtdt().rot; if (ChQuaternion.Qnotnull(temp2)) { q_8 = ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord_dtdt().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord().rot), ChQuaternion.Qcross(Body1.GetCoord().rot, marker1.FrameMoving.GetCoord().rot))); // q_dtdt'm2 * q'o2 * q,o1 * q,m1 } else { //q_8 = ChQuaternion.QNULL; temp1 = marker1.FrameMoving.GetCoord_dtdt().rot; } if (ChQuaternion.Qnotnull(temp1)) { qtemp1 = ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord().rot), ChQuaternion.Qcross(Body1.GetCoord().rot, marker1.FrameMoving.GetCoord_dtdt().rot))); // q'm2 * q'o2 * q,o1 * q_dtdt,m1 q_8 = ChQuaternion.Qadd(q_8, qtemp1); } temp2 = marker2.FrameMoving.GetCoord_dt().rot; if (ChQuaternion.Qnotnull(temp2)) { qtemp1 = ChQuaternion.Qcross( ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord_dt().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord_dt().rot), ChQuaternion.Qcross(Body1.GetCoord().rot, marker1.FrameMoving.GetCoord().rot))); qtemp1 = ChQuaternion.Qscale(qtemp1, 2); // 2( q_dt'm2 * q_dt'o2 * q,o1 * q,m1) q_8 = ChQuaternion.Qadd(q_8, qtemp1); } temp2 = marker2.FrameMoving.GetCoord_dt().rot; if (ChQuaternion.Qnotnull(temp2)) { qtemp1 = ChQuaternion.Qcross( ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord_dt().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord().rot), ChQuaternion.Qcross(Body1.GetCoord_dt().rot, marker1.FrameMoving.GetCoord().rot))); qtemp1 = ChQuaternion.Qscale(qtemp1, 2); // 2( q_dt'm2 * q'o2 * q_dt,o1 * q,m1) q_8 = ChQuaternion.Qadd(q_8, qtemp1); } temp1 = marker1.FrameMoving.GetCoord_dt().rot; temp2 = marker2.FrameMoving.GetCoord_dt().rot; if (ChQuaternion.Qnotnull(temp2) && ChQuaternion.Qnotnull(temp1)) { qtemp1 = ChQuaternion.Qcross( ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord_dt().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord().rot), ChQuaternion.Qcross(Body1.GetCoord().rot, marker1.FrameMoving.GetCoord_dt().rot))); qtemp1 = ChQuaternion.Qscale(qtemp1, 2); // 2( q_dt'm2 * q'o2 * q,o1 * q_dt,m1) q_8 = ChQuaternion.Qadd(q_8, qtemp1); } qtemp1 = ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord_dt().rot), ChQuaternion.Qcross(Body1.GetCoord_dt().rot, marker1.FrameMoving.GetCoord().rot))); qtemp1 = ChQuaternion.Qscale(qtemp1, 2); // 2( q'm2 * q_dt'o2 * q_dt,o1 * q,m1) q_8 = ChQuaternion.Qadd(q_8, qtemp1); temp1 = marker1.FrameMoving.GetCoord_dt().rot; if (ChQuaternion.Qnotnull(temp1)) { qtemp1 = ChQuaternion.Qcross( ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord_dt().rot), ChQuaternion.Qcross(Body1.GetCoord().rot, marker1.FrameMoving.GetCoord_dt().rot))); qtemp1 = ChQuaternion.Qscale(qtemp1, 2); // 2( q'm2 * q_dt'o2 * q,o1 * q_dt,m1) q_8 = ChQuaternion.Qadd(q_8, qtemp1); } temp1 = marker1.FrameMoving.GetCoord_dt().rot; if (ChQuaternion.Qnotnull(temp1)) { qtemp1 = ChQuaternion.Qcross( ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord().rot), ChQuaternion.Qcross(Body1.GetCoord_dt().rot, marker1.FrameMoving.GetCoord_dt().rot))); qtemp1 = ChQuaternion.Qscale(qtemp1, 2); // 2( q'm2 * q'o2 * q_dt,o1 * q_dt,m1) q_8 = ChQuaternion.Qadd(q_8, qtemp1); } // q_4 = [Adtdt]'[A]'q + 2[Adt]'[Adt]'q // + 2[Adt]'[A]'qdt + 2[A]'[Adt]'qdt // ChMatrix33<double> m2_Rel_A_dt = new ChMatrix33<double>(0); marker2.FrameMoving.Compute_Adt(ref m2_Rel_A_dt); // ChMatrix33<double> m2_Rel_A_dtdt = new ChMatrix33<double>(0); marker2.FrameMoving.Compute_Adtdt(ref m2_Rel_A_dtdt); vtemp1 = Body2.GetA_dt().MatrT_x_Vect(PQw); vtemp2 = m2_Rel_A_dt.MatrT_x_Vect(vtemp1); q_4 = ChVector.Vmul(vtemp2, 2); // 2[Aq_dt]'[Ao2_dt]'*Qpq,w vtemp1 = Body2.GetA().MatrT_x_Vect(PQw_dt); vtemp2 = m2_Rel_A_dt.MatrT_x_Vect(vtemp1); vtemp2 = ChVector.Vmul(vtemp2, 2); // 2[Aq_dt]'[Ao2]'*Qpq,w_dt q_4 = ChVector.Vadd(q_4, vtemp2); vtemp1 = Body2.GetA_dt().MatrT_x_Vect(PQw_dt); vtemp2 = marker2.FrameMoving.GetA().MatrT_x_Vect(vtemp1); vtemp2 = ChVector.Vmul(vtemp2, 2); // 2[Aq]'[Ao2_dt]'*Qpq,w_dt q_4 = ChVector.Vadd(q_4, vtemp2); vtemp1 = Body2.GetA().MatrT_x_Vect(PQw); vtemp2 = m2_Rel_A_dtdt.MatrT_x_Vect(vtemp1); q_4 = ChVector.Vadd(q_4, vtemp2); // [Aq_dtdt]'[Ao2]'*Qpq,w // ----------- RELATIVE MARKER COORDINATES // relM.pos relM.pos = marker2.FrameMoving.GetA().MatrT_x_Vect(Body2.GetA().MatrT_x_Vect(PQw)); // relM.rot relM.rot = ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.GetBody().BodyFrame.GetCoord().rot), ChQuaternion.Qcross((marker1.GetBody().BodyFrame.GetCoord().rot), (marker1.FrameMoving.GetCoord().rot)))); // relM_dt.pos relM_dt.pos = ChVector.Vadd(ChVector.Vadd(m2_Rel_A_dt.MatrT_x_Vect(Body2.GetA().MatrT_x_Vect(PQw)), marker2.FrameMoving.GetA().MatrT_x_Vect(Body2.GetA_dt().MatrT_x_Vect(PQw))), marker2.FrameMoving.GetA().MatrT_x_Vect(Body2.GetA().MatrT_x_Vect(PQw_dt))); // relM_dt.rot relM_dt.rot = ChQuaternion.Qadd(q_AD, q_BC); // relM_dtdt.pos relM_dtdt.pos = ChVector.Vadd(ChVector.Vadd(marker2.FrameMoving.GetA().MatrT_x_Vect(Body2.GetA_dtdt().MatrT_x_Vect(PQw)), marker2.FrameMoving.GetA().MatrT_x_Vect(Body2.GetA().MatrT_x_Vect(PQw_dtdt))), q_4); // relM_dtdt.rot qtemp1 = ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord_dtdt().rot), ChQuaternion.Qcross(Body1.GetCoord().rot, marker1.FrameMoving.GetCoord().rot))); // ( q'm2 * q_dtdt'o2 * q,o1 * q,m1) relM_dtdt.rot = ChQuaternion.Qadd(q_8, qtemp1); qtemp1 = ChQuaternion.Qcross(ChQuaternion.Qconjugate(marker2.FrameMoving.GetCoord().rot), ChQuaternion.Qcross(ChQuaternion.Qconjugate(Body2.GetCoord().rot), ChQuaternion.Qcross(Body1.GetCoord_dtdt().rot, marker1.FrameMoving.GetCoord().rot))); // ( q'm2 * q'o2 * q_dtdt,o1 * q,m1) relM_dtdt.rot = ChQuaternion.Qadd(relM_dtdt.rot, qtemp1); // = q_8 + qq''qq + qqq''q // ... and also "user-friendly" relative coordinates: // relAngle and relAxis ChQuaternion.Q_to_AngAxis(relM.rot, ref relAngle, ref relAxis); // flip rel rotation axis if jerky sign if (relAxis.z < 0) { relAxis = ChVector.Vmul(relAxis, -1); relAngle = -relAngle; } // rotation axis relRotaxis = ChVector.Vmul(relAxis, relAngle); // relWvel ChFrame <double> .SetMatrix_Gw(ref relGw, relM.rot); // relGw.Set_Gw_matrix(relM.rot); relWvel = relGw.matrix.Matr34_x_Quat(relM_dt.rot); // relWacc relWacc = relGw.matrix.Matr34_x_Quat(relM_dtdt.rot); }
// Updates motion laws, marker positions, etc. public override void UpdateTime(double mytime) { // First, inherit to parent class base.UpdateTime(mytime); // If LEARN MODE, just record motion if (learn) { /* do not change deltas, in free mode maybe that 'limit on X' changed them * deltaC.pos = VNULL; * deltaC_dt.pos = VNULL; * deltaC_dtdt.pos = VNULL; * deltaC.rot = QUNIT; * deltaC_dt.rot = QNULL; * deltaC_dtdt.rot = QNULL; */ // if (dist_funct.Get_Type() != ChFunction.FunctionType.FUNCT_RECORDER) // dist_funct = new ChFunction_Recorder(); // record point double rec_dist = ChVector.Vlength(ChVector.Vsub(marker1.GetAbsCoord().pos, marker2.GetAbsCoord().pos)); rec_dist -= offset; // (ChFunction_Recorder)(dist_funct).AddPoint(mytime, rec_dist, 1); // (x,y,w) x=t } // Move (well, rotate...) marker 2 to align it in actuator direction // ! Require that the BDF routine of marker won't handle speed and acc.calculus of the moved marker 2! marker2.SetMotionType(ChMarker.eChMarkerMotion.M_MOTION_EXTERNAL); // ChMatrix33<double> ma = new ChMatrix33<double>(0); ma.Set_A_quaternion(marker2.GetAbsCoord().rot); ChVector absdist = ChVector.Vsub(marker1.GetAbsCoord().pos, marker2.GetAbsCoord().pos); ChVector mx = ChVector.Vnorm(absdist); ChVector my = ma.Get_A_Yaxis(); if (ChVector.Vequal(mx, my)) { if (mx.x == 1.0) { my = ChVector.VECT_Y; } else { my = ChVector.VECT_X; } } ChVector mz = ChVector.Vnorm(ChVector.Vcross(mx, my)); my = ChVector.Vnorm(ChVector.Vcross(mz, mx)); ma.Set_A_axis(mx, my, mz); ChCoordsys newmarkpos; ChVector oldpos = marker2.FrameMoving.GetPos(); // backup to avoid numerical err.accumulation newmarkpos.pos = marker2.GetAbsCoord().pos; newmarkpos.rot = ma.Get_A_quaternion(); marker2.Impose_Abs_Coord(newmarkpos); // rotate "main" marker2 into tangent position (may add err.accumulation) marker2.FrameMoving.SetPos(oldpos); // backup to avoid numerical err.accumulation if (learn) { return; // no need to go on further...--.>>> } // imposed relative positions/speeds deltaC.pos = ChVector.VNULL; deltaC.pos.x = dist_funct.Get_y(ChTime) + offset; // distance is always on M2 'X' axis deltaC_dt.pos = ChVector.VNULL; deltaC_dt.pos.x = dist_funct.Get_y_dx(ChTime); // distance speed deltaC_dtdt.pos = ChVector.VNULL; deltaC_dtdt.pos.x = dist_funct.Get_y_dxdx(ChTime); // distance acceleration // add also the centripetal acceleration if distance vector's rotating, // as centripetal acc. of point sliding on a sphere surface. ChVector tang_speed = GetRelM_dt().pos; tang_speed.x = 0; // only z-y coords in relative tang speed vector double len_absdist = ChVector.Vlength(absdist); // don't divide by zero if (len_absdist > 1E-6) { deltaC_dtdt.pos.x -= Math.Pow(ChVector.Vlength(tang_speed), 2) / ChVector.Vlength(absdist); // An = Adelta -(Vt^2 / r) } deltaC.rot = ChQuaternion.QUNIT; // no relative rotations imposed! deltaC_dt.rot = ChQuaternion.QNULL; deltaC_dtdt.rot = ChQuaternion.QNULL; // Compute motor variables // double m_rotation; // double m_torque; mot_rerot = (deltaC.pos.x - offset) / mot_tau; mot_rerot_dt = deltaC_dt.pos.x / mot_tau; mot_rerot_dtdt = deltaC_dtdt.pos.x / mot_tau; mot_retorque = mot_rerot_dtdt * mot_inertia + (react_force.x * mot_tau) / mot_eta; // m_rotation = (deltaC.pos.x() - offset) / mot_tau; // m_torque = (deltaC_dtdt.pos.x() / mot_tau) * mot_inertia + (react_force.x() * mot_tau) / mot_eta; if (learn_torque_rotation) { // if (mot_torque.Get_Type() != ChFunction.FunctionType.FUNCT_RECORDER) // mot_torque = new ChFunction_Recorder(); // if (mot_rot.Get_Type() != ChFunction.FunctionType.FUNCT_RECORDER) // mot_rot = new ChFunction_Recorder(); // std::static_pointer_cast<ChFunction_Recorder>(mot_torque).AddPoint(mytime, mot_retorque, 1); // (x,y,w) x=t // std::static_pointer_cast<ChFunction_Recorder>(mot_rot).AddPoint(mytime, mot_rerot, 1); // (x,y,w) x=t } }
// Updates motion laws, marker positions, etc. public override void UpdateTime(double mytime) { // First, inherit to parent class base.UpdateTime(mytime); // Move markers 1 and 2 to align them as gear teeth ChMatrix33 <double> ma1 = new ChMatrix33 <double>(0); ChMatrix33 <double> ma2 = new ChMatrix33 <double>(0); ChMatrix33 <double> mrotma = new ChMatrix33 <double>(0); ChMatrix33 <double> marot_beta = new ChMatrix33 <double>(0); ChVector mx; ChVector my; ChVector mz; ChVector mr; ChVector mmark1; ChVector mmark2; ChVector lastX; ChVector vrota; ChCoordsys newmarkpos = new ChCoordsys(new ChVector(0, 0, 0), new ChQuaternion(1, 0, 0, 0)); ChFrame <double> abs_shaft1 = ChFrame <double> .FNULL; // new ChFrame<double>(); ChFrame <double> abs_shaft2 = ChFrame <double> .FNULL; //new ChFrame<double>(); ((ChFrame <double>)Body1).TransformLocalToParent(local_shaft1, abs_shaft1); ((ChFrame <double>)Body2).TransformLocalToParent(local_shaft2, abs_shaft2); ChVector vbdist = ChVector.Vsub(Get_shaft_pos1(), Get_shaft_pos2()); // ChVector Trad1 = ChVector.Vnorm(ChVector.Vcross(Get_shaft_dir1(), ChVector.Vnorm(ChVector.Vcross(Get_shaft_dir1(), vbdist)))); // ChVector Trad2 = ChVector.Vnorm(ChVector.Vcross(ChVector.Vnorm(ChVector.Vcross(Get_shaft_dir2(), vbdist)), Get_shaft_dir2())); double dist = ChVector.Vlength(vbdist); // compute actual rotation of the two wheels (relative to truss). ChVector md1 = abs_shaft1.GetA().MatrT_x_Vect(-vbdist); md1.z = 0; md1 = ChVector.Vnorm(md1); ChVector md2 = abs_shaft2.GetA().MatrT_x_Vect(-vbdist); md2.z = 0; md2 = ChVector.Vnorm(md2); double periodic_a1 = ChMaths.ChAtan2(md1.x, md1.y); double periodic_a2 = ChMaths.ChAtan2(md2.x, md2.y); double old_a1 = a1; double old_a2 = a2; double turns_a1 = Math.Floor(old_a1 / ChMaths.CH_C_2PI); double turns_a2 = Math.Floor(old_a2 / ChMaths.CH_C_2PI); double a1U = turns_a1 * ChMaths.CH_C_2PI + periodic_a1 + ChMaths.CH_C_2PI; double a1M = turns_a1 * ChMaths.CH_C_2PI + periodic_a1; double a1L = turns_a1 * ChMaths.CH_C_2PI + periodic_a1 - ChMaths.CH_C_2PI; a1 = a1M; if (Math.Abs(a1U - old_a1) < Math.Abs(a1M - old_a1)) { a1 = a1U; } if (Math.Abs(a1L - a1) < Math.Abs(a1M - a1)) { a1 = a1L; } double a2U = turns_a2 * ChMaths.CH_C_2PI + periodic_a2 + ChMaths.CH_C_2PI; double a2M = turns_a2 * ChMaths.CH_C_2PI + periodic_a2; double a2L = turns_a2 * ChMaths.CH_C_2PI + periodic_a2 - ChMaths.CH_C_2PI; a2 = a2M; if (Math.Abs(a2U - old_a2) < Math.Abs(a2M - old_a2)) { a2 = a2U; } if (Math.Abs(a2L - a2) < Math.Abs(a2M - a2)) { a2 = a2L; } // compute new markers coordsystem alignment my = ChVector.Vnorm(vbdist); mz = Get_shaft_dir1(); mx = ChVector.Vnorm(ChVector.Vcross(my, mz)); mr = ChVector.Vnorm(ChVector.Vcross(mz, mx)); mz = ChVector.Vnorm(ChVector.Vcross(mx, my)); ChVector mz2, mx2, mr2, my2; my2 = my; mz2 = Get_shaft_dir2(); mx2 = ChVector.Vnorm(ChVector.Vcross(my2, mz2)); mr2 = ChVector.Vnorm(ChVector.Vcross(mz2, mx2)); ma1.Set_A_axis(mx, my, mz); // rotate csys because of beta vrota.x = 0.0; vrota.y = beta; vrota.z = 0.0; mrotma.Set_A_Rxyz(vrota); marot_beta.nm.matrix.MatrMultiply(ma1.nm.matrix, mrotma.nm.matrix); // rotate csys because of alpha vrota.x = 0.0; vrota.y = 0.0; vrota.z = alpha; if (react_force.x < 0) { vrota.z = alpha; } else { vrota.z = -alpha; } mrotma.Set_A_Rxyz(vrota); ma1.nm.matrix.MatrMultiply(marot_beta.nm.matrix, mrotma.nm.matrix); ma2.nm.matrix.CopyFromMatrix(ma1.nm.matrix); // is a bevel gear? double be = Math.Acos(ChVector.Vdot(Get_shaft_dir1(), Get_shaft_dir2())); bool is_bevel = true; if (Math.Abs(ChVector.Vdot(Get_shaft_dir1(), Get_shaft_dir2())) > 0.96) { is_bevel = false; } // compute wheel radii so that: // w2 = - tau * w1 if (!is_bevel) { double pardist = ChVector.Vdot(mr, vbdist); double inv_tau = 1.0 / tau; if (!epicyclic) { r2 = pardist - pardist / (inv_tau + 1.0); } else { r2 = pardist - (tau * pardist) / (tau - 1.0); } r1 = r2 * tau; } else { double gamma2; if (!epicyclic) { gamma2 = be / (tau + 1.0); } else { gamma2 = be / (-tau + 1.0); } double al = ChMaths.CH_C_PI - Math.Acos(ChVector.Vdot(Get_shaft_dir2(), my)); double te = ChMaths.CH_C_PI - al - be; double fd = Math.Sin(te) * (dist / Math.Sin(be)); r2 = fd * Math.Tan(gamma2); r1 = r2 * tau; } // compute markers positions, supposing they // stay on the ideal wheel contact point mmark1 = ChVector.Vadd(Get_shaft_pos2(), ChVector.Vmul(mr2, r2)); mmark2 = mmark1; contact_pt = mmark1; // correct marker 1 position if phasing is not correct if (checkphase) { double realtau = tau; if (epicyclic) { realtau = -tau; } double m_delta; m_delta = -(a2 / realtau) - a1 - phase; if (m_delta > ChMaths.CH_C_PI) { m_delta -= (ChMaths.CH_C_2PI); // range -180..+180 is better than 0...360 } if (m_delta > (ChMaths.CH_C_PI / 4.0)) { m_delta = (ChMaths.CH_C_PI / 4.0); // phase correction only in +/- 45° } if (m_delta < -(ChMaths.CH_C_PI / 4.0)) { m_delta = -(ChMaths.CH_C_PI / 4.0); } vrota.x = vrota.y = 0.0; vrota.z = -m_delta; mrotma.Set_A_Rxyz(vrota); // rotate about Z of shaft to correct mmark1 = abs_shaft1.GetA().MatrT_x_Vect(ChVector.Vsub(mmark1, Get_shaft_pos1())); mmark1 = mrotma.Matr_x_Vect(mmark1); mmark1 = ChVector.Vadd(abs_shaft1.GetA().Matr_x_Vect(mmark1), Get_shaft_pos1()); } // Move Shaft 1 along its direction if not aligned to wheel double offset = ChVector.Vdot(Get_shaft_dir1(), (contact_pt - Get_shaft_pos1())); ChVector moff = Get_shaft_dir1() * offset; if (Math.Abs(offset) > 0.0001) { local_shaft1.SetPos(local_shaft1.GetPos() + Body1.TransformDirectionParentToLocal(moff)); } // ! Require that the BDF routine of marker won't handle speed and acc.calculus of the moved marker 2! marker2.SetMotionType(ChMarker.eChMarkerMotion.M_MOTION_EXTERNAL); marker1.SetMotionType(ChMarker.eChMarkerMotion.M_MOTION_EXTERNAL); // move marker1 in proper positions newmarkpos.pos = mmark1; newmarkpos.rot = ma1.Get_A_quaternion(); marker1.Impose_Abs_Coord(newmarkpos); // move marker1 into teeth position // move marker2 in proper positions newmarkpos.pos = mmark2; newmarkpos.rot = ma2.Get_A_quaternion(); marker2.Impose_Abs_Coord(newmarkpos); // move marker2 into teeth position // imposed relative positions/speeds deltaC.pos = ChVector.VNULL; deltaC_dt.pos = ChVector.VNULL; deltaC_dtdt.pos = ChVector.VNULL; deltaC.rot = ChQuaternion.QUNIT; // no relative rotations imposed! deltaC_dt.rot = ChQuaternion.QNULL; deltaC_dtdt.rot = ChQuaternion.QNULL; }