//Create ROVerto body
//Main Frame
sf::Polyhedron* profileO = new sf::Polyhedron("ProfileOrigin", path_data + "/bperfil_59,5_ORIGIN_.stl", 1, sf::I4(), "ProfileMat", sf::BodyPhysicsType::SUBMERGED, "metal_gray");
profileO->ScalePhysicalPropertiesToArbitraryMass(1.364);
sf::Polyhedron* profile53 = new sf::Polyhedron("ProfileHorizontalLateral", path_data + "/bperfil_53_.stl", 1, sf::I4(), "ProfileMat", sf::BodyPhysicsType::SUBMERGED, "metal_gray");
profile53->ScalePhysicalPropertiesToArbitraryMass(1.763);
sf::Polyhedron* profile11 = new sf::Polyhedron("ProfileVerticalFeet", path_data + "/bperfil_11,0_.stl", 1, sf::I4(), "ProfileMat", sf::BodyPhysicsType::SUBMERGED, "metal_gray");
profile11->ScalePhysicalPropertiesToArbitraryMass(.366);
sf::Polyhedron* profile41 = new sf::Polyhedron("ProfileHorizontalInner", path_data + "/bperfil_59,5_ORIGIN_.stl", 1, sf::I4(), "ProfileMat", sf::BodyPhysicsType::SUBMERGED, "metal_gray");
profile41->ScalePhysicalPropertiesToArbitraryMass(1.364);
sf::Polyhedron* sheet_acr = new sf::Polyhedron("Sheet", path_data + "/bsoporte_lateral_.stl", 1, sf::I4(), "AcrMat", sf::BodyPhysicsType::SUBMERGED, "polim_white");
sheet_acr->ScalePhysicalPropertiesToArbitraryMass(1.11);
sf::Polyhedron* top_acr = new sf::Polyhedron("TopAcrylic", path_data + "/bsoporte_acr_.stl", 1, sf::I4(), "AcrMat", sf::BodyPhysicsType::SUBMERGED, "polim_white");
top_acr->ScalePhysicalPropertiesToArbitraryMass(.142);
sf::Polyhedron* foam_feet = new sf::Polyhedron("FoamFeet", path_data + "/bespuma_pata_.stl", 1, sf::I4(), "FoamMat", sf::BodyPhysicsType::SUBMERGED, "yellow");
foam_feet->ScalePhysicalPropertiesToArbitraryMass(.01);
// sf::Cylinder* cylinder = new sf::Cylinder("cylinder", .3, .1, sf::I4(), "BoxMat", sf::BodyPhysicsType::SUBMERGED, "yellow");
//Inner Components
sf::Polyhedron* bottle = new sf::Polyhedron("AluminiumBottle", path_data + "/bbotella_alu_.stl", 1, sf::I4(), "FoamMat", sf::BodyPhysicsType::SUBMERGED, "black");
bottle->ScalePhysicalPropertiesToArbitraryMass(3.7); // Peso promedio entre ambas botellas
sf::Polyhedron* camera = new sf::Polyhedron("Camera", path_data + "/bcamara_.stl", 1, sf::I4(), "CamMat", sf::BodyPhysicsType::SUBMERGED, "black");
camera->ScalePhysicalPropertiesToArbitraryMass(1.718);
sf::Polyhedron* supp_cams_l = new sf::Polyhedron("SupportCameraLow", path_data + "/bsoporte_cams_abj_.stl", 1, sf::I4(), "SuppMat", sf::BodyPhysicsType::SUBMERGED, "black");
supp_cams_l->ScalePhysicalPropertiesToArbitraryMass(.277);
sf::Polyhedron* supp_cams_h = new sf::Polyhedron("SupportCameraHigh", path_data + "/bsoporte_cams_arr_.stl", 1, sf::I4(), "SuppMat", sf::BodyPhysicsType::SUBMERGED, "black");
supp_cams_h->ScalePhysicalPropertiesToArbitraryMass(.655);
sf::Polyhedron* supp_sens = new sf::Polyhedron("SupportSensor", path_data + "/bsoporte_sens_.stl", 1, sf::I4(), "SuppMat", sf::BodyPhysicsType::SUBMERGED, "black");
supp_sens->ScalePhysicalPropertiesToArbitraryMass(1.189);
sf::Polyhedron* light = new sf::Polyhedron("LightBottle", path_data + "/bluz_.stl", 1, sf::I4(), "LightMat", sf::BodyPhysicsType::SUBMERGED, "black");
light->ScalePhysicalPropertiesToArbitraryMass(.668);
sf::Polyhedron* ROV_sensor = new sf::Polyhedron("ROVSensor", path_data + "/bsensor_.stl", 1, sf::I4(), "SensorMat", sf::BodyPhysicsType::SUBMERGED, "black");
ROV_sensor->ScalePhysicalPropertiesToArbitraryMass(7.2);
sf::Polyhedron* foam_block_1 = new sf::Polyhedron("FoamBlock", path_data + "/bespuma_.stl", 1, sf::I4(), "FoamMat", sf::BodyPhysicsType::SUBMERGED, "yellow");
// foam_block_1->ScalePhysicalPropertiesToArbitraryMass(.123);
sf::Box* foam_block_2 = new sf::Box("FoamBlock2", sf::Vector3(.1,.12,.035), sf::I4(), "FoamMat", sf::BodyPhysicsType::SUBMERGED, "yellow");
sf::Box* foam_block_3 = new sf::Box("FoamBlock3", sf::Vector3(.08,.12,.3), sf::I4(), "FoamMat", sf::BodyPhysicsType::SUBMERGED, "yellow");
sf::Polyhedron* foam_corner = new sf::Polyhedron("FoamCorner", path_data + "/bespuma_esq_.stl", 1, sf::I4(), "FoamMat", sf::BodyPhysicsType::SUBMERGED, "yellow");
foam_corner->ScalePhysicalPropertiesToArbitraryMass(.016);
sf::Polyhedron* propeller = new sf::Polyhedron("Propeller", path_data + "/bT200_.stl", 1, sf::Transform(sf::Quaternion(M_PI_2, 0, 0)), "ThrustMat", sf::BodyPhysicsType::SUBMERGED, "black");
propeller->ScalePhysicalPropertiesToArbitraryMass(.34382302);
//NOTE: investigate variable "isBuoyant". In the example UnderwaterTest they set it false.
//Build body
vehicle = new sf::Compound("Vehicle", profileO, sf::I4(), sf::BodyPhysicsType::SUBMERGED);
vehicle->AddExternalPart(profile11, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.250, .220500, 0.07)));
vehicle->AddExternalPart(profile11, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.250, .220500, 0.07)));
vehicle->AddExternalPart(profile11, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.250, -.220500, 0.07)));
vehicle->AddExternalPart(profile11, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.250, -.220500, 0.07)));
vehicle->AddExternalPart(profile41, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.090, 0, -0.154)));
vehicle->AddExternalPart(profile41, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0, 0, -0.315)));
vehicle->AddExternalPart(profile53, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0, .220500, 0)));
vehicle->AddExternalPart(profile53, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0, -.220500, 0)));
vehicle->AddExternalPart(profile53, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0, .220500, -0.154)));
vehicle->AddExternalPart(profile53, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0, -.220500, -0.154)));
vehicle->AddExternalPart(profile53, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0, .220500, -0.315)));
vehicle->AddExternalPart(profile53, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0, -.220500, -0.315)));
vehicle->AddExternalPart(foam_feet, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.250, 0.220500, 0.137732)));
vehicle->AddExternalPart(foam_feet, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.250, 0.220500, 0.137732)));
vehicle->AddExternalPart(foam_feet, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.250, -0.220500, 0.137732)));
vehicle->AddExternalPart(foam_feet, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.250, -0.220500, 0.137732)));
vehicle->AddExternalPart(sheet_acr, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.268075, 0, -0.1575)));
vehicle->AddExternalPart(sheet_acr, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.268075, 0, -0.1575)));
vehicle->AddExternalPart(top_acr, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.129032, 0.158930, -0.3315)));
vehicle->AddExternalPart(top_acr, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.129032, 0.158930, -0.3315)));
vehicle->AddExternalPart(top_acr, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.129032, -0.158930, -0.3315)));
vehicle->AddExternalPart(top_acr, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.129032, -0.158930, -0.3315)));
// vehicle->AddExternalPart(cylinder, sf::Transform(sf::Quaternion::getIdentity(), sf::Vector3(1.2, 1.2, 0)));
//Add inner components
vehicle->AddExternalPart(bottle, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.093553, 0.0055, -0.073530)));
vehicle->AddExternalPart(bottle, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.093460, 0.0055, -0.235823)));
// vehicle->AddExternalPart(bottle, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.004749, 0.0055, -0.155542)));
vehicle->AddExternalPart(camera, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.210, 0.079198, -0.099868)));
vehicle->AddExternalPart(camera, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.210, -0.003752, -0.099868)));
vehicle->AddExternalPart(camera, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.210, -0.086702, -0.099868)));
vehicle->AddExternalPart(supp_cams_l, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.210694, -0.004496, -0.179)));
vehicle->AddExternalPart(supp_cams_h, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.209106, -0.002968, -0.025)));
vehicle->AddExternalPart(supp_sens, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.165369, -0.0055, -0.129)));
vehicle->AddExternalPart(light, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.165, 0.1414, -0.129844)));
vehicle->AddExternalPart(light, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.165, -0.1524, -0.129844)));
vehicle->AddExternalPart(ROV_sensor, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.164742, -0.005441, -0.186226)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, M_PI_2), sf::Vector3(0.213250, 0.1735, -0.2684)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.0225, 0, -0.268))); //ADDED
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.0225, 0, -0.204))); //ADDED
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.0225, 0.12, -0.048))); //ADDED
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.0225, -0.12, -0.048))); //ADDED
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.0225, 0, -0.048))); //ADDED
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.0805, 0.1439, -0.298)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.184, 0.1439, -0.298)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.184, -0.1439, -0.298)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.0805, -0.1439, -0.298)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, M_PI_2), sf::Vector3(0.213250, -0.1735, -0.2684)));
vehicle->AddExternalPart(foam_block_2, sf::Transform(sf::Quaternion(0, 0, M_PI_2), sf::Vector3(0.213250, -0.1735, -0.0984))); //ADDED
vehicle->AddExternalPart(foam_block_2, sf::Transform(sf::Quaternion(0, 0, M_PI_2), sf::Vector3(0.213250, 0.1735, -0.0984))); //ADDED
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.182, 0.16061, -0.365)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.0785, 0.16061, -0.365)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.078844, 0.16061, -0.365)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.182344, 0.16061, -0.365)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.182344, -0.155684, -0.365)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.078844, -0.155684, -0.365)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.0785, -0.155684, -0.365)));
vehicle->AddExternalPart(foam_block_1, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.182, -0.155684, -0.365)));
vehicle->AddExternalPart(foam_corner, sf::Transform(sf::Quaternion(0, 0, M_PI), sf::Vector3(0.261650, 0.248232, -0.300)));
vehicle->AddExternalPart(foam_corner, sf::Transform(sf::Quaternion(0, 0, M_PI), sf::Vector3(-0.261650, 0.248232, -0.300)));
vehicle->AddExternalPart(foam_corner, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.261650, -0.248232, -0.300)));
vehicle->AddExternalPart(foam_corner, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.261650, -0.248232, -0.300)));
vehicle->AddExternalPart(foam_block_3, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.308075, 0.15, -0.1575))); //ADDED
vehicle->AddExternalPart(foam_block_3, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0.308075, -0.15, -0.1575))); //ADDED
vehicle->AddExternalPart(foam_block_3, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.308075, 0.15, -0.1575))); //ADDED
vehicle->AddExternalPart(foam_block_3, sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(-0.308075, -0.15, -0.1575))); //ADDED
//Create Thrusters
xl = new sf::Thruster("XL", propeller, 0.076, std::make_pair(0.43,0.43), 0.09, 3000, true);
xr = new sf::Thruster("XR", propeller, 0.076, std::make_pair(0.43,0.43), 0.09, 3000, true);
zb = new sf::Thruster("ZB", propeller, 0.076, std::make_pair(0.43,0.43), 0.09, 3000, true);
zf = new sf::Thruster("ZF", propeller, 0.076, std::make_pair(0.43,0.43), 0.09, 3000, true);
yd = new sf::Thruster("YD", propeller, 0.076, std::make_pair(0.43,0.43), 0.09, 3000, true);
yu = new sf::Thruster("YU", propeller, 0.076, std::make_pair(0.43,0.43), 0.09, 3000, true);
//Thrusters
roverto->DefineLinks(vehicle);
roverto->AddLinkActuator(xl, "Vehicle", sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0, -0.289940, -0.144792)));
roverto->AddLinkActuator(xr, "Vehicle", sf::Transform(sf::Quaternion(0, 0, 0), sf::Vector3(0, 0.289940, -0.144792)));
roverto->AddLinkActuator(yd, "Vehicle", sf::Transform(sf::Quaternion(M_PI_2, 0, 0), sf::Vector3(-0.009208, 0, 0.069440)));
roverto->AddLinkActuator(yu, "Vehicle", sf::Transform(sf::Quaternion(M_PI_2, 0, 0), sf::Vector3(-0.009208, 0, -0.38440)));
roverto->AddLinkActuator(zb, "Vehicle", sf::Transform(sf::Quaternion(0, -M_PI_2, 0), sf::Vector3(-0.319590, -0.003956, -0.153)));
roverto->AddLinkActuator(zf, "Vehicle", sf::Transform(sf::Quaternion(0, -M_PI_2, 0), sf::Vector3(0.319590, -0.003956, -0.153)));