diff --git a/.github/workflows/rust.yml b/.github/workflows/rust.yml index 19196bc..8eb3df6 100644 --- a/.github/workflows/rust.yml +++ b/.github/workflows/rust.yml @@ -16,10 +16,12 @@ jobs: steps: - uses: actions/checkout@v3 + - name: Update Rrust + run: rustup update - name: Build run: cargo build --verbose - name: Run tests run: cargo test --verbose - name: Check format - run: cargo fmt; git diff-index --exit-code HEAD -- . + run: cargo fmt --verbose; git diff-index --exit-code HEAD -- . diff --git a/src/remote_api_objects/sim/mod.rs b/src/remote_api_objects/sim/mod.rs index 0d8e0ce..ea93d51 100644 --- a/src/remote_api_objects/sim/mod.rs +++ b/src/remote_api_objects/sim/mod.rs @@ -1,9 +1,7 @@ #[rustfmt::skip] mod sim_api; - #[rustfmt::skip] mod sim_const; - #[rustfmt::skip] mod sim_ik_api; diff --git a/src/remote_api_objects/sim/sim_api.rs b/src/remote_api_objects/sim/sim_api.rs index 97ba155..22bf90f 100644 --- a/src/remote_api_objects/sim/sim_api.rs +++ b/src/remote_api_objects/sim/sim_api.rs @@ -1,384 +1,384 @@ use crate::RemoteApiClientInterface; -pub trait Sim: RemoteApiClientInterface { - requests! { - "sim", - (sim_set_joint_max_force,"setJointMaxForce",(object_handle:i64,force_or_torque:f64)->()), - (sim_get_joint_max_force,"getJointMaxForce",(joint_handle:i64)->f64), - (sim_create_pure_shape,"createPureShape",(primitive_type:i64,options:i64,sizes:Vec,mass:f64),opt(precision:Vec)->i64), - (sim_remove_object,"removeObject",(object_handle:i64)->()), - (sim_get_vision_sensor_depth_buffer,"getVisionSensorDepthBuffer",(sensor_handle:i64),opt(pos:Vec,size:Vec)->(Vec,Vec)), - (sim_get_vision_sensor_char_image,"getVisionSensorCharImage",(sensor_handle:i64),opt(pos:Vec,size:Vec)->(Vec,Vec)), - (sim_set_vision_sensor_char_image,"setVisionSensorCharImage",(sensor_handle:i64,image:Vec)->()), - (sim_get_object_selection,"getObjectSelection"->Vec), - (sim_set_object_selection,"setObjectSelection",(object_handles:Vec)->()), - (sim_get_string_signal,"getStringSignal",(signal_name:String)->Option>), - (sim_get_int32_signal,"getInt32Signal",(signal_name:String)->Option), - (sim_get_float_signal,"getFloatSignal",(signal_name:String)->Option), - (sim_acquire_lock,"acquireLock"->()), - (sim_add_drawing_object,"addDrawingObject",(object_type:i64,size:f64,duplicate_tolerance:f64,parent_object_handle:i64,max_item_count:i64),opt(color:Vec)->i64), - (sim_add_drawing_object_item,"addDrawingObjectItem",(drawing_object_handle:i64,item_data:Vec)->i64), - (sim_add_force,"addForce",(shape_handle:i64,position:Vec,force:Vec)->()), - (sim_add_force_and_torque,"addForceAndTorque",(shape_handle:i64),opt(force:Vec,torque:Vec)->()), - (sim_add_graph_curve,"addGraphCurve",(graph_handle:i64,curve_name:String,dim:i64,stream_ids:Vec,default_values:Vec,unit_str:String),opt(options:i64,color:Vec,curve_width:i64)->i64), - (sim_add_graph_stream,"addGraphStream",(graph_handle:i64,stream_name:String,unit:String),opt(options:i64,color:Vec,cyclic_range:f64)->i64), - (sim_add_item_to_collection,"addItemToCollection",(collection_handle:i64,what:i64,object_handle:i64,options:i64)->()), - (sim_add_log,"addLog",(verbosity_level:i64,log_message:String)->()), - (sim_add_particle_object,"addParticleObject",(object_type:i64,size:f64,density:f64,params:Vec,life_time:f64,max_item_count:i64),opt(color:Vec)->i64), - (sim_add_particle_object_item,"addParticleObjectItem",(object_handle:i64,item_data:Vec)->()), - (sim_add_referenced_handle,"addReferencedHandle",(object_handle:i64,referenced_handle:i64)->()), - (sim_add_script,"addScript",(script_type:i64)->i64), - (sim_adjust_view,"adjustView",(view_handle_or_index:i64,associated_viewable_object_handle:i64,options:i64),opt(view_label:String)->i64), - (sim_align_shape_bb,"alignShapeBB",(shape_handle:i64,pose:Vec)->i64), - (sim_alpha_beta_gamma_to_yaw_pitch_roll,"alphaBetaGammaToYawPitchRoll",(alpha_angle:f64,beta_angle:f64,gamma_angle:f64)->(f64,f64,f64)), - (sim_announce_scene_content_change,"announceSceneContentChange"->i64), - (sim_associate_script_with_object,"associateScriptWithObject",(script_handle:i64,object_handle:i64)->()), - (sim_auxiliary_console_close,"auxiliaryConsoleClose",(console_handle:i64)->i64), - (sim_auxiliary_console_open,"auxiliaryConsoleOpen",(title:String,max_lines:i64,mode:i64),opt(position:Vec,size:Vec,text_color:Vec,background_color:Vec)->i64), - (sim_auxiliary_console_print,"auxiliaryConsolePrint",(console_handle:i64,text:String)->i64), - (sim_auxiliary_console_show,"auxiliaryConsoleShow",(console_handle:i64,show_state:bool)->i64), - (sim_broadcast_msg,"broadcastMsg",(message:serde_json::Value),opt(options:i64)->()), - (sim_build_identity_matrix,"buildIdentityMatrix"->Vec), - (sim_build_matrix,"buildMatrix",(position:Vec,euler_angles:Vec)->Vec), - (sim_build_matrix_q,"buildMatrixQ",(position:Vec,quaternion:Vec)->Vec), - (sim_build_pose,"buildPose",(position:Vec,euler_angles_or_axis:Vec),opt(mode:i64,axis2:Vec)->Vec), - (sim_call_script_function,"callScriptFunction",(function_name:String,script_handle:i64),opt(in_arg:serde_json::Value)->serde_json::Value), - (sim_camera_fit_to_view,"cameraFitToView",(view_handle_or_index:i64),opt(object_handles:Vec,options:i64,scaling:f64)->i64), - (sim_change_entity_color,"changeEntityColor",(entity_handle:i64,new_color:Vec),opt(color_component:i64)->Vec), - (sim_check_collision,"checkCollision",(entity1_handle:i64,entity2_handle:i64)->(i64,Vec)), - (sim_check_collision_ex,"checkCollisionEx",(entity1_handle:i64,entity2_handle:i64)->(i64,Vec)), - (sim_check_distance,"checkDistance",(entity1_handle:i64,entity2_handle:i64),opt(threshold:f64)->(i64,Vec,Vec)), - (sim_check_octree_point_occupancy,"checkOctreePointOccupancy",(octree_handle:i64,options:i64,points:Vec)->(i64,i64,i64,i64)), - (sim_check_proximity_sensor,"checkProximitySensor",(sensor_handle:i64,entity_handle:i64)->(i64,f64,Vec,i64,Vec)), - (sim_check_proximity_sensor_ex,"checkProximitySensorEx",(sensor_handle:i64,entity_handle:i64,mode:i64,threshold:f64,max_angle:f64)->(i64,f64,Vec,i64,Vec)), - (sim_check_proximity_sensor_ex2,"checkProximitySensorEx2",(sensor_handle:i64,vertices:Vec,item_type:i64,item_count:i64,mode:i64,threshold:f64,max_angle:f64)->(i64,f64,Vec,Vec)), - (sim_check_vision_sensor,"checkVisionSensor",(sensor_handle:i64,entity_handle:i64)->(i64,Vec,Vec)), - (sim_check_vision_sensor_ex,"checkVisionSensorEx",(sensor_handle:i64,entity_handle:i64,return_image:bool)->Vec), - (sim_clear_float_signal,"clearFloatSignal",(signal_name:String)->()), - (sim_clear_int32_signal,"clearInt32Signal",(signal_name:String)->()), - (sim_clear_string_signal,"clearStringSignal",(signal_name:String)->()), - (sim_close_scene,"closeScene"->i64), - (sim_combine_rgb_images,"combineRgbImages",(img1:Vec,img1_res:Vec,img2:Vec,img2_res:Vec,operation:i64)->Vec), - (sim_compute_mass_and_inertia,"computeMassAndInertia",(shape_handle:i64,density:f64)->i64), - (sim_convex_decompose,"convexDecompose",(shape_handle:i64,options:i64,int_params:Vec,float_params:Vec)->i64), - (sim_copy_paste_objects,"copyPasteObjects",(object_handles:Vec),opt(options:i64)->Vec), - (sim_copy_table,"copyTable",(original:Vec)->Vec), - (sim_create_collection,"createCollection",opt(options:i64)->i64), - (sim_create_dummy,"createDummy",(size:f64)->i64), - (sim_create_force_sensor,"createForceSensor",(options:i64,int_params:Vec,float_params:Vec)->i64), - (sim_create_heightfield_shape,"createHeightfieldShape",(options:i64,shading_angle:f64,x_point_count:i64,y_point_count:i64,x_size:f64,heights:Vec)->i64), - (sim_create_joint,"createJoint",(joint_type:i64,joint_mode:i64,options:i64),opt(sizes:Vec)->i64), - (sim_create_octree,"createOctree",(voxel_size:f64,options:i64,point_size:f64)->i64), - (sim_create_path,"createPath",(ctrl_pts:Vec),opt(options:i64,subdiv:i64,smoothness:f64,orientation_mode:i64,up_vector:Vec)->i64), - (sim_create_point_cloud,"createPointCloud",(max_voxel_size:f64,max_pt_cnt_per_voxel:i64,options:i64,point_size:f64)->i64), - (sim_create_primitive_shape,"createPrimitiveShape",(primitive_type:i64,sizes:Vec),opt(options:i64)->i64), - (sim_create_proximity_sensor,"createProximitySensor",(sensor_type:i64,sub_type:i64,options:i64,int_params:Vec,float_params:Vec)->i64), - (sim_create_shape,"createShape",(options:i64,shading_angle:f64,vertices:Vec,indices:Vec,normals:Vec,texture_coordinates:Vec,texture:Vec,texture_resolution:Vec)->i64), - (sim_create_texture,"createTexture",(file_name:String,options:i64),opt(plane_sizes:Vec,scaling_uv:Vec,xy_g:Vec,fixed_resolution:i64,resolution:Vec)->(i64,i64,Vec)), - (sim_create_vision_sensor,"createVisionSensor",(options:i64,int_params:Vec,float_params:Vec)->i64), - (sim_destroy_collection,"destroyCollection",(collection_handle:i64)->()), - (sim_destroy_graph_curve,"destroyGraphCurve",(graph_handle:i64,curve_id:i64)->()), - (sim_duplicate_graph_curve_to_static,"duplicateGraphCurveToStatic",(graph_handle:i64,curve_id:i64),opt(curve_name:String)->i64), - (sim_execute_script_string,"executeScriptString",(string_to_execute:String,script_handle:i64)->(i64,serde_json::Value)), - (sim_export_mesh,"exportMesh",(fileformat:i64,path_and_filename:String,options:i64,scaling_factor:f64,vertices:Vec,indices:Vec)->()), - (sim_floating_view_add,"floatingViewAdd",(pos_x:f64,pos_y:f64,size_x:f64,size_y:f64,options:i64)->i64), - (sim_floating_view_remove,"floatingViewRemove",(floating_view_handle:i64)->i64), - (sim_generate_shape_from_path,"generateShapeFromPath",(path:Vec,section:Vec),opt(options:i64,up_vector:Vec)->i64), - (sim_generate_text_shape,"generateTextShape",(txt:String),opt(color:Vec,height:f64,centered:bool,alphabet_location:String)->i64), - (sim_generate_time_optimal_trajectory,"generateTimeOptimalTrajectory",(path:Vec,path_lengths:Vec,min_max_vel:Vec,min_max_accel:Vec),opt(traj_pt_samples:i64,boundary_condition:String,timeout:f64)->(Vec,Vec)), - (sim_get_alternate_configs,"getAlternateConfigs",(joint_handles:Vec,input_config:Vec),opt(tip_handle:i64,low_limits:Vec,ranges:Vec)->Vec), - (sim_get_api_func,"getApiFunc",(script_handle:i64,api_word:String)->Vec), - (sim_get_api_info,"getApiInfo",(script_handle:i64,api_word:String)->String), - (sim_get_array_param,"getArrayParam",(parameter:i64)->Vec), - (sim_get_auto_yield_delay,"getAutoYieldDelay"->f64), - (sim_get_bool_param,"getBoolParam",(parameter:i64)->bool), - (sim_get_closest_pos_on_path,"getClosestPosOnPath",(path:Vec,path_lengths:Vec,abs_pt:Vec)->f64), - (sim_get_collection_objects,"getCollectionObjects",(collection_handle:i64)->Vec), - (sim_get_config_distance,"getConfigDistance",(config_a:Vec,config_b:Vec),opt(metric:Vec,types:Vec)->f64), - (sim_get_contact_info,"getContactInfo",(dynamic_pass:i64,object_handle:i64,index:i64)->(Vec,Vec,Vec,Vec)), - (sim_get_decimated_mesh,"getDecimatedMesh",(vertices_in:Vec,indices_in:Vec,decimation_percentage:f64)->(Vec,Vec)), - (sim_get_engine_bool_param,"getEngineBoolParam",(param_id:i64,object_handle:i64)->bool), - (sim_get_engine_float_param,"getEngineFloatParam",(param_id:i64,object_handle:i64)->f64), - (sim_get_engine_int32_param,"getEngineInt32Param",(param_id:i64,object_handle:i64)->i64), - (sim_get_euler_angles_from_matrix,"getEulerAnglesFromMatrix",(matrix:Vec)->Vec), - (sim_get_explicit_handling,"getExplicitHandling",(object_handle:i64)->i64), - (sim_get_extension_string,"getExtensionString",(object_handle:i64,index:i64),opt(key:String)->String), - (sim_get_float_param,"getFloatParam",(parameter:i64)->f64), - (sim_get_genesis_events,"getGenesisEvents"->Vec), - (sim_get_graph_curve,"getGraphCurve",(graph_handle:i64,graph_type:i64,curve_index:i64)->(String,i64,Vec,Vec,Vec,Vec,i64,i64)), - (sim_get_graph_info,"getGraphInfo",(graph_handle:i64)->(i64,Vec,Vec,i64)), - (sim_get_int32_param,"getInt32Param",(parameter:i64)->i64), - (sim_get_is_real_time_simulation,"getIsRealTimeSimulation"->i64), - (sim_get_joint_dependency,"getJointDependency",(joint_handle:i64)->(i64,f64,f64)), - (sim_get_joint_force,"getJointForce",(joint_handle:i64)->f64), - (sim_get_joint_interval,"getJointInterval",(object_handle:i64)->(bool,Vec)), - (sim_get_joint_mode,"getJointMode",(joint_handle:i64)->(i64,i64)), - (sim_get_joint_position,"getJointPosition",(object_handle:i64)->f64), - (sim_get_joint_target_force,"getJointTargetForce",(joint_handle:i64)->f64), - (sim_get_joint_target_position,"getJointTargetPosition",(object_handle:i64)->f64), - (sim_get_joint_target_velocity,"getJointTargetVelocity",(object_handle:i64)->f64), - (sim_get_joint_type,"getJointType",(object_handle:i64)->i64), - (sim_get_joint_velocity,"getJointVelocity",(joint_handle:i64)->f64), - (sim_get_last_info,"getLastInfo"->String), - (sim_get_light_parameters,"getLightParameters",(light_handle:i64)->(i64,Vec,Vec,Vec)), - (sim_get_link_dummy,"getLinkDummy",(dummy_handle:i64)->i64), - (sim_get_matching_persistent_data_tags,"getMatchingPersistentDataTags",(pattern:String)->Vec), - (sim_get_matrix_inverse,"getMatrixInverse",(matrix:Vec)->Vec), - (sim_get_model_property,"getModelProperty",(object_handle:i64)->i64), - (sim_get_named_bool_param,"getNamedBoolParam",(name:String)->bool), - (sim_get_named_float_param,"getNamedFloatParam",(name:String)->f64), - (sim_get_named_int32_param,"getNamedInt32Param",(name:String)->i64), - (sim_get_named_string_param,"getNamedStringParam",(param_name:String)->Vec), - (sim_get_navigation_mode,"getNavigationMode"->i64), - (sim_get_object,"getObject",(path:String),opt(options:serde_json::Value)->i64), - (sim_get_object_alias,"getObjectAlias",(object_handle:i64),opt(options:i64)->String), - (sim_get_object_alias_relative,"getObjectAliasRelative",(handle:i64,base_handle:i64),opt(options:i64)->String), - (sim_get_object_child,"getObjectChild",(object_handle:i64,index:i64)->i64), - (sim_get_object_child_pose,"getObjectChildPose",(object_handle:i64)->Vec), - (sim_get_object_color,"getObjectColor",(object_handle:i64,index:i64,color_component:i64)->Vec), - (sim_get_object_float_array_param,"getObjectFloatArrayParam",(object_handle:i64,parameter_id:i64)->Vec), - (sim_get_object_float_param,"getObjectFloatParam",(object_handle:i64,parameter_id:i64)->f64), - (sim_get_object_from_uid,"getObjectFromUid",(uid:i64),opt(options:serde_json::Value)->()), - (sim_get_object_int32_param,"getObjectInt32Param",(object_handle:i64,parameter_id:i64)->i64), - (sim_get_object_matrix,"getObjectMatrix",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), - (sim_get_object_orientation,"getObjectOrientation",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), - (sim_get_object_parent,"getObjectParent",(object_handle:i64)->i64), - (sim_get_object_pose,"getObjectPose",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), - (sim_get_object_position,"getObjectPosition",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), - (sim_get_object_property,"getObjectProperty",(object_handle:i64)->i64), - (sim_get_object_quaternion,"getObjectQuaternion",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), - (sim_get_object_sel,"getObjectSel"->Vec), - (sim_get_object_size_factor,"getObjectSizeFactor",(object_handle:i64)->f64), - (sim_get_object_special_property,"getObjectSpecialProperty",(object_handle:i64)->i64), - (sim_get_object_string_param,"getObjectStringParam",(object_handle:i64,parameter_id:i64)->Vec), - (sim_get_object_type,"getObjectType",(object_handle:i64)->i64), - (sim_get_object_uid,"getObjectUid",(object_handle:i64)->i64), - (sim_get_object_velocity,"getObjectVelocity",(object_handle:i64)->(Vec,Vec)), - (sim_get_objects,"getObjects",(index:i64,object_type:i64)->i64), - (sim_get_objects_in_tree,"getObjectsInTree",(tree_base_handle:i64),opt(object_type:i64,options:i64)->Vec), - (sim_get_octree_voxels,"getOctreeVoxels",(octree_handle:i64)->Vec), - (sim_get_page,"getPage"->i64), - (sim_get_path_interpolated_config,"getPathInterpolatedConfig",(path:Vec,path_lengths:Vec,t:f64),opt(method:serde_json::Value,types:Vec)->Vec), - (sim_get_path_lengths,"getPathLengths",(path:Vec,dof:i64),opt(dist_callback:String)->(Vec,f64)), - (sim_get_persistent_data_tags,"getPersistentDataTags"->Vec), - (sim_get_plugin_info,"getPluginInfo",(plugin_name:String,info_type:i64)->String), - (sim_get_plugin_name,"getPluginName",(index:i64)->String), - (sim_get_point_cloud_options,"getPointCloudOptions",(point_cloud_handle:i64)->(f64,i64,i64,f64)), - (sim_get_point_cloud_points,"getPointCloudPoints",(point_cloud_handle:i64)->Vec), - (sim_get_pose_inverse,"getPoseInverse",(pose:Vec)->Vec), - (sim_get_q_hull,"getQHull",(vertices_in:Vec)->(Vec,Vec)), - (sim_get_quaternion_from_matrix,"getQuaternionFromMatrix",(matrix:Vec)->Vec), - (sim_get_random,"getRandom",opt(seed:i64)->f64), - (sim_get_referenced_handles,"getReferencedHandles",(object_handle:i64)->Vec), - (sim_get_rotation_axis,"getRotationAxis",(matrix_start:Vec,matrix_goal:Vec)->(Vec,f64)), - (sim_get_scaled_image,"getScaledImage",(image_in:Vec,resolution_in:Vec,desired_resolution_out:Vec,options:i64)->(Vec,Vec)), - (sim_get_script,"getScript",(script_type:i64),opt(object_handle:i64,script_name:String)->i64), - (sim_get_script_functions,"getScriptFunctions",(script_handle:i64)->serde_json::Value), - (sim_get_script_int32_param,"getScriptInt32Param",(script_handle:i64,parameter_id:i64)->i64), - (sim_get_script_string_param,"getScriptStringParam",(script_handle:i64,parameter_id:i64)->Vec), - (sim_get_setting_bool,"getSettingBool",(key:String)->bool), - (sim_get_setting_float,"getSettingFloat",(key:String)->f64), - (sim_get_setting_int32,"getSettingInt32",(key:String)->i64), - (sim_get_setting_string,"getSettingString",(key:String)->String), - (sim_get_shape_bb,"getShapeBB",(shape_handle:i64)->Vec), - (sim_get_shape_color,"getShapeColor",(shape_handle:i64,color_name:String,color_component:i64)->(i64,Vec)), - (sim_get_shape_geom_info,"getShapeGeomInfo",(shape_handle:i64)->(i64,i64,Vec)), - (sim_get_shape_inertia,"getShapeInertia",(shape_handle:i64)->(Vec,Vec)), - (sim_get_shape_mass_and_inertia,"getShapeMassAndInertia",(shape_handle:i64)->f64), - (sim_get_shape_mesh,"getShapeMesh",(shape_handle:i64)->(Vec,Vec,Vec)), - (sim_get_shape_texture_id,"getShapeTextureId",(shape_handle:i64)->i64), - (sim_get_shape_viz,"getShapeViz",(shape_handle:i64,item_index:i64)->serde_json::Value), - (sim_get_signal_name,"getSignalName",(signal_index:i64,signal_type:i64)->String), - (sim_get_simulation_state,"getSimulationState"->i64), - (sim_get_simulation_stopping,"getSimulationStopping"->bool), - (sim_get_simulation_time,"getSimulationTime"->f64), - (sim_get_simulation_time_step,"getSimulationTimeStep"->f64), - (sim_get_simulator_message,"getSimulatorMessage"->(i64,Vec,Vec)), - (sim_get_stack_traceback,"getStackTraceback",opt(script_handle:i64)->String), - (sim_get_string_param,"getStringParam",(parameter:i64)->String), - (sim_get_system_time,"getSystemTime"->f64), - (sim_get_texture_id,"getTextureId",(texture_name:String)->(i64,Vec)), - (sim_get_thread_id,"getThreadId"->i64), - (sim_get_user_variables,"getUserVariables"->Vec), - (sim_get_velocity,"getVelocity",(shape_handle:i64)->(Vec,Vec)), - (sim_get_vision_sensor_depth,"getVisionSensorDepth",(sensor_handle:i64),opt(options:i64,pos:Vec,size:Vec)->(Vec,Vec)), - (sim_get_vision_sensor_img,"getVisionSensorImg",(sensor_handle:i64),opt(options:i64,rgba_cut_off:f64,pos:Vec,size:Vec)->(Vec,Vec)), - (sim_get_vision_sensor_res,"getVisionSensorRes",(sensor_handle:i64)->()), - (sim_group_shapes,"groupShapes",(shape_handles:Vec),opt(merge:bool)->i64), - (sim_handle_add_on_scripts,"handleAddOnScripts",(call_type:i64)->i64), - (sim_handle_child_scripts,"handleChildScripts",(call_type:i64)->i64), - (sim_handle_dynamics,"handleDynamics",(delta_time:f64)->i64), - (sim_handle_embedded_scripts,"handleEmbeddedScripts",(call_type:i64)->i64), - (sim_handle_graph,"handleGraph",(object_handle:i64,simulation_time:f64)->()), - (sim_handle_joint_motion,"handleJointMotion"->()), - (sim_handle_proximity_sensor,"handleProximitySensor",(sensor_handle:i64)->(i64,f64,Vec,i64,Vec)), - (sim_handle_sandbox_script,"handleSandboxScript",(call_type:i64)->()), - (sim_handle_sensing_start,"handleSensingStart"->()), - (sim_handle_simulation_start,"handleSimulationStart"->()), - (sim_handle_vision_sensor,"handleVisionSensor",(sensor_handle:i64)->(i64,Vec,Vec)), - (sim_import_mesh,"importMesh",(fileformat:i64,path_and_filename:String,options:i64,identical_vertice_tolerance:f64,scaling_factor:f64)->(Vec,Vec)), - (sim_import_shape,"importShape",(fileformat:i64,path_and_filename:String,options:i64,identical_vertice_tolerance:f64,scaling_factor:f64)->i64), - (sim_init_script,"initScript",(script_handle:i64)->bool), - (sim_insert_object_into_octree,"insertObjectIntoOctree",(octree_handle:i64,object_handle:i64,options:i64),opt(color:Vec,tag:i64)->i64), - (sim_insert_object_into_point_cloud,"insertObjectIntoPointCloud",(point_cloud_handle:i64,object_handle:i64,options:i64,grid_size:f64),opt(color:Vec,duplicate_tolerance:f64)->i64), - (sim_insert_points_into_point_cloud,"insertPointsIntoPointCloud",(point_cloud_handle:i64,options:i64,points:Vec),opt(color:Vec,duplicate_tolerance:f64)->i64), - (sim_insert_voxels_into_octree,"insertVoxelsIntoOctree",(octree_handle:i64,options:i64,points:Vec),opt(color:Vec,tag:Vec)->i64), - (sim_interpolate_matrices,"interpolateMatrices",(matrix_in1:Vec,matrix_in2:Vec,interpol_factor:f64)->Vec), - (sim_interpolate_poses,"interpolatePoses",(pose_in1:Vec,pose_in2:Vec,interpol_factor:f64)->Vec), - (sim_intersect_points_with_point_cloud,"intersectPointsWithPointCloud",(point_cloud_handle:i64,options:i64,points:Vec,tolerance:f64)->i64), - (sim_is_deprecated,"isDeprecated",(func_or_const:String)->i64), - (sim_is_dynamically_enabled,"isDynamicallyEnabled",(object_handle:i64)->bool), - (sim_is_handle,"isHandle",(object_handle:i64)->bool), - (sim_launch_executable,"launchExecutable",(filename:String),opt(parameters:String,show_status:i64)->()), - (sim_load_image,"loadImage",(options:i64,filename:String)->(Vec,Vec)), - (sim_load_model,"loadModel",(filename:String)->i64), - (sim_load_scene,"loadScene",(filename:String)->()), - (sim_matrix_to_pose,"matrixToPose",(matrix:Vec)->Vec), - (sim_module_entry,"moduleEntry",(handle:i64),opt(label:String,state:i64)->i64), - (sim_move_to_config,"moveToConfig",(flags:i64,current_pos:Vec,current_vel:Vec,current_accel:Vec,max_vel:Vec,max_accel:Vec,max_jerk:Vec,target_pos:Vec,target_vel:Vec,callback:String),opt(aux_data:serde_json::Value,cyclic_joints:Vec,time_step:f64)->(Vec,Vec,Vec,f64)), - (sim_move_to_pose,"moveToPose",(flags:i64,current_pose:Vec,max_vel:Vec,max_accel:Vec,max_jerk:Vec,target_pose:Vec,callback:String),opt(aux_data:serde_json::Value,metric:Vec,time_step:f64)->(Vec,f64)), - (sim_multiply_matrices,"multiplyMatrices",(matrix_in1:Vec,matrix_in2:Vec)->Vec), - (sim_multiply_poses,"multiplyPoses",(pose_in1:Vec,pose_in2:Vec)->Vec), - (sim_multiply_vector,"multiplyVector",(matrix:Vec,in_vectors:Vec)->Vec), - (sim_pack_double_table,"packDoubleTable",(double_numbers:Vec),opt(start_double_index:i64,double_count:i64)->Vec), - (sim_pack_float_table,"packFloatTable",(float_numbers:Vec),opt(start_float_index:i64,float_count:i64)->Vec), - (sim_pack_int32_table,"packInt32Table",(int32_numbers:Vec),opt(start_int32_index:i64,int32_count:i64)->Vec), - (sim_pack_table,"packTable",(a_table:Vec),opt(scheme:i64)->Vec), - (sim_pack_u_int16_table,"packUInt16Table",(uint16_numbers:Vec),opt(start_uint16_index:i64,uint16_count:i64)->Vec), - (sim_pack_u_int32_table,"packUInt32Table",(uint32_numbers:Vec),opt(start_u_int32_index:i64,uint32_count:i64)->Vec), - (sim_pack_u_int8_table,"packUInt8Table",(uint8_numbers:Vec),opt(start_uint8_index:i64,uint8count:i64)->Vec), - (sim_pause_simulation,"pauseSimulation"->i64), - (sim_persistent_data_read,"persistentDataRead",(data_tag:String)->Vec), - (sim_persistent_data_write,"persistentDataWrite",(data_tag:String,data_value:Vec),opt(options:i64)->()), - (sim_pose_to_matrix,"poseToMatrix",(pose:Vec)->Vec), - (sim_push_user_event,"pushUserEvent",(event:String,handle:i64,uid:i64,event_data:serde_json::Value),opt(options:i64)->()), - (sim_quit_simulator,"quitSimulator"->()), - (sim_read_custom_data_block,"readCustomDataBlock",(object_handle:i64,tag_name:String)->Vec), - (sim_read_custom_data_block_ex,"readCustomDataBlockEx",(handle:i64,tag_name:String),opt(options:serde_json::Value)->()), - (sim_read_custom_data_block_tags,"readCustomDataBlockTags",(object_handle:i64)->Vec), - (sim_read_custom_table_data,"readCustomTableData",(handle:i64,tag_name:String),opt(options:serde_json::Value)->()), - (sim_read_force_sensor,"readForceSensor",(object_handle:i64)->(i64,Vec,Vec)), - (sim_read_proximity_sensor,"readProximitySensor",(sensor_handle:i64)->(i64,f64,Vec,i64,Vec)), - (sim_read_texture,"readTexture",(texture_id:i64,options:i64),opt(pos_x:i64,pos_y:i64,size_x:i64,size_y:i64)->Vec), - (sim_read_vision_sensor,"readVisionSensor",(sensor_handle:i64)->(i64,Vec,Vec)), - (sim_refresh_dialogs,"refreshDialogs",(refresh_degree:i64)->i64), - (sim_release_lock,"releaseLock"->()), - (sim_relocate_shape_frame,"relocateShapeFrame",(shape_handle:i64,pose:Vec)->i64), - (sim_remove_drawing_object,"removeDrawingObject",(drawing_object_handle:i64)->()), - (sim_remove_model,"removeModel",(object_handle:i64)->i64), - (sim_remove_objects,"removeObjects",(object_handles:Vec)->()), - (sim_remove_particle_object,"removeParticleObject",(particle_object_handle:i64)->()), - (sim_remove_points_from_point_cloud,"removePointsFromPointCloud",(point_cloud_handle:i64,options:i64,points:Vec,tolerance:f64)->i64), - (sim_remove_referenced_objects,"removeReferencedObjects",(object_handle:i64)->()), - (sim_remove_script,"removeScript",(script_handle:i64)->()), - (sim_remove_voxels_from_octree,"removeVoxelsFromOctree",(octree_handle:i64,options:i64,points:Vec)->i64), - (sim_resample_path,"resamplePath",(path:Vec,path_lengths:Vec,final_config_cnt:i64),opt(method:serde_json::Value,types:Vec)->Vec), - (sim_reset_dynamic_object,"resetDynamicObject",(object_handle:i64)->()), - (sim_reset_graph,"resetGraph",(object_handle:i64)->()), - (sim_reset_proximity_sensor,"resetProximitySensor",(object_handle:i64)->()), - (sim_reset_vision_sensor,"resetVisionSensor",(sensor_handle:i64)->()), - (sim_restore_entity_color,"restoreEntityColor",(original_color_data:Vec)->()), - (sim_rotate_around_axis,"rotateAroundAxis",(matrix_in:Vec,axis:Vec,axis_pos:Vec,angle:f64)->Vec), - (sim_ruckig_pos,"ruckigPos",(dofs:i64,base_cycle_time:f64,flags:i64,current_pos_vel_accel:Vec,max_vel_accel_jerk:Vec,selection:Vec,target_pos_vel:Vec)->i64), - (sim_ruckig_remove,"ruckigRemove",(handle:i64)->()), - (sim_ruckig_step,"ruckigStep",(handle:i64,cycle_time:f64)->(i64,Vec,f64)), - (sim_ruckig_vel,"ruckigVel",(dofs:i64,base_cycle_time:f64,flags:i64,current_pos_vel_accel:Vec,max_accel_jerk:Vec,selection:Vec,target_vel:Vec)->i64), - (sim_save_image,"saveImage",(image:Vec,resolution:Vec,options:i64,filename:String,quality:i64)->Vec), - (sim_save_model,"saveModel",(model_base_handle:i64,filename:String)->()), - (sim_save_scene,"saveScene",(filename:String)->()), - (sim_scale_object,"scaleObject",(object_handle:i64,x_scale:f64,y_scale:f64,z_scale:f64),opt(options:i64)->()), - (sim_scale_objects,"scaleObjects",(object_handles:Vec,scaling_factor:f64,scale_positions_too:bool)->()), - (sim_serial_check,"serialCheck",(port_handle:i64)->i64), - (sim_serial_close,"serialClose",(port_handle:i64)->()), - (sim_serial_open,"serialOpen",(port_string:String,baudrate:i64)->i64), - (sim_serial_read,"serialRead",(port_handle:i64,data_length_to_read:i64,blocking_operation:bool),opt(closing_string:Vec,timeout:f64)->Vec), - (sim_serial_send,"serialSend",(port_handle:i64,data:Vec)->i64), - (sim_set_array_param,"setArrayParam",(parameter:i64,array_of_values:Vec)->()), - (sim_set_auto_yield_delay,"setAutoYieldDelay",(dt:f64)->()), - (sim_set_bool_param,"setBoolParam",(parameter:i64,bool_state:bool)->()), - (sim_set_engine_bool_param,"setEngineBoolParam",(param_id:i64,object_handle:i64,bool_param:bool)->()), - (sim_set_engine_float_param,"setEngineFloatParam",(param_id:i64,object_handle:i64,float_param:f64)->()), - (sim_set_engine_int32_param,"setEngineInt32Param",(param_id:i64,object_handle:i64,int32_param:i64)->()), - (sim_set_explicit_handling,"setExplicitHandling",(object_handle:i64,explicit_handling_flags:i64)->()), - (sim_set_float_param,"setFloatParam",(parameter:i64,float_state:f64)->()), - (sim_set_float_signal,"setFloatSignal",(signal_name:String,signal_value:f64)->()), - (sim_set_graph_stream_transformation,"setGraphStreamTransformation",(graph_handle:i64,stream_id:i64,tr_type:i64),opt(mult:f64,off:f64,mov_avg_period:i64)->()), - (sim_set_graph_stream_value,"setGraphStreamValue",(graph_handle:i64,stream_id:i64,value:f64)->()), - (sim_set_int32_param,"setInt32Param",(parameter:i64,int_state:i64)->()), - (sim_set_int32_signal,"setInt32Signal",(signal_name:String,signal_value:i64)->()), - (sim_set_joint_dependency,"setJointDependency",(joint_handle:i64,master_joint_handle:i64,offset:f64,mult_coeff:f64)->()), - (sim_set_joint_interval,"setJointInterval",(object_handle:i64,cyclic:bool,interval:Vec)->()), - (sim_set_joint_mode,"setJointMode",(joint_handle:i64,joint_mode:i64,options:i64)->()), - (sim_set_joint_position,"setJointPosition",(object_handle:i64,position:f64)->()), - (sim_set_joint_target_force,"setJointTargetForce",(object_handle:i64,force_or_torque:f64),opt(signed_value:bool)->()), - (sim_set_joint_target_position,"setJointTargetPosition",(object_handle:i64,target_position:f64),opt(motion_params:Vec)->()), - (sim_set_joint_target_velocity,"setJointTargetVelocity",(object_handle:i64,target_velocity:f64),opt(motion_params:Vec)->()), - (sim_set_light_parameters,"setLightParameters",(light_handle:i64,state:i64,reserved:Vec,diffuse_part:Vec,specular_part:Vec)->()), - (sim_set_link_dummy,"setLinkDummy",(dummy_handle:i64,link_dummy_handle:i64)->()), - (sim_set_model_property,"setModelProperty",(object_handle:i64,property:i64)->()), - (sim_set_named_bool_param,"setNamedBoolParam",(name:String,value:bool)->()), - (sim_set_named_float_param,"setNamedFloatParam",(name:String,value:f64)->()), - (sim_set_named_int32_param,"setNamedInt32Param",(name:String,value:i64)->()), - (sim_set_named_string_param,"setNamedStringParam",(param_name:String,string_param:Vec)->()), - (sim_set_navigation_mode,"setNavigationMode",(navigation_mode:i64)->()), - (sim_set_object_alias,"setObjectAlias",(object_handle:i64,object_alias:String)->()), - (sim_set_object_child_pose,"setObjectChildPose",(object_handle:i64,pose:Vec)->()), - (sim_set_object_color,"setObjectColor",(object_handle:i64,index:i64,color_component:i64,rgb_data:Vec)->bool), - (sim_set_object_float_array_param,"setObjectFloatArrayParam",(object_handle:i64,parameter_id:i64,params:Vec)->()), - (sim_set_object_float_param,"setObjectFloatParam",(object_handle:i64,parameter_id:i64,parameter:f64)->()), - (sim_set_object_int32_param,"setObjectInt32Param",(object_handle:i64,parameter_id:i64,parameter:i64)->()), - (sim_set_object_matrix,"setObjectMatrix",(object_handle:i64,matrix:Vec),opt(relative_to_object_handle:i64)->()), - (sim_set_object_orientation,"setObjectOrientation",(object_handle:i64,euler_angles:Vec),opt(relative_to_object_handle:i64)->()), - (sim_set_object_parent,"setObjectParent",(object_handle:i64,parent_object_handle:i64),opt(keep_in_place:bool)->()), - (sim_set_object_pose,"setObjectPose",(object_handle:i64,pose:Vec),opt(relative_to_object_handle:i64)->()), - (sim_set_object_position,"setObjectPosition",(object_handle:i64,position:Vec),opt(relative_to_object_handle:i64)->()), - (sim_set_object_property,"setObjectProperty",(object_handle:i64,property:i64)->()), - (sim_set_object_quaternion,"setObjectQuaternion",(object_handle:i64,quaternion:Vec),opt(relative_to_object_handle:i64)->()), - (sim_set_object_sel,"setObjectSel",(object_handles:Vec)->()), - (sim_set_object_special_property,"setObjectSpecialProperty",(object_handle:i64,property:i64)->()), - (sim_set_object_string_param,"setObjectStringParam",(object_handle:i64,parameter_id:i64,parameter:Vec)->()), - (sim_set_page,"setPage",(page_index:i64)->()), - (sim_set_plugin_info,"setPluginInfo",(plugin_name:String,info_type:i64,info:String)->()), - (sim_set_point_cloud_options,"setPointCloudOptions",(point_cloud_handle:i64,max_voxel_size:f64,max_pt_cnt_per_voxel:i64,options:i64,point_size:f64)->()), - (sim_set_referenced_handles,"setReferencedHandles",(object_handle:i64,referenced_handles:Vec)->()), - (sim_set_script_int32_param,"setScriptInt32Param",(script_handle:i64,parameter_id:i64,parameter:i64)->()), - (sim_set_script_string_param,"setScriptStringParam",(script_handle:i64,parameter_id:i64,parameter:Vec)->()), - (sim_set_shape_bb,"setShapeBB",(shape_handle:i64,size:Vec)->()), - (sim_set_shape_color,"setShapeColor",(shape_handle:i64,color_name:String,color_component:i64,rgb_data:Vec)->()), - (sim_set_shape_inertia,"setShapeInertia",(shape_handle:i64,inertia_matrix:Vec,transformation_matrix:Vec)->()), - (sim_set_shape_mass,"setShapeMass",(shape_handle:i64,mass:f64)->()), - (sim_set_shape_material,"setShapeMaterial",(shape_handle:i64,material_id_or_shape_handle:i64)->()), - (sim_set_shape_texture,"setShapeTexture",(shape_handle:i64,texture_id:i64,mapping_mode:i64,options:i64,uv_scaling:Vec),opt(position:Vec,orientation:Vec)->()), - (sim_set_stepping,"setStepping",(enabled:bool)->i64), - (sim_set_string_param,"setStringParam",(parameter:i64,string_state:String)->()), - (sim_set_string_signal,"setStringSignal",(signal_name:String,signal_value:Vec)->()), - (sim_set_vision_sensor_img,"setVisionSensorImg",(sensor_handle:i64,image:Vec),opt(options:i64,pos:Vec,size:Vec)->()), - (sim_start_simulation,"startSimulation"->i64), - (sim_step,"step"->()), - (sim_stop_simulation,"stopSimulation"->i64), - (sim_subtract_object_from_octree,"subtractObjectFromOctree",(octree_handle:i64,object_handle:i64,options:i64)->i64), - (sim_subtract_object_from_point_cloud,"subtractObjectFromPointCloud",(point_cloud_handle:i64,object_handle:i64,options:i64,tolerance:f64)->i64), - (sim_text_editor_close,"textEditorClose",(handle:i64)->(String,Vec,Vec)), - (sim_text_editor_get_info,"textEditorGetInfo",(handle:i64)->(String,Vec,Vec,bool)), - (sim_text_editor_open,"textEditorOpen",(init_text:String,properties:String)->i64), - (sim_text_editor_show,"textEditorShow",(handle:i64,show_state:bool)->()), - (sim_transform_buffer,"transformBuffer",(in_buffer:Vec,in_format:i64,multiplier:f64,offset:f64,out_format:i64)->Vec), - (sim_transform_image,"transformImage",(image:Vec,resolution:Vec,options:i64)->()), - (sim_ungroup_shape,"ungroupShape",(shape_handle:i64)->Vec), - (sim_unpack_double_table,"unpackDoubleTable",(data:Vec),opt(start_double_index:i64,double_count:i64,additional_byte_offset:i64)->Vec), - (sim_unpack_float_table,"unpackFloatTable",(data:Vec),opt(start_float_index:i64,float_count:i64,additional_byte_offset:i64)->Vec), - (sim_unpack_int32_table,"unpackInt32Table",(data:Vec),opt(start_int32_index:i64,int32_count:i64,additional_byte_offset:i64)->Vec), - (sim_unpack_table,"unpackTable",(buffer:Vec)->serde_json::Value), - (sim_unpack_u_int16_table,"unpackUInt16Table",(data:Vec),opt(start_uint16_index:i64,uint16_count:i64,additional_byte_offset:i64)->Vec), - (sim_unpack_u_int32_table,"unpackUInt32Table",(data:Vec),opt(start_uint32_index:i64,uint32_count:i64,additional_byte_offset:i64)->Vec), - (sim_unpack_u_int8_table,"unpackUInt8Table",(data:Vec),opt(start_uint8_index:i64,uint8count:i64)->Vec), - (sim_visit_tree,"visitTree",(root_handle:i64,visitor_func:String),opt(options:serde_json::Value)->()), - (sim_wait,"wait",(dt:f64),opt(simulation_time:bool)->f64), - (sim_wait_for_signal,"waitForSignal",(sig_name:String)->serde_json::Value), - (sim_write_custom_data_block,"writeCustomDataBlock",(object_handle:i64,tag_name:String,data:Vec)->()), - (sim_write_custom_data_block_ex,"writeCustomDataBlockEx",(handle:i64,tag_name:String,data:String),opt(options:serde_json::Value)->()), - (sim_write_custom_table_data,"writeCustomTableData",(handle:i64,tag_name:String,the_table:serde_json::Value),opt(options:serde_json::Value)->()), - (sim_write_texture,"writeTexture",(texture_id:i64,options:i64,texture_data:Vec),opt(pos_x:i64,pos_y:i64,size_x:i64,size_y:i64,interpol:f64)->()), - (sim_yaw_pitch_roll_to_alpha_beta_gamma,"yawPitchRollToAlphaBetaGamma",(yaw_angle:f64,pitch_angle:f64,roll_angle:f64)->(f64,f64,f64)), - (sim_yield,"yield"->()) - } +pub trait Sim : RemoteApiClientInterface { + requests!{ +"sim", +(sim_set_joint_max_force,"setJointMaxForce",(object_handle:i64,force_or_torque:f64)->()), +(sim_get_joint_max_force,"getJointMaxForce",(joint_handle:i64)->f64), +(sim_create_pure_shape,"createPureShape",(primitive_type:i64,options:i64,sizes:Vec,mass:f64),opt(precision:Vec)->i64), +(sim_remove_object,"removeObject",(object_handle:i64)->()), +(sim_get_vision_sensor_depth_buffer,"getVisionSensorDepthBuffer",(sensor_handle:i64),opt(pos:Vec,size:Vec)->(Vec,Vec)), +(sim_get_vision_sensor_char_image,"getVisionSensorCharImage",(sensor_handle:i64),opt(pos:Vec,size:Vec)->(Vec,Vec)), +(sim_set_vision_sensor_char_image,"setVisionSensorCharImage",(sensor_handle:i64,image:Vec)->()), +(sim_get_object_selection,"getObjectSelection"->Vec), +(sim_set_object_selection,"setObjectSelection",(object_handles:Vec)->()), +(sim_get_string_signal,"getStringSignal",(signal_name:String)->Option>), +(sim_get_int32_signal,"getInt32Signal",(signal_name:String)->Option), +(sim_get_float_signal,"getFloatSignal",(signal_name:String)->Option), +(sim_acquire_lock,"acquireLock"->()), +(sim_add_drawing_object,"addDrawingObject",(object_type:i64,size:f64,duplicate_tolerance:f64,parent_object_handle:i64,max_item_count:i64),opt(color:Vec)->i64), +(sim_add_drawing_object_item,"addDrawingObjectItem",(drawing_object_handle:i64,item_data:Vec)->i64), +(sim_add_force,"addForce",(shape_handle:i64,position:Vec,force:Vec)->()), +(sim_add_force_and_torque,"addForceAndTorque",(shape_handle:i64),opt(force:Vec,torque:Vec)->()), +(sim_add_graph_curve,"addGraphCurve",(graph_handle:i64,curve_name:String,dim:i64,stream_ids:Vec,default_values:Vec,unit_str:String),opt(options:i64,color:Vec,curve_width:i64)->i64), +(sim_add_graph_stream,"addGraphStream",(graph_handle:i64,stream_name:String,unit:String),opt(options:i64,color:Vec,cyclic_range:f64)->i64), +(sim_add_item_to_collection,"addItemToCollection",(collection_handle:i64,what:i64,object_handle:i64,options:i64)->()), +(sim_add_log,"addLog",(verbosity_level:i64,log_message:String)->()), +(sim_add_particle_object,"addParticleObject",(object_type:i64,size:f64,density:f64,params:Vec,life_time:f64,max_item_count:i64),opt(color:Vec)->i64), +(sim_add_particle_object_item,"addParticleObjectItem",(object_handle:i64,item_data:Vec)->()), +(sim_add_referenced_handle,"addReferencedHandle",(object_handle:i64,referenced_handle:i64)->()), +(sim_add_script,"addScript",(script_type:i64)->i64), +(sim_adjust_view,"adjustView",(view_handle_or_index:i64,associated_viewable_object_handle:i64,options:i64),opt(view_label:String)->i64), +(sim_align_shape_bb,"alignShapeBB",(shape_handle:i64,pose:Vec)->i64), +(sim_alpha_beta_gamma_to_yaw_pitch_roll,"alphaBetaGammaToYawPitchRoll",(alpha_angle:f64,beta_angle:f64,gamma_angle:f64)->(f64,f64,f64)), +(sim_announce_scene_content_change,"announceSceneContentChange"->i64), +(sim_associate_script_with_object,"associateScriptWithObject",(script_handle:i64,object_handle:i64)->()), +(sim_auxiliary_console_close,"auxiliaryConsoleClose",(console_handle:i64)->i64), +(sim_auxiliary_console_open,"auxiliaryConsoleOpen",(title:String,max_lines:i64,mode:i64),opt(position:Vec,size:Vec,text_color:Vec,background_color:Vec)->i64), +(sim_auxiliary_console_print,"auxiliaryConsolePrint",(console_handle:i64,text:String)->i64), +(sim_auxiliary_console_show,"auxiliaryConsoleShow",(console_handle:i64,show_state:bool)->i64), +(sim_broadcast_msg,"broadcastMsg",(message:serde_json::Value),opt(options:i64)->()), +(sim_build_identity_matrix,"buildIdentityMatrix"->Vec), +(sim_build_matrix,"buildMatrix",(position:Vec,euler_angles:Vec)->Vec), +(sim_build_matrix_q,"buildMatrixQ",(position:Vec,quaternion:Vec)->Vec), +(sim_build_pose,"buildPose",(position:Vec,euler_angles_or_axis:Vec),opt(mode:i64,axis2:Vec)->Vec), +(sim_call_script_function,"callScriptFunction",(function_name:String,script_handle:i64),opt(in_arg:serde_json::Value)->serde_json::Value), +(sim_camera_fit_to_view,"cameraFitToView",(view_handle_or_index:i64),opt(object_handles:Vec,options:i64,scaling:f64)->i64), +(sim_change_entity_color,"changeEntityColor",(entity_handle:i64,new_color:Vec),opt(color_component:i64)->Vec), +(sim_check_collision,"checkCollision",(entity1_handle:i64,entity2_handle:i64)->(i64,Vec)), +(sim_check_collision_ex,"checkCollisionEx",(entity1_handle:i64,entity2_handle:i64)->(i64,Vec)), +(sim_check_distance,"checkDistance",(entity1_handle:i64,entity2_handle:i64),opt(threshold:f64)->(i64,Vec,Vec)), +(sim_check_octree_point_occupancy,"checkOctreePointOccupancy",(octree_handle:i64,options:i64,points:Vec)->(i64,i64,i64,i64)), +(sim_check_proximity_sensor,"checkProximitySensor",(sensor_handle:i64,entity_handle:i64)->(i64,f64,Vec,i64,Vec)), +(sim_check_proximity_sensor_ex,"checkProximitySensorEx",(sensor_handle:i64,entity_handle:i64,mode:i64,threshold:f64,max_angle:f64)->(i64,f64,Vec,i64,Vec)), +(sim_check_proximity_sensor_ex2,"checkProximitySensorEx2",(sensor_handle:i64,vertices:Vec,item_type:i64,item_count:i64,mode:i64,threshold:f64,max_angle:f64)->(i64,f64,Vec,Vec)), +(sim_check_vision_sensor,"checkVisionSensor",(sensor_handle:i64,entity_handle:i64)->(i64,Vec,Vec)), +(sim_check_vision_sensor_ex,"checkVisionSensorEx",(sensor_handle:i64,entity_handle:i64,return_image:bool)->Vec), +(sim_clear_float_signal,"clearFloatSignal",(signal_name:String)->()), +(sim_clear_int32_signal,"clearInt32Signal",(signal_name:String)->()), +(sim_clear_string_signal,"clearStringSignal",(signal_name:String)->()), +(sim_close_scene,"closeScene"->i64), +(sim_combine_rgb_images,"combineRgbImages",(img1:Vec,img1_res:Vec,img2:Vec,img2_res:Vec,operation:i64)->Vec), +(sim_compute_mass_and_inertia,"computeMassAndInertia",(shape_handle:i64,density:f64)->i64), +(sim_convex_decompose,"convexDecompose",(shape_handle:i64,options:i64,int_params:Vec,float_params:Vec)->i64), +(sim_copy_paste_objects,"copyPasteObjects",(object_handles:Vec),opt(options:i64)->Vec), +(sim_copy_table,"copyTable",(original:Vec)->Vec), +(sim_create_collection,"createCollection",opt(options:i64)->i64), +(sim_create_dummy,"createDummy",(size:f64)->i64), +(sim_create_force_sensor,"createForceSensor",(options:i64,int_params:Vec,float_params:Vec)->i64), +(sim_create_heightfield_shape,"createHeightfieldShape",(options:i64,shading_angle:f64,x_point_count:i64,y_point_count:i64,x_size:f64,heights:Vec)->i64), +(sim_create_joint,"createJoint",(joint_type:i64,joint_mode:i64,options:i64),opt(sizes:Vec)->i64), +(sim_create_octree,"createOctree",(voxel_size:f64,options:i64,point_size:f64)->i64), +(sim_create_path,"createPath",(ctrl_pts:Vec),opt(options:i64,subdiv:i64,smoothness:f64,orientation_mode:i64,up_vector:Vec)->i64), +(sim_create_point_cloud,"createPointCloud",(max_voxel_size:f64,max_pt_cnt_per_voxel:i64,options:i64,point_size:f64)->i64), +(sim_create_primitive_shape,"createPrimitiveShape",(primitive_type:i64,sizes:Vec),opt(options:i64)->i64), +(sim_create_proximity_sensor,"createProximitySensor",(sensor_type:i64,sub_type:i64,options:i64,int_params:Vec,float_params:Vec)->i64), +(sim_create_shape,"createShape",(options:i64,shading_angle:f64,vertices:Vec,indices:Vec,normals:Vec,texture_coordinates:Vec,texture:Vec,texture_resolution:Vec)->i64), +(sim_create_texture,"createTexture",(file_name:String,options:i64),opt(plane_sizes:Vec,scaling_uv:Vec,xy_g:Vec,fixed_resolution:i64,resolution:Vec)->(i64,i64,Vec)), +(sim_create_vision_sensor,"createVisionSensor",(options:i64,int_params:Vec,float_params:Vec)->i64), +(sim_destroy_collection,"destroyCollection",(collection_handle:i64)->()), +(sim_destroy_graph_curve,"destroyGraphCurve",(graph_handle:i64,curve_id:i64)->()), +(sim_duplicate_graph_curve_to_static,"duplicateGraphCurveToStatic",(graph_handle:i64,curve_id:i64),opt(curve_name:String)->i64), +(sim_execute_script_string,"executeScriptString",(string_to_execute:String,script_handle:i64)->(i64,serde_json::Value)), +(sim_export_mesh,"exportMesh",(fileformat:i64,path_and_filename:String,options:i64,scaling_factor:f64,vertices:Vec,indices:Vec)->()), +(sim_floating_view_add,"floatingViewAdd",(pos_x:f64,pos_y:f64,size_x:f64,size_y:f64,options:i64)->i64), +(sim_floating_view_remove,"floatingViewRemove",(floating_view_handle:i64)->i64), +(sim_generate_shape_from_path,"generateShapeFromPath",(path:Vec,section:Vec),opt(options:i64,up_vector:Vec)->i64), +(sim_generate_text_shape,"generateTextShape",(txt:String),opt(color:Vec,height:f64,centered:bool,alphabet_location:String)->i64), +(sim_generate_time_optimal_trajectory,"generateTimeOptimalTrajectory",(path:Vec,path_lengths:Vec,min_max_vel:Vec,min_max_accel:Vec),opt(traj_pt_samples:i64,boundary_condition:String,timeout:f64)->(Vec,Vec)), +(sim_get_alternate_configs,"getAlternateConfigs",(joint_handles:Vec,input_config:Vec),opt(tip_handle:i64,low_limits:Vec,ranges:Vec)->Vec), +(sim_get_api_func,"getApiFunc",(script_handle:i64,api_word:String)->Vec), +(sim_get_api_info,"getApiInfo",(script_handle:i64,api_word:String)->String), +(sim_get_array_param,"getArrayParam",(parameter:i64)->Vec), +(sim_get_auto_yield_delay,"getAutoYieldDelay"->f64), +(sim_get_bool_param,"getBoolParam",(parameter:i64)->bool), +(sim_get_closest_pos_on_path,"getClosestPosOnPath",(path:Vec,path_lengths:Vec,abs_pt:Vec)->f64), +(sim_get_collection_objects,"getCollectionObjects",(collection_handle:i64)->Vec), +(sim_get_config_distance,"getConfigDistance",(config_a:Vec,config_b:Vec),opt(metric:Vec,types:Vec)->f64), +(sim_get_contact_info,"getContactInfo",(dynamic_pass:i64,object_handle:i64,index:i64)->(Vec,Vec,Vec,Vec)), +(sim_get_decimated_mesh,"getDecimatedMesh",(vertices_in:Vec,indices_in:Vec,decimation_percentage:f64)->(Vec,Vec)), +(sim_get_engine_bool_param,"getEngineBoolParam",(param_id:i64,object_handle:i64)->bool), +(sim_get_engine_float_param,"getEngineFloatParam",(param_id:i64,object_handle:i64)->f64), +(sim_get_engine_int32_param,"getEngineInt32Param",(param_id:i64,object_handle:i64)->i64), +(sim_get_euler_angles_from_matrix,"getEulerAnglesFromMatrix",(matrix:Vec)->Vec), +(sim_get_explicit_handling,"getExplicitHandling",(object_handle:i64)->i64), +(sim_get_extension_string,"getExtensionString",(object_handle:i64,index:i64),opt(key:String)->String), +(sim_get_float_param,"getFloatParam",(parameter:i64)->f64), +(sim_get_genesis_events,"getGenesisEvents"->Vec), +(sim_get_graph_curve,"getGraphCurve",(graph_handle:i64,graph_type:i64,curve_index:i64)->(String,i64,Vec,Vec,Vec,Vec,i64,i64)), +(sim_get_graph_info,"getGraphInfo",(graph_handle:i64)->(i64,Vec,Vec,i64)), +(sim_get_int32_param,"getInt32Param",(parameter:i64)->i64), +(sim_get_is_real_time_simulation,"getIsRealTimeSimulation"->i64), +(sim_get_joint_dependency,"getJointDependency",(joint_handle:i64)->(i64,f64,f64)), +(sim_get_joint_force,"getJointForce",(joint_handle:i64)->f64), +(sim_get_joint_interval,"getJointInterval",(object_handle:i64)->(bool,Vec)), +(sim_get_joint_mode,"getJointMode",(joint_handle:i64)->(i64,i64)), +(sim_get_joint_position,"getJointPosition",(object_handle:i64)->f64), +(sim_get_joint_target_force,"getJointTargetForce",(joint_handle:i64)->f64), +(sim_get_joint_target_position,"getJointTargetPosition",(object_handle:i64)->f64), +(sim_get_joint_target_velocity,"getJointTargetVelocity",(object_handle:i64)->f64), +(sim_get_joint_type,"getJointType",(object_handle:i64)->i64), +(sim_get_joint_velocity,"getJointVelocity",(joint_handle:i64)->f64), +(sim_get_last_info,"getLastInfo"->String), +(sim_get_light_parameters,"getLightParameters",(light_handle:i64)->(i64,Vec,Vec,Vec)), +(sim_get_link_dummy,"getLinkDummy",(dummy_handle:i64)->i64), +(sim_get_matching_persistent_data_tags,"getMatchingPersistentDataTags",(pattern:String)->Vec), +(sim_get_matrix_inverse,"getMatrixInverse",(matrix:Vec)->Vec), +(sim_get_model_property,"getModelProperty",(object_handle:i64)->i64), +(sim_get_named_bool_param,"getNamedBoolParam",(name:String)->bool), +(sim_get_named_float_param,"getNamedFloatParam",(name:String)->f64), +(sim_get_named_int32_param,"getNamedInt32Param",(name:String)->i64), +(sim_get_named_string_param,"getNamedStringParam",(param_name:String)->Vec), +(sim_get_navigation_mode,"getNavigationMode"->i64), +(sim_get_object,"getObject",(path:String),opt(options:serde_json::Value)->i64), +(sim_get_object_alias,"getObjectAlias",(object_handle:i64),opt(options:i64)->String), +(sim_get_object_alias_relative,"getObjectAliasRelative",(handle:i64,base_handle:i64),opt(options:i64)->String), +(sim_get_object_child,"getObjectChild",(object_handle:i64,index:i64)->i64), +(sim_get_object_child_pose,"getObjectChildPose",(object_handle:i64)->Vec), +(sim_get_object_color,"getObjectColor",(object_handle:i64,index:i64,color_component:i64)->Vec), +(sim_get_object_float_array_param,"getObjectFloatArrayParam",(object_handle:i64,parameter_id:i64)->Vec), +(sim_get_object_float_param,"getObjectFloatParam",(object_handle:i64,parameter_id:i64)->f64), +(sim_get_object_from_uid,"getObjectFromUid",(uid:i64),opt(options:serde_json::Value)->()), +(sim_get_object_int32_param,"getObjectInt32Param",(object_handle:i64,parameter_id:i64)->i64), +(sim_get_object_matrix,"getObjectMatrix",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(sim_get_object_orientation,"getObjectOrientation",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(sim_get_object_parent,"getObjectParent",(object_handle:i64)->i64), +(sim_get_object_pose,"getObjectPose",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(sim_get_object_position,"getObjectPosition",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(sim_get_object_property,"getObjectProperty",(object_handle:i64)->i64), +(sim_get_object_quaternion,"getObjectQuaternion",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(sim_get_object_sel,"getObjectSel"->Vec), +(sim_get_object_size_factor,"getObjectSizeFactor",(object_handle:i64)->f64), +(sim_get_object_special_property,"getObjectSpecialProperty",(object_handle:i64)->i64), +(sim_get_object_string_param,"getObjectStringParam",(object_handle:i64,parameter_id:i64)->Vec), +(sim_get_object_type,"getObjectType",(object_handle:i64)->i64), +(sim_get_object_uid,"getObjectUid",(object_handle:i64)->i64), +(sim_get_object_velocity,"getObjectVelocity",(object_handle:i64)->(Vec,Vec)), +(sim_get_objects,"getObjects",(index:i64,object_type:i64)->i64), +(sim_get_objects_in_tree,"getObjectsInTree",(tree_base_handle:i64),opt(object_type:i64,options:i64)->Vec), +(sim_get_octree_voxels,"getOctreeVoxels",(octree_handle:i64)->Vec), +(sim_get_page,"getPage"->i64), +(sim_get_path_interpolated_config,"getPathInterpolatedConfig",(path:Vec,path_lengths:Vec,t:f64),opt(method:serde_json::Value,types:Vec)->Vec), +(sim_get_path_lengths,"getPathLengths",(path:Vec,dof:i64),opt(dist_callback:String)->(Vec,f64)), +(sim_get_persistent_data_tags,"getPersistentDataTags"->Vec), +(sim_get_plugin_info,"getPluginInfo",(plugin_name:String,info_type:i64)->String), +(sim_get_plugin_name,"getPluginName",(index:i64)->String), +(sim_get_point_cloud_options,"getPointCloudOptions",(point_cloud_handle:i64)->(f64,i64,i64,f64)), +(sim_get_point_cloud_points,"getPointCloudPoints",(point_cloud_handle:i64)->Vec), +(sim_get_pose_inverse,"getPoseInverse",(pose:Vec)->Vec), +(sim_get_q_hull,"getQHull",(vertices_in:Vec)->(Vec,Vec)), +(sim_get_quaternion_from_matrix,"getQuaternionFromMatrix",(matrix:Vec)->Vec), +(sim_get_random,"getRandom",opt(seed:i64)->f64), +(sim_get_referenced_handles,"getReferencedHandles",(object_handle:i64)->Vec), +(sim_get_rotation_axis,"getRotationAxis",(matrix_start:Vec,matrix_goal:Vec)->(Vec,f64)), +(sim_get_scaled_image,"getScaledImage",(image_in:Vec,resolution_in:Vec,desired_resolution_out:Vec,options:i64)->(Vec,Vec)), +(sim_get_script,"getScript",(script_type:i64),opt(object_handle:i64,script_name:String)->i64), +(sim_get_script_functions,"getScriptFunctions",(script_handle:i64)->serde_json::Value), +(sim_get_script_int32_param,"getScriptInt32Param",(script_handle:i64,parameter_id:i64)->i64), +(sim_get_script_string_param,"getScriptStringParam",(script_handle:i64,parameter_id:i64)->Vec), +(sim_get_setting_bool,"getSettingBool",(key:String)->bool), +(sim_get_setting_float,"getSettingFloat",(key:String)->f64), +(sim_get_setting_int32,"getSettingInt32",(key:String)->i64), +(sim_get_setting_string,"getSettingString",(key:String)->String), +(sim_get_shape_bb,"getShapeBB",(shape_handle:i64)->Vec), +(sim_get_shape_color,"getShapeColor",(shape_handle:i64,color_name:String,color_component:i64)->(i64,Vec)), +(sim_get_shape_geom_info,"getShapeGeomInfo",(shape_handle:i64)->(i64,i64,Vec)), +(sim_get_shape_inertia,"getShapeInertia",(shape_handle:i64)->(Vec,Vec)), +(sim_get_shape_mass_and_inertia,"getShapeMassAndInertia",(shape_handle:i64)->f64), +(sim_get_shape_mesh,"getShapeMesh",(shape_handle:i64)->(Vec,Vec,Vec)), +(sim_get_shape_texture_id,"getShapeTextureId",(shape_handle:i64)->i64), +(sim_get_shape_viz,"getShapeViz",(shape_handle:i64,item_index:i64)->serde_json::Value), +(sim_get_signal_name,"getSignalName",(signal_index:i64,signal_type:i64)->String), +(sim_get_simulation_state,"getSimulationState"->i64), +(sim_get_simulation_stopping,"getSimulationStopping"->bool), +(sim_get_simulation_time,"getSimulationTime"->f64), +(sim_get_simulation_time_step,"getSimulationTimeStep"->f64), +(sim_get_simulator_message,"getSimulatorMessage"->(i64,Vec,Vec)), +(sim_get_stack_traceback,"getStackTraceback",opt(script_handle:i64)->String), +(sim_get_string_param,"getStringParam",(parameter:i64)->String), +(sim_get_system_time,"getSystemTime"->f64), +(sim_get_texture_id,"getTextureId",(texture_name:String)->(i64,Vec)), +(sim_get_thread_id,"getThreadId"->i64), +(sim_get_user_variables,"getUserVariables"->Vec), +(sim_get_velocity,"getVelocity",(shape_handle:i64)->(Vec,Vec)), +(sim_get_vision_sensor_depth,"getVisionSensorDepth",(sensor_handle:i64),opt(options:i64,pos:Vec,size:Vec)->(Vec,Vec)), +(sim_get_vision_sensor_img,"getVisionSensorImg",(sensor_handle:i64),opt(options:i64,rgba_cut_off:f64,pos:Vec,size:Vec)->(Vec,Vec)), +(sim_get_vision_sensor_res,"getVisionSensorRes",(sensor_handle:i64)->()), +(sim_group_shapes,"groupShapes",(shape_handles:Vec),opt(merge:bool)->i64), +(sim_handle_add_on_scripts,"handleAddOnScripts",(call_type:i64)->i64), +(sim_handle_child_scripts,"handleChildScripts",(call_type:i64)->i64), +(sim_handle_dynamics,"handleDynamics",(delta_time:f64)->i64), +(sim_handle_embedded_scripts,"handleEmbeddedScripts",(call_type:i64)->i64), +(sim_handle_graph,"handleGraph",(object_handle:i64,simulation_time:f64)->()), +(sim_handle_joint_motion,"handleJointMotion"->()), +(sim_handle_proximity_sensor,"handleProximitySensor",(sensor_handle:i64)->(i64,f64,Vec,i64,Vec)), +(sim_handle_sandbox_script,"handleSandboxScript",(call_type:i64)->()), +(sim_handle_sensing_start,"handleSensingStart"->()), +(sim_handle_simulation_start,"handleSimulationStart"->()), +(sim_handle_vision_sensor,"handleVisionSensor",(sensor_handle:i64)->(i64,Vec,Vec)), +(sim_import_mesh,"importMesh",(fileformat:i64,path_and_filename:String,options:i64,identical_vertice_tolerance:f64,scaling_factor:f64)->(Vec,Vec)), +(sim_import_shape,"importShape",(fileformat:i64,path_and_filename:String,options:i64,identical_vertice_tolerance:f64,scaling_factor:f64)->i64), +(sim_init_script,"initScript",(script_handle:i64)->bool), +(sim_insert_object_into_octree,"insertObjectIntoOctree",(octree_handle:i64,object_handle:i64,options:i64),opt(color:Vec,tag:i64)->i64), +(sim_insert_object_into_point_cloud,"insertObjectIntoPointCloud",(point_cloud_handle:i64,object_handle:i64,options:i64,grid_size:f64),opt(color:Vec,duplicate_tolerance:f64)->i64), +(sim_insert_points_into_point_cloud,"insertPointsIntoPointCloud",(point_cloud_handle:i64,options:i64,points:Vec),opt(color:Vec,duplicate_tolerance:f64)->i64), +(sim_insert_voxels_into_octree,"insertVoxelsIntoOctree",(octree_handle:i64,options:i64,points:Vec),opt(color:Vec,tag:Vec)->i64), +(sim_interpolate_matrices,"interpolateMatrices",(matrix_in1:Vec,matrix_in2:Vec,interpol_factor:f64)->Vec), +(sim_interpolate_poses,"interpolatePoses",(pose_in1:Vec,pose_in2:Vec,interpol_factor:f64)->Vec), +(sim_intersect_points_with_point_cloud,"intersectPointsWithPointCloud",(point_cloud_handle:i64,options:i64,points:Vec,tolerance:f64)->i64), +(sim_is_deprecated,"isDeprecated",(func_or_const:String)->i64), +(sim_is_dynamically_enabled,"isDynamicallyEnabled",(object_handle:i64)->bool), +(sim_is_handle,"isHandle",(object_handle:i64)->bool), +(sim_launch_executable,"launchExecutable",(filename:String),opt(parameters:String,show_status:i64)->()), +(sim_load_image,"loadImage",(options:i64,filename:String)->(Vec,Vec)), +(sim_load_model,"loadModel",(filename:String)->i64), +(sim_load_scene,"loadScene",(filename:String)->()), +(sim_matrix_to_pose,"matrixToPose",(matrix:Vec)->Vec), +(sim_module_entry,"moduleEntry",(handle:i64),opt(label:String,state:i64)->i64), +(sim_move_to_config,"moveToConfig",(flags:i64,current_pos:Vec,current_vel:Vec,current_accel:Vec,max_vel:Vec,max_accel:Vec,max_jerk:Vec,target_pos:Vec,target_vel:Vec,callback:String),opt(aux_data:serde_json::Value,cyclic_joints:Vec,time_step:f64)->(Vec,Vec,Vec,f64)), +(sim_move_to_pose,"moveToPose",(flags:i64,current_pose:Vec,max_vel:Vec,max_accel:Vec,max_jerk:Vec,target_pose:Vec,callback:String),opt(aux_data:serde_json::Value,metric:Vec,time_step:f64)->(Vec,f64)), +(sim_multiply_matrices,"multiplyMatrices",(matrix_in1:Vec,matrix_in2:Vec)->Vec), +(sim_multiply_poses,"multiplyPoses",(pose_in1:Vec,pose_in2:Vec)->Vec), +(sim_multiply_vector,"multiplyVector",(matrix:Vec,in_vectors:Vec)->Vec), +(sim_pack_double_table,"packDoubleTable",(double_numbers:Vec),opt(start_double_index:i64,double_count:i64)->Vec), +(sim_pack_float_table,"packFloatTable",(float_numbers:Vec),opt(start_float_index:i64,float_count:i64)->Vec), +(sim_pack_int32_table,"packInt32Table",(int32_numbers:Vec),opt(start_int32_index:i64,int32_count:i64)->Vec), +(sim_pack_table,"packTable",(a_table:Vec),opt(scheme:i64)->Vec), +(sim_pack_u_int16_table,"packUInt16Table",(uint16_numbers:Vec),opt(start_uint16_index:i64,uint16_count:i64)->Vec), +(sim_pack_u_int32_table,"packUInt32Table",(uint32_numbers:Vec),opt(start_u_int32_index:i64,uint32_count:i64)->Vec), +(sim_pack_u_int8_table,"packUInt8Table",(uint8_numbers:Vec),opt(start_uint8_index:i64,uint8count:i64)->Vec), +(sim_pause_simulation,"pauseSimulation"->i64), +(sim_persistent_data_read,"persistentDataRead",(data_tag:String)->Vec), +(sim_persistent_data_write,"persistentDataWrite",(data_tag:String,data_value:Vec),opt(options:i64)->()), +(sim_pose_to_matrix,"poseToMatrix",(pose:Vec)->Vec), +(sim_push_user_event,"pushUserEvent",(event:String,handle:i64,uid:i64,event_data:serde_json::Value),opt(options:i64)->()), +(sim_quit_simulator,"quitSimulator"->()), +(sim_read_custom_data_block,"readCustomDataBlock",(object_handle:i64,tag_name:String)->Vec), +(sim_read_custom_data_block_ex,"readCustomDataBlockEx",(handle:i64,tag_name:String),opt(options:serde_json::Value)->()), +(sim_read_custom_data_block_tags,"readCustomDataBlockTags",(object_handle:i64)->Vec), +(sim_read_custom_table_data,"readCustomTableData",(handle:i64,tag_name:String),opt(options:serde_json::Value)->()), +(sim_read_force_sensor,"readForceSensor",(object_handle:i64)->(i64,Vec,Vec)), +(sim_read_proximity_sensor,"readProximitySensor",(sensor_handle:i64)->(i64,f64,Vec,i64,Vec)), +(sim_read_texture,"readTexture",(texture_id:i64,options:i64),opt(pos_x:i64,pos_y:i64,size_x:i64,size_y:i64)->Vec), +(sim_read_vision_sensor,"readVisionSensor",(sensor_handle:i64)->(i64,Vec,Vec)), +(sim_refresh_dialogs,"refreshDialogs",(refresh_degree:i64)->i64), +(sim_release_lock,"releaseLock"->()), +(sim_relocate_shape_frame,"relocateShapeFrame",(shape_handle:i64,pose:Vec)->i64), +(sim_remove_drawing_object,"removeDrawingObject",(drawing_object_handle:i64)->()), +(sim_remove_model,"removeModel",(object_handle:i64)->i64), +(sim_remove_objects,"removeObjects",(object_handles:Vec)->()), +(sim_remove_particle_object,"removeParticleObject",(particle_object_handle:i64)->()), +(sim_remove_points_from_point_cloud,"removePointsFromPointCloud",(point_cloud_handle:i64,options:i64,points:Vec,tolerance:f64)->i64), +(sim_remove_referenced_objects,"removeReferencedObjects",(object_handle:i64)->()), +(sim_remove_script,"removeScript",(script_handle:i64)->()), +(sim_remove_voxels_from_octree,"removeVoxelsFromOctree",(octree_handle:i64,options:i64,points:Vec)->i64), +(sim_resample_path,"resamplePath",(path:Vec,path_lengths:Vec,final_config_cnt:i64),opt(method:serde_json::Value,types:Vec)->Vec), +(sim_reset_dynamic_object,"resetDynamicObject",(object_handle:i64)->()), +(sim_reset_graph,"resetGraph",(object_handle:i64)->()), +(sim_reset_proximity_sensor,"resetProximitySensor",(object_handle:i64)->()), +(sim_reset_vision_sensor,"resetVisionSensor",(sensor_handle:i64)->()), +(sim_restore_entity_color,"restoreEntityColor",(original_color_data:Vec)->()), +(sim_rotate_around_axis,"rotateAroundAxis",(matrix_in:Vec,axis:Vec,axis_pos:Vec,angle:f64)->Vec), +(sim_ruckig_pos,"ruckigPos",(dofs:i64,base_cycle_time:f64,flags:i64,current_pos_vel_accel:Vec,max_vel_accel_jerk:Vec,selection:Vec,target_pos_vel:Vec)->i64), +(sim_ruckig_remove,"ruckigRemove",(handle:i64)->()), +(sim_ruckig_step,"ruckigStep",(handle:i64,cycle_time:f64)->(i64,Vec,f64)), +(sim_ruckig_vel,"ruckigVel",(dofs:i64,base_cycle_time:f64,flags:i64,current_pos_vel_accel:Vec,max_accel_jerk:Vec,selection:Vec,target_vel:Vec)->i64), +(sim_save_image,"saveImage",(image:Vec,resolution:Vec,options:i64,filename:String,quality:i64)->Vec), +(sim_save_model,"saveModel",(model_base_handle:i64,filename:String)->()), +(sim_save_scene,"saveScene",(filename:String)->()), +(sim_scale_object,"scaleObject",(object_handle:i64,x_scale:f64,y_scale:f64,z_scale:f64),opt(options:i64)->()), +(sim_scale_objects,"scaleObjects",(object_handles:Vec,scaling_factor:f64,scale_positions_too:bool)->()), +(sim_serial_check,"serialCheck",(port_handle:i64)->i64), +(sim_serial_close,"serialClose",(port_handle:i64)->()), +(sim_serial_open,"serialOpen",(port_string:String,baudrate:i64)->i64), +(sim_serial_read,"serialRead",(port_handle:i64,data_length_to_read:i64,blocking_operation:bool),opt(closing_string:Vec,timeout:f64)->Vec), +(sim_serial_send,"serialSend",(port_handle:i64,data:Vec)->i64), +(sim_set_array_param,"setArrayParam",(parameter:i64,array_of_values:Vec)->()), +(sim_set_auto_yield_delay,"setAutoYieldDelay",(dt:f64)->()), +(sim_set_bool_param,"setBoolParam",(parameter:i64,bool_state:bool)->()), +(sim_set_engine_bool_param,"setEngineBoolParam",(param_id:i64,object_handle:i64,bool_param:bool)->()), +(sim_set_engine_float_param,"setEngineFloatParam",(param_id:i64,object_handle:i64,float_param:f64)->()), +(sim_set_engine_int32_param,"setEngineInt32Param",(param_id:i64,object_handle:i64,int32_param:i64)->()), +(sim_set_explicit_handling,"setExplicitHandling",(object_handle:i64,explicit_handling_flags:i64)->()), +(sim_set_float_param,"setFloatParam",(parameter:i64,float_state:f64)->()), +(sim_set_float_signal,"setFloatSignal",(signal_name:String,signal_value:f64)->()), +(sim_set_graph_stream_transformation,"setGraphStreamTransformation",(graph_handle:i64,stream_id:i64,tr_type:i64),opt(mult:f64,off:f64,mov_avg_period:i64)->()), +(sim_set_graph_stream_value,"setGraphStreamValue",(graph_handle:i64,stream_id:i64,value:f64)->()), +(sim_set_int32_param,"setInt32Param",(parameter:i64,int_state:i64)->()), +(sim_set_int32_signal,"setInt32Signal",(signal_name:String,signal_value:i64)->()), +(sim_set_joint_dependency,"setJointDependency",(joint_handle:i64,master_joint_handle:i64,offset:f64,mult_coeff:f64)->()), +(sim_set_joint_interval,"setJointInterval",(object_handle:i64,cyclic:bool,interval:Vec)->()), +(sim_set_joint_mode,"setJointMode",(joint_handle:i64,joint_mode:i64,options:i64)->()), +(sim_set_joint_position,"setJointPosition",(object_handle:i64,position:f64)->()), +(sim_set_joint_target_force,"setJointTargetForce",(object_handle:i64,force_or_torque:f64),opt(signed_value:bool)->()), +(sim_set_joint_target_position,"setJointTargetPosition",(object_handle:i64,target_position:f64),opt(motion_params:Vec)->()), +(sim_set_joint_target_velocity,"setJointTargetVelocity",(object_handle:i64,target_velocity:f64),opt(motion_params:Vec)->()), +(sim_set_light_parameters,"setLightParameters",(light_handle:i64,state:i64,reserved:Vec,diffuse_part:Vec,specular_part:Vec)->()), +(sim_set_link_dummy,"setLinkDummy",(dummy_handle:i64,link_dummy_handle:i64)->()), +(sim_set_model_property,"setModelProperty",(object_handle:i64,property:i64)->()), +(sim_set_named_bool_param,"setNamedBoolParam",(name:String,value:bool)->()), +(sim_set_named_float_param,"setNamedFloatParam",(name:String,value:f64)->()), +(sim_set_named_int32_param,"setNamedInt32Param",(name:String,value:i64)->()), +(sim_set_named_string_param,"setNamedStringParam",(param_name:String,string_param:Vec)->()), +(sim_set_navigation_mode,"setNavigationMode",(navigation_mode:i64)->()), +(sim_set_object_alias,"setObjectAlias",(object_handle:i64,object_alias:String)->()), +(sim_set_object_child_pose,"setObjectChildPose",(object_handle:i64,pose:Vec)->()), +(sim_set_object_color,"setObjectColor",(object_handle:i64,index:i64,color_component:i64,rgb_data:Vec)->bool), +(sim_set_object_float_array_param,"setObjectFloatArrayParam",(object_handle:i64,parameter_id:i64,params:Vec)->()), +(sim_set_object_float_param,"setObjectFloatParam",(object_handle:i64,parameter_id:i64,parameter:f64)->()), +(sim_set_object_int32_param,"setObjectInt32Param",(object_handle:i64,parameter_id:i64,parameter:i64)->()), +(sim_set_object_matrix,"setObjectMatrix",(object_handle:i64,matrix:Vec),opt(relative_to_object_handle:i64)->()), +(sim_set_object_orientation,"setObjectOrientation",(object_handle:i64,euler_angles:Vec),opt(relative_to_object_handle:i64)->()), +(sim_set_object_parent,"setObjectParent",(object_handle:i64,parent_object_handle:i64),opt(keep_in_place:bool)->()), +(sim_set_object_pose,"setObjectPose",(object_handle:i64,pose:Vec),opt(relative_to_object_handle:i64)->()), +(sim_set_object_position,"setObjectPosition",(object_handle:i64,position:Vec),opt(relative_to_object_handle:i64)->()), +(sim_set_object_property,"setObjectProperty",(object_handle:i64,property:i64)->()), +(sim_set_object_quaternion,"setObjectQuaternion",(object_handle:i64,quaternion:Vec),opt(relative_to_object_handle:i64)->()), +(sim_set_object_sel,"setObjectSel",(object_handles:Vec)->()), +(sim_set_object_special_property,"setObjectSpecialProperty",(object_handle:i64,property:i64)->()), +(sim_set_object_string_param,"setObjectStringParam",(object_handle:i64,parameter_id:i64,parameter:Vec)->()), +(sim_set_page,"setPage",(page_index:i64)->()), +(sim_set_plugin_info,"setPluginInfo",(plugin_name:String,info_type:i64,info:String)->()), +(sim_set_point_cloud_options,"setPointCloudOptions",(point_cloud_handle:i64,max_voxel_size:f64,max_pt_cnt_per_voxel:i64,options:i64,point_size:f64)->()), +(sim_set_referenced_handles,"setReferencedHandles",(object_handle:i64,referenced_handles:Vec)->()), +(sim_set_script_int32_param,"setScriptInt32Param",(script_handle:i64,parameter_id:i64,parameter:i64)->()), +(sim_set_script_string_param,"setScriptStringParam",(script_handle:i64,parameter_id:i64,parameter:Vec)->()), +(sim_set_shape_bb,"setShapeBB",(shape_handle:i64,size:Vec)->()), +(sim_set_shape_color,"setShapeColor",(shape_handle:i64,color_name:String,color_component:i64,rgb_data:Vec)->()), +(sim_set_shape_inertia,"setShapeInertia",(shape_handle:i64,inertia_matrix:Vec,transformation_matrix:Vec)->()), +(sim_set_shape_mass,"setShapeMass",(shape_handle:i64,mass:f64)->()), +(sim_set_shape_material,"setShapeMaterial",(shape_handle:i64,material_id_or_shape_handle:i64)->()), +(sim_set_shape_texture,"setShapeTexture",(shape_handle:i64,texture_id:i64,mapping_mode:i64,options:i64,uv_scaling:Vec),opt(position:Vec,orientation:Vec)->()), +(sim_set_stepping,"setStepping",(enabled:bool)->i64), +(sim_set_string_param,"setStringParam",(parameter:i64,string_state:String)->()), +(sim_set_string_signal,"setStringSignal",(signal_name:String,signal_value:Vec)->()), +(sim_set_vision_sensor_img,"setVisionSensorImg",(sensor_handle:i64,image:Vec),opt(options:i64,pos:Vec,size:Vec)->()), +(sim_start_simulation,"startSimulation"->i64), +(sim_step,"step"->()), +(sim_stop_simulation,"stopSimulation"->i64), +(sim_subtract_object_from_octree,"subtractObjectFromOctree",(octree_handle:i64,object_handle:i64,options:i64)->i64), +(sim_subtract_object_from_point_cloud,"subtractObjectFromPointCloud",(point_cloud_handle:i64,object_handle:i64,options:i64,tolerance:f64)->i64), +(sim_text_editor_close,"textEditorClose",(handle:i64)->(String,Vec,Vec)), +(sim_text_editor_get_info,"textEditorGetInfo",(handle:i64)->(String,Vec,Vec,bool)), +(sim_text_editor_open,"textEditorOpen",(init_text:String,properties:String)->i64), +(sim_text_editor_show,"textEditorShow",(handle:i64,show_state:bool)->()), +(sim_transform_buffer,"transformBuffer",(in_buffer:Vec,in_format:i64,multiplier:f64,offset:f64,out_format:i64)->Vec), +(sim_transform_image,"transformImage",(image:Vec,resolution:Vec,options:i64)->()), +(sim_ungroup_shape,"ungroupShape",(shape_handle:i64)->Vec), +(sim_unpack_double_table,"unpackDoubleTable",(data:Vec),opt(start_double_index:i64,double_count:i64,additional_byte_offset:i64)->Vec), +(sim_unpack_float_table,"unpackFloatTable",(data:Vec),opt(start_float_index:i64,float_count:i64,additional_byte_offset:i64)->Vec), +(sim_unpack_int32_table,"unpackInt32Table",(data:Vec),opt(start_int32_index:i64,int32_count:i64,additional_byte_offset:i64)->Vec), +(sim_unpack_table,"unpackTable",(buffer:Vec)->serde_json::Value), +(sim_unpack_u_int16_table,"unpackUInt16Table",(data:Vec),opt(start_uint16_index:i64,uint16_count:i64,additional_byte_offset:i64)->Vec), +(sim_unpack_u_int32_table,"unpackUInt32Table",(data:Vec),opt(start_uint32_index:i64,uint32_count:i64,additional_byte_offset:i64)->Vec), +(sim_unpack_u_int8_table,"unpackUInt8Table",(data:Vec),opt(start_uint8_index:i64,uint8count:i64)->Vec), +(sim_visit_tree,"visitTree",(root_handle:i64,visitor_func:String),opt(options:serde_json::Value)->()), +(sim_wait,"wait",(dt:f64),opt(simulation_time:bool)->f64), +(sim_wait_for_signal,"waitForSignal",(sig_name:String)->serde_json::Value), +(sim_write_custom_data_block,"writeCustomDataBlock",(object_handle:i64,tag_name:String,data:Vec)->()), +(sim_write_custom_data_block_ex,"writeCustomDataBlockEx",(handle:i64,tag_name:String,data:String),opt(options:serde_json::Value)->()), +(sim_write_custom_table_data,"writeCustomTableData",(handle:i64,tag_name:String,the_table:serde_json::Value),opt(options:serde_json::Value)->()), +(sim_write_texture,"writeTexture",(texture_id:i64,options:i64,texture_data:Vec),opt(pos_x:i64,pos_y:i64,size_x:i64,size_y:i64,interpol:f64)->()), +(sim_yaw_pitch_roll_to_alpha_beta_gamma,"yawPitchRollToAlphaBetaGamma",(yaw_angle:f64,pitch_angle:f64,roll_angle:f64)->(f64,f64,f64)), +(sim_yield,"yield"->()) } +} \ No newline at end of file diff --git a/src/remote_api_objects/sim/sim_ik_api.rs b/src/remote_api_objects/sim/sim_ik_api.rs index f39411b..f9a9ee3 100644 --- a/src/remote_api_objects/sim/sim_ik_api.rs +++ b/src/remote_api_objects/sim/sim_ik_api.rs @@ -1,82 +1,82 @@ use crate::RemoteApiClientInterface; -pub trait SimIK: RemoteApiClientInterface { - requests! { - "simIK", - (sim_ik_add_element,"addElement",(environment_handle:i64,ik_group_handle:i64,tip_dummy_handle:i64)->i64), - (sim_ik_add_element_from_scene,"addElementFromScene",(environment_handle:i64,ik_group:i64,base_handle:i64,tip_handle:i64,target_handle:i64,constraints:i64)->(i64,serde_json::Value,serde_json::Value)), - (sim_ik_compute_group_jacobian,"computeGroupJacobian",(environment_handle:i64,ik_group_handle:i64)->(Vec,Vec)), - (sim_ik_compute_jacobian,"computeJacobian",(environment_handle:i64,base_object:i64,last_joint:i64,constraints:i64,tip_matrix:Vec),opt(target_matrix:Vec,constr_base_matrix:Vec)->(Vec,Vec)), - (sim_ik_create_debug_overlay,"createDebugOverlay",(environment_handle:i64,tip_handle:i64),opt(base_handle:i64)->i64), - (sim_ik_create_dummy,"createDummy",(environment_handle:i64),opt(dummy_name:String)->i64), - (sim_ik_create_environment,"createEnvironment",opt(flags:i64)->i64), - (sim_ik_create_group,"createGroup",(environment_handle:i64),opt(ik_group_name:String)->i64), - (sim_ik_create_joint,"createJoint",(environment_handle:i64,joint_type:i64),opt(joint_name:String)->i64), - (sim_ik_does_group_exist,"doesGroupExist",(environment_handle:i64,ik_group_name:String)->bool), - (sim_ik_does_object_exist,"doesObjectExist",(environment_handle:i64,object_name:String)->bool), - (sim_ik_duplicate_environment,"duplicateEnvironment",(environment_handle:i64)->i64), - (sim_ik_erase_debug_overlay,"eraseDebugOverlay",(debug_object:i64)->()), - (sim_ik_erase_environment,"eraseEnvironment",(environment_handle:i64)->()), - (sim_ik_erase_object,"eraseObject",(environment_handle:i64,object_handle:i64)->()), - (sim_ik_find_config,"findConfig",(environment_handle:i64,ik_group_handle:i64,joint_handles:Vec),opt(threshold_dist:f64,max_time:f64,metric:Vec,validation_callback:String,aux_data:serde_json::Value)->Vec), - (sim_ik_generate_path,"generatePath",(environment_handle:i64,ik_group_handle:i64,joint_handles:Vec,tip_handle:i64,path_point_count:i64),opt(validation_callback:String,aux_data:serde_json::Value)->Vec), - (sim_ik_get_alternate_configs,"getAlternateConfigs",(environment_handle:i64,joint_handles:Vec),opt(low_limits:Vec,ranges:Vec)->Vec), - (sim_ik_get_element_base,"getElementBase",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->(i64,i64)), - (sim_ik_get_element_constraints,"getElementConstraints",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->i64), - (sim_ik_get_element_flags,"getElementFlags",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->i64), - (sim_ik_get_element_precision,"getElementPrecision",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->Vec), - (sim_ik_get_element_weights,"getElementWeights",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->Vec), - (sim_ik_get_failure_description,"getFailureDescription",(reason:i64)->String), - (sim_ik_get_group_calculation,"getGroupCalculation",(environment_handle:i64,ik_group_handle:i64)->(i64,f64,i64)), - (sim_ik_get_group_flags,"getGroupFlags",(environment_handle:i64,ik_group_handle:i64)->i64), - (sim_ik_get_group_handle,"getGroupHandle",(environment_handle:i64,ik_group_name:String)->i64), - (sim_ik_get_group_joint_limit_hits,"getGroupJointLimitHits",(environment_handle:i64,ik_group_handle:i64)->(Vec,Vec)), - (sim_ik_get_group_joints,"getGroupJoints",(environment_handle:i64,ik_group_handle:i64)->Vec), - (sim_ik_get_joint_dependency,"getJointDependency",(environment_handle:i64,joint_handle:i64)->(i64,f64,f64)), - (sim_ik_get_joint_interval,"getJointInterval",(environment_handle:i64,joint_handle:i64)->(bool,Vec)), - (sim_ik_get_joint_limit_margin,"getJointLimitMargin",(environment_handle:i64,joint_handle:i64)->f64), - (sim_ik_get_joint_matrix,"getJointMatrix",(environment_handle:i64,joint_handle:i64)->Vec), - (sim_ik_get_joint_max_step_size,"getJointMaxStepSize",(environment_handle:i64,joint_handle:i64)->f64), - (sim_ik_get_joint_mode,"getJointMode",(environment_handle:i64,joint_handle:i64)->i64), - (sim_ik_get_joint_position,"getJointPosition",(environment_handle:i64,joint_handle:i64)->f64), - (sim_ik_get_joint_screw_lead,"getJointScrewLead",(environment_handle:i64,joint_handle:i64)->f64), - (sim_ik_get_joint_transformation,"getJointTransformation",(environment_handle:i64,joint_handle:i64)->(Vec,Vec,Vec)), - (sim_ik_get_joint_type,"getJointType",(environment_handle:i64,joint_handle:i64)->i64), - (sim_ik_get_joint_weight,"getJointWeight",(environment_handle:i64,joint_handle:i64)->f64), - (sim_ik_get_object_handle,"getObjectHandle",(environment_handle:i64,object_name:String)->i64), - (sim_ik_get_object_matrix,"getObjectMatrix",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64)->Vec), - (sim_ik_get_object_parent,"getObjectParent",(environment_handle:i64,object_handle:i64)->i64), - (sim_ik_get_object_pose,"getObjectPose",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64)->Vec), - (sim_ik_get_object_transformation,"getObjectTransformation",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64)->(Vec,Vec,Vec)), - (sim_ik_get_object_type,"getObjectType",(environment_handle:i64,object_handle:i64)->i64), - (sim_ik_get_objects,"getObjects",(environment_handle:i64,index:i64)->(i64,String,bool,i64)), - (sim_ik_get_target_dummy,"getTargetDummy",(environment_handle:i64,dummy_handle:i64)->i64), - (sim_ik_handle_group,"handleGroup",(environment_handle:i64,ik_group:i64),opt(options:serde_json::Value)->(i64,i64,Vec)), - (sim_ik_handle_groups,"handleGroups",(environment_handle:i64,ik_groups:Vec),opt(options:serde_json::Value)->(i64,i64,Vec)), - (sim_ik_load,"load",(environment_handle:i64,data:String)->()), - (sim_ik_save,"save",(environment_handle:i64)->String), - (sim_ik_set_element_base,"setElementBase",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,base_handle:i64),opt(constraints_base_handle:i64)->()), - (sim_ik_set_element_constraints,"setElementConstraints",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,constraints:i64)->()), - (sim_ik_set_element_flags,"setElementFlags",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,flags:i64)->()), - (sim_ik_set_element_precision,"setElementPrecision",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,precision:Vec)->()), - (sim_ik_set_element_weights,"setElementWeights",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,weights:Vec)->()), - (sim_ik_set_group_calculation,"setGroupCalculation",(environment_handle:i64,ik_group_handle:i64,method:i64,damping:f64,max_iterations:i64)->()), - (sim_ik_set_group_flags,"setGroupFlags",(environment_handle:i64,ik_group_handle:i64,flags:i64)->()), - (sim_ik_set_joint_dependency,"setJointDependency",(environment_handle:i64,joint_handle:i64,master_joint_handle:i64),opt(offset:f64,mult:f64,callback:String)->()), - (sim_ik_set_joint_interval,"setJointInterval",(environment_handle:i64,joint_handle:i64,cyclic:bool),opt(interval:Vec)->()), - (sim_ik_set_joint_limit_margin,"setJointLimitMargin",(environment_handle:i64,joint_handle:i64,margin:f64)->()), - (sim_ik_set_joint_max_step_size,"setJointMaxStepSize",(environment_handle:i64,joint_handle:i64,step_size:f64)->()), - (sim_ik_set_joint_mode,"setJointMode",(environment_handle:i64,joint_handle:i64,joint_mode:i64)->()), - (sim_ik_set_joint_position,"setJointPosition",(environment_handle:i64,joint_handle:i64,position:f64)->()), - (sim_ik_set_joint_screw_lead,"setJointScrewLead",(environment_handle:i64,joint_handle:i64,lead:f64)->()), - (sim_ik_set_joint_weight,"setJointWeight",(environment_handle:i64,joint_handle:i64,weight:f64)->()), - (sim_ik_set_object_matrix,"setObjectMatrix",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64,matrix:Vec)->()), - (sim_ik_set_object_parent,"setObjectParent",(environment_handle:i64,object_handle:i64,parent_object_handle:i64),opt(keep_in_place:bool)->()), - (sim_ik_set_object_pose,"setObjectPose",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64,pose:Vec)->()), - (sim_ik_set_object_transformation,"setObjectTransformation",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64,position:Vec,euler_or_quaternion:Vec)->()), - (sim_ik_set_spherical_joint_matrix,"setSphericalJointMatrix",(environment_handle:i64,joint_handle:i64,matrix:Vec)->()), - (sim_ik_set_spherical_joint_rotation,"setSphericalJointRotation",(environment_handle:i64,joint_handle:i64,euler_or_quaternion:Vec)->()), - (sim_ik_set_target_dummy,"setTargetDummy",(environment_handle:i64,dummy_handle:i64,target_dummy_handle:i64)->()), - (sim_ik_sync_from_sim,"syncFromSim",(environment_handle:i64,ik_groups:Vec)->()), - (sim_ik_sync_to_sim,"syncToSim",(environment_handle:i64,ik_groups:Vec)->()) - } +pub trait SimIK : RemoteApiClientInterface { + requests!{ +"simIK", +(sim_ik_add_element,"addElement",(environment_handle:i64,ik_group_handle:i64,tip_dummy_handle:i64)->i64), +(sim_ik_add_element_from_scene,"addElementFromScene",(environment_handle:i64,ik_group:i64,base_handle:i64,tip_handle:i64,target_handle:i64,constraints:i64)->(i64,serde_json::Value,serde_json::Value)), +(sim_ik_compute_group_jacobian,"computeGroupJacobian",(environment_handle:i64,ik_group_handle:i64)->(Vec,Vec)), +(sim_ik_compute_jacobian,"computeJacobian",(environment_handle:i64,base_object:i64,last_joint:i64,constraints:i64,tip_matrix:Vec),opt(target_matrix:Vec,constr_base_matrix:Vec)->(Vec,Vec)), +(sim_ik_create_debug_overlay,"createDebugOverlay",(environment_handle:i64,tip_handle:i64),opt(base_handle:i64)->i64), +(sim_ik_create_dummy,"createDummy",(environment_handle:i64),opt(dummy_name:String)->i64), +(sim_ik_create_environment,"createEnvironment",opt(flags:i64)->i64), +(sim_ik_create_group,"createGroup",(environment_handle:i64),opt(ik_group_name:String)->i64), +(sim_ik_create_joint,"createJoint",(environment_handle:i64,joint_type:i64),opt(joint_name:String)->i64), +(sim_ik_does_group_exist,"doesGroupExist",(environment_handle:i64,ik_group_name:String)->bool), +(sim_ik_does_object_exist,"doesObjectExist",(environment_handle:i64,object_name:String)->bool), +(sim_ik_duplicate_environment,"duplicateEnvironment",(environment_handle:i64)->i64), +(sim_ik_erase_debug_overlay,"eraseDebugOverlay",(debug_object:i64)->()), +(sim_ik_erase_environment,"eraseEnvironment",(environment_handle:i64)->()), +(sim_ik_erase_object,"eraseObject",(environment_handle:i64,object_handle:i64)->()), +(sim_ik_find_config,"findConfig",(environment_handle:i64,ik_group_handle:i64,joint_handles:Vec),opt(threshold_dist:f64,max_time:f64,metric:Vec,validation_callback:String,aux_data:serde_json::Value)->Vec), +(sim_ik_generate_path,"generatePath",(environment_handle:i64,ik_group_handle:i64,joint_handles:Vec,tip_handle:i64,path_point_count:i64),opt(validation_callback:String,aux_data:serde_json::Value)->Vec), +(sim_ik_get_alternate_configs,"getAlternateConfigs",(environment_handle:i64,joint_handles:Vec),opt(low_limits:Vec,ranges:Vec)->Vec), +(sim_ik_get_element_base,"getElementBase",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->(i64,i64)), +(sim_ik_get_element_constraints,"getElementConstraints",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->i64), +(sim_ik_get_element_flags,"getElementFlags",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->i64), +(sim_ik_get_element_precision,"getElementPrecision",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->Vec), +(sim_ik_get_element_weights,"getElementWeights",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->Vec), +(sim_ik_get_failure_description,"getFailureDescription",(reason:i64)->String), +(sim_ik_get_group_calculation,"getGroupCalculation",(environment_handle:i64,ik_group_handle:i64)->(i64,f64,i64)), +(sim_ik_get_group_flags,"getGroupFlags",(environment_handle:i64,ik_group_handle:i64)->i64), +(sim_ik_get_group_handle,"getGroupHandle",(environment_handle:i64,ik_group_name:String)->i64), +(sim_ik_get_group_joint_limit_hits,"getGroupJointLimitHits",(environment_handle:i64,ik_group_handle:i64)->(Vec,Vec)), +(sim_ik_get_group_joints,"getGroupJoints",(environment_handle:i64,ik_group_handle:i64)->Vec), +(sim_ik_get_joint_dependency,"getJointDependency",(environment_handle:i64,joint_handle:i64)->(i64,f64,f64)), +(sim_ik_get_joint_interval,"getJointInterval",(environment_handle:i64,joint_handle:i64)->(bool,Vec)), +(sim_ik_get_joint_limit_margin,"getJointLimitMargin",(environment_handle:i64,joint_handle:i64)->f64), +(sim_ik_get_joint_matrix,"getJointMatrix",(environment_handle:i64,joint_handle:i64)->Vec), +(sim_ik_get_joint_max_step_size,"getJointMaxStepSize",(environment_handle:i64,joint_handle:i64)->f64), +(sim_ik_get_joint_mode,"getJointMode",(environment_handle:i64,joint_handle:i64)->i64), +(sim_ik_get_joint_position,"getJointPosition",(environment_handle:i64,joint_handle:i64)->f64), +(sim_ik_get_joint_screw_lead,"getJointScrewLead",(environment_handle:i64,joint_handle:i64)->f64), +(sim_ik_get_joint_transformation,"getJointTransformation",(environment_handle:i64,joint_handle:i64)->(Vec,Vec,Vec)), +(sim_ik_get_joint_type,"getJointType",(environment_handle:i64,joint_handle:i64)->i64), +(sim_ik_get_joint_weight,"getJointWeight",(environment_handle:i64,joint_handle:i64)->f64), +(sim_ik_get_object_handle,"getObjectHandle",(environment_handle:i64,object_name:String)->i64), +(sim_ik_get_object_matrix,"getObjectMatrix",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64)->Vec), +(sim_ik_get_object_parent,"getObjectParent",(environment_handle:i64,object_handle:i64)->i64), +(sim_ik_get_object_pose,"getObjectPose",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64)->Vec), +(sim_ik_get_object_transformation,"getObjectTransformation",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64)->(Vec,Vec,Vec)), +(sim_ik_get_object_type,"getObjectType",(environment_handle:i64,object_handle:i64)->i64), +(sim_ik_get_objects,"getObjects",(environment_handle:i64,index:i64)->(i64,String,bool,i64)), +(sim_ik_get_target_dummy,"getTargetDummy",(environment_handle:i64,dummy_handle:i64)->i64), +(sim_ik_handle_group,"handleGroup",(environment_handle:i64,ik_group:i64),opt(options:serde_json::Value)->(i64,i64,Vec)), +(sim_ik_handle_groups,"handleGroups",(environment_handle:i64,ik_groups:Vec),opt(options:serde_json::Value)->(i64,i64,Vec)), +(sim_ik_load,"load",(environment_handle:i64,data:String)->()), +(sim_ik_save,"save",(environment_handle:i64)->String), +(sim_ik_set_element_base,"setElementBase",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,base_handle:i64),opt(constraints_base_handle:i64)->()), +(sim_ik_set_element_constraints,"setElementConstraints",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,constraints:i64)->()), +(sim_ik_set_element_flags,"setElementFlags",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,flags:i64)->()), +(sim_ik_set_element_precision,"setElementPrecision",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,precision:Vec)->()), +(sim_ik_set_element_weights,"setElementWeights",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,weights:Vec)->()), +(sim_ik_set_group_calculation,"setGroupCalculation",(environment_handle:i64,ik_group_handle:i64,method:i64,damping:f64,max_iterations:i64)->()), +(sim_ik_set_group_flags,"setGroupFlags",(environment_handle:i64,ik_group_handle:i64,flags:i64)->()), +(sim_ik_set_joint_dependency,"setJointDependency",(environment_handle:i64,joint_handle:i64,master_joint_handle:i64),opt(offset:f64,mult:f64,callback:String)->()), +(sim_ik_set_joint_interval,"setJointInterval",(environment_handle:i64,joint_handle:i64,cyclic:bool),opt(interval:Vec)->()), +(sim_ik_set_joint_limit_margin,"setJointLimitMargin",(environment_handle:i64,joint_handle:i64,margin:f64)->()), +(sim_ik_set_joint_max_step_size,"setJointMaxStepSize",(environment_handle:i64,joint_handle:i64,step_size:f64)->()), +(sim_ik_set_joint_mode,"setJointMode",(environment_handle:i64,joint_handle:i64,joint_mode:i64)->()), +(sim_ik_set_joint_position,"setJointPosition",(environment_handle:i64,joint_handle:i64,position:f64)->()), +(sim_ik_set_joint_screw_lead,"setJointScrewLead",(environment_handle:i64,joint_handle:i64,lead:f64)->()), +(sim_ik_set_joint_weight,"setJointWeight",(environment_handle:i64,joint_handle:i64,weight:f64)->()), +(sim_ik_set_object_matrix,"setObjectMatrix",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64,matrix:Vec)->()), +(sim_ik_set_object_parent,"setObjectParent",(environment_handle:i64,object_handle:i64,parent_object_handle:i64),opt(keep_in_place:bool)->()), +(sim_ik_set_object_pose,"setObjectPose",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64,pose:Vec)->()), +(sim_ik_set_object_transformation,"setObjectTransformation",(environment_handle:i64,object_handle:i64,relative_to_object_handle:i64,position:Vec,euler_or_quaternion:Vec)->()), +(sim_ik_set_spherical_joint_matrix,"setSphericalJointMatrix",(environment_handle:i64,joint_handle:i64,matrix:Vec)->()), +(sim_ik_set_spherical_joint_rotation,"setSphericalJointRotation",(environment_handle:i64,joint_handle:i64,euler_or_quaternion:Vec)->()), +(sim_ik_set_target_dummy,"setTargetDummy",(environment_handle:i64,dummy_handle:i64,target_dummy_handle:i64)->()), +(sim_ik_sync_from_sim,"syncFromSim",(environment_handle:i64,ik_groups:Vec)->()), +(sim_ik_sync_to_sim,"syncToSim",(environment_handle:i64,ik_groups:Vec)->()) } +} \ No newline at end of file