/// <summary> /// Partial initialisation function /// Calculates the state vector \vct{y}_{pi} and Jacobians for a new /// partially-initialised feature from an initial observation. /// @param hi The initial measurement \vct{h}_i , in this case the (x,y) /// image location of the feature. /// </summary> /// <param name="hi"></param> /// <param name="xp">The robot position state \vct{x}_p from which the initial observation was made.</param> public override void func_ypi_and_dypi_by_dxp_and_dypi_by_dhi_and_Ri(Vector hi, Vector xp) { // Representation of a line here: // ypi = (rWi ) // (hLhatWi) // Form the ray (in camera co-ordinates by unprojecting this image location Vector3D hLRi = new Vector3D(((Wide_Camera_Point_Feature_Measurement_Model)wide_model).m_camera.Unproject(hi)); //if (Camera_Constants.DEBUGDUMP) Debug.WriteLine("debug hLRi"); // Form hLhatRi from hLRi // Normalise Vector3D hLhatRi = hLRi; hLhatRi.Normalise(); MatrixFixed dhLhatRi_by_dhLRi = MatrixFixed.dvnorm_by_dv(hLRi); //if (Camera_Constants.DEBUGDUMP) Debug.WriteLine("debug hLhatRi" + hLhatRi); // Now convert this into a direction in world co-ordinates by rotating // Form hLhatWi from hLhatRi // Rotate ((Wide_Camera_Point_Feature_Measurement_Model)wide_model).threed_motion_model.func_q(xp); RotationMatrix RWR = ((Wide_Camera_Point_Feature_Measurement_Model)wide_model).threed_motion_model.get_qRES().RotationMatrix(); Vector3D hLhatWi = new Vector3D(RWR * hLhatRi); //if (Camera_Constants.DEBUGDUMP) Debug.WriteLine("debug hLhatWi" + hLhatWi); // Extract rW from xp ((Wide_Camera_Point_Feature_Measurement_Model)wide_model).threed_motion_model.func_r(xp); // And form ypiRES ypiRES.Update(((Wide_Camera_Point_Feature_Measurement_Model)wide_model).threed_motion_model.get_rRES().GetVNL3(), 0); ypiRES.Update(hLhatWi.GetVNL3(), 3); //if (Camera_Constants.DEBUGDUMP) Debug.WriteLine("debug ypiRES" + ypiRES); // Form Jacobians dypi_by_dxp and dypi_by_dhi // dypi_by_dxp = (drWi_by_dr drWi_by_dq ) // (dhLhatWi_by_dr dhLhatWi_by_dq) // = (I 0 ) // (0 dhLhatWi_by_dq) // hLhatWi = RWR * hLhatRi // => dhLhatWi_by_dq = d/dq ( R(qWR) * hLhatRi) MatrixFixed dhLhatWi_by_dq = MatrixFixed.dRq_times_a_by_dq(((Wide_Camera_Point_Feature_Measurement_Model)wide_model).threed_motion_model.get_qRES(), hLhatRi); // Put dypi_by_dxp together dypi_by_dxpRES.Fill(0.0f); dypi_by_dxpRES.Put(0, 0, 1.0f); dypi_by_dxpRES.Put(1, 1, 1.0f); dypi_by_dxpRES.Put(2, 2, 1.0f); dypi_by_dxpRES.Update(dhLhatWi_by_dq, 3, 3); // cout << "dypi_by_dxpRES" << dypi_by_dxpRES; // dypi_by_dhi = (drWi_by_dhi ) // (dhLhatWi_by_dhi) // = (0 ) // (dhLhatWi_by_dhi) // hLhatWi = RWR * hLhatRi // Need to work out derivative for this // dhLhatWi_by_dhi = RWR * dhLhatRi_by_dhLRi * dhLRi_by_dhi MatrixFixed dhLhatWi_by_dhi = RWR * dhLhatRi_by_dhLRi * ((Wide_Camera_Point_Feature_Measurement_Model)wide_model).m_camera.UnprojectionJacobian(); dypi_by_dhiRES.Fill(0.0f); dypi_by_dhiRES.Update(dhLhatWi_by_dhi, 3, 0); // cout << "dypi_by_dhiRES" << dypi_by_dhiRES; // And construct Ri func_Ri(hi); /* * if (Camera_Constants.DEBUGDUMP) Debug.WriteLine("func_ypi: hi = " + hi + "," + * "xp = " + xp + "," + * "ypiRES = " + ypiRES); */ }