diff --git a/Cargo.toml b/Cargo.toml index 80dae1f..38260b1 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,6 +1,6 @@ [package] name = "zmq_remote_api" -version = "0.2.0" +version = "4.6.0" edition = "2021" diff --git a/examples/sim_ik_example.rs b/examples/sim_ik_example.rs index 2fef711..36df03e 100644 --- a/examples/sim_ik_example.rs +++ b/examples/sim_ik_example.rs @@ -27,7 +27,7 @@ fn main() -> Result<(), RemoteAPIError> { })?; // Must call require before usint sim_ik functions - client.require(sim::Module::SimIK)?; + client.require(sim::Plugin::SimIK)?; // When simulation is not running, ZMQ message handling could be a bit // slow, since the idle loop runs at 8 Hz by default. So let's make diff --git a/src/lib.rs b/src/lib.rs index 6376d31..f25f983 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -1,4 +1,29 @@ -pub mod log_utils; +//! # ZMQ Remote API for CoppeliaSim, Rust implementation +//! The ZMQ Remote API requires the [ZMQ plugin](https://github.com/CoppeliaRobotics/simExtZMQ). +//! +//! the Current Plugins support is +//! - [SimIK](https://www.coppeliarobotics.com/helpFiles/en/simIK.htm) +//! - [The Remote API](https://www.coppeliarobotics.com/helpFiles/index.html) +//! +//! Make sure that you are using the same version of the Client and CoppeliaSim, see the branchs of the repository +//! [rust_zmqRemoteApi](https://github.com/samuel-cavalcanti/rust_zmqRemoteApi) +//! +//! ## Get started +//! +//! ``` +//! use zmq_remote_api::{sim, sim::Sim, RemoteAPIError, RemoteApiClientParams}; +//! +//! fn main() -> Result<(), RemoteAPIError> { +//! let client = zmq_remote_api::RemoteApiClient::new(RemoteApiClientParams::default())?; +//! +//! Ok(()) +//! } +//! +//! ``` +//! Or See an example in +//! [examples](https://github.com/samuel-cavalcanti/rust_zmqRemoteApi/tree/main/examples) +//! +mod log_utils; mod remote_api_client; mod remote_api_objects; mod zmq_protocol; @@ -9,5 +34,5 @@ pub use zmq_protocol::{ErrorResponse, FunctionResponse, ObjectResponse, ZmqRespo pub use zmq_protocol::{RawRequest, ZmqRequest, LANG, VERSION}; pub use remote_api_objects::connection_error::RemoteAPIError; - +/// You will need to use Json to communicate with the the ZMQ server pub use serde_json; diff --git a/src/remote_api_client/client.rs b/src/remote_api_client/client.rs index 40245fe..3a4fa4a 100644 --- a/src/remote_api_client/client.rs +++ b/src/remote_api_client/client.rs @@ -11,7 +11,14 @@ use crate::zmq_protocol::{RawRequest, ZmqRequest}; use crate::{log_utils, RemoteAPIError, RemoteApiClientParams}; const ZMQ_RECV_FLAG_NONE: i32 = 0; - +/// The ZEROMQ Socket Connection +/// BY default host:"localhost" +/// BY default port:23000 +/// # Example: +/// ``` +/// use zmq_remote_api::{RemoteApiClient,RemoteApiClientParams}; +/// let client = RemoteApiClient::new(RemoteApiClientParams::default()).unwrap(); +/// ``` pub struct RemoteApiClient { rpc_socket: zmq::Socket, end_point: String, diff --git a/src/remote_api_client/remote_api_client_params.rs b/src/remote_api_client/remote_api_client_params.rs index ac6a27c..6bf0e83 100644 --- a/src/remote_api_client/remote_api_client_params.rs +++ b/src/remote_api_client/remote_api_client_params.rs @@ -1,5 +1,9 @@ +/// The Socket connection Parameters, in most of the cases the default is Okay to use +/// If the simulation is running in another pc, make sure the ip is correct pub struct RemoteApiClientParams { + /// the Ip address, the default is "localhost" pub host: String, + /// The socket port, the default is 23000 pub rpc_port: usize, } diff --git a/src/remote_api_client/remote_api_client_trait.rs b/src/remote_api_client/remote_api_client_trait.rs index a6e27f0..3a4aa0c 100644 --- a/src/remote_api_client/remote_api_client_trait.rs +++ b/src/remote_api_client/remote_api_client_trait.rs @@ -1,15 +1,18 @@ use serde_json::Value as JsonValue; -use crate::{sim::Module, RawRequest, RemoteAPIError, ZmqRequest, ZmqResponse}; +use crate::{sim::Plugin, RawRequest, RemoteAPIError, ZmqRequest, ZmqResponse}; +/// THe implementation of the [PROTOCOL](https://github.com/CoppeliaRobotics/zmqRemoteApi/blob/master/PROTOCOL.md) +/// This trait forces a socket connection to implement the PROTOCOL +/// The Sim, SimIK, rely on this trait pub trait RemoteApiClientInterface { fn send_raw_request(&self, request: Vec) -> Result; fn get_uuid(&self) -> String; fn get_callback(&self, function_name: &str) -> Option<&Box JsonValue>>; - fn require(&self, module: Module) -> Result<(), RemoteAPIError> { + fn require(&self, module: Plugin) -> Result<(), RemoteAPIError> { let name = match module { - Module::SimIK => "simIK".into(), + Plugin::SimIK => "simIK".into(), }; let require_req = ZmqRequest::require_request(name, self.get_uuid()); diff --git a/src/remote_api_objects/connection_error.rs b/src/remote_api_objects/connection_error.rs index e0de449..61d128f 100644 --- a/src/remote_api_objects/connection_error.rs +++ b/src/remote_api_objects/connection_error.rs @@ -1,4 +1,5 @@ #[derive(Debug)] +/// RemoteAPIError will be retured if the client was unable to send our receive messages pub struct RemoteAPIError { message: String, } diff --git a/src/remote_api_objects/requests_macro.rs b/src/remote_api_objects/requests_macro.rs index 8ad9c47..fdb91ca 100644 --- a/src/remote_api_objects/requests_macro.rs +++ b/src/remote_api_objects/requests_macro.rs @@ -1,13 +1,13 @@ macro_rules! requests { ( $sim_type:literal, $( - ($rust_fn:ident,$function_name:literal $(, ( $($arg_id:ident : $arg_type:ty),+ ) )? $(, opt( $($opt_arg_id:ident : $opt_arg_type:ty),+ ) )? $(->$return_type:ty)? ) + ($rust_doc:literal, $rust_fn:ident,$function_name:literal $(, ( $($arg_id:ident : $arg_type:ty),+ ) )? $(, opt( $($opt_arg_id:ident : $opt_arg_type:ty),+ ) )? $(->$return_type:ty)? ) ),+ $(,)? ) => { $( - + #[doc=$rust_doc] #[allow(dead_code,clippy::too_many_arguments)] fn $rust_fn(&self, $( $($arg_id:$arg_type,)* )* $( $($opt_arg_id:Option<$opt_arg_type>,)* )* ) -> Result<$($return_type)*, crate::remote_api_objects::connection_error::RemoteAPIError> {// diff --git a/src/remote_api_objects/sim/mod.rs b/src/remote_api_objects/sim/mod.rs index ea93d51..95613ef 100644 --- a/src/remote_api_objects/sim/mod.rs +++ b/src/remote_api_objects/sim/mod.rs @@ -1,3 +1,6 @@ +//! All the Supported Plugins is insite this module +//! Current only the Remote API and SimIK is Supported + #[rustfmt::skip] mod sim_api; #[rustfmt::skip] @@ -9,7 +12,8 @@ pub use sim_api::Sim; pub use sim_const::*; pub use sim_ik_api::SimIK; -pub enum Module { +/// The Supported extra plugins +pub enum Plugin { SimIK, } diff --git a/src/remote_api_objects/sim/sim_api.rs b/src/remote_api_objects/sim/sim_api.rs index 66303e6..fd4b20f 100644 --- a/src/remote_api_objects/sim/sim_api.rs +++ b/src/remote_api_objects/sim/sim_api.rs @@ -1,385 +1,457 @@ use crate::RemoteApiClientInterface; +#[doc=r#"The list of API functions below allows you to access many CoppeliaSim parameters. There are however too many parameters in CoppeliaSim to have a specific API function for each one of them. Auxiliary parameters can be accessed via a set of given functions that use object parameter IDs. Refer also to the global parameter IDs. +All units going to, or coming from the API are in meters, kilograms, seconds and radians or a combination of those (unless otherwise explicitly indicated). +"#] 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_test_cb,"testCB",(a:i64,cb:String,b:i64)->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"->()) +(r#"Deprecated. See sim.setJointTargetForce instead."#,sim_set_joint_max_force,"setJointMaxForce",(object_handle:i64,force_or_torque:f64)->()), +(r#"Deprecated. See sim.getJointTargetForce instead."#,sim_get_joint_max_force,"getJointMaxForce",(joint_handle:i64)->f64), +(r#"Deprecated. Use sim.createPrimitiveShape instead"#,sim_create_pure_shape,"createPureShape",(primitive_type:i64,options:i64,sizes:Vec,mass:f64),opt(precision:Vec)->i64), +(r#"Deprecated. See sim.removeObjects instead +"#,sim_remove_object,"removeObject",(object_handle:i64)->()), +(r#"Deprecated. Use sim.getVisionSensorDepth instead"#,sim_get_vision_sensor_depth_buffer,"getVisionSensorDepthBuffer",(sensor_handle:i64),opt(pos:Vec,size:Vec)->(Vec,Vec)), +(r#"Deprecated. Use sim.getVisionSensorImg instead"#,sim_get_vision_sensor_char_image,"getVisionSensorCharImage",(sensor_handle:i64),opt(pos:Vec,size:Vec)->(Vec,Vec)), +(r#"Deprecated. Use sim.setVisionSensorImg instead"#,sim_set_vision_sensor_char_image,"setVisionSensorCharImage",(sensor_handle:i64,image:Vec)->()), +(r#"Deprecated. Use sim.getObjectSel instead"#,sim_get_object_selection,"getObjectSelection"->Vec), +(r#"Deprecated. Use sim.setObjectSel instead"#,sim_set_object_selection,"setObjectSelection",(object_handles:Vec)->()), +(r#"Gets the value of a string signal. See also the other signal functions."#,sim_get_string_signal,"getStringSignal",(signal_name:String)->Option>), +(r#"Gets the value of an integer signal. See also the other signal functions."#,sim_get_int32_signal,"getInt32Signal",(signal_name:String)->Option), +(r#"Gets the value of a double signal. See also the other signal functions."#,sim_get_float_signal,"getFloatSignal",(signal_name:String)->Option), +(r#"Allows to have CoppeliaSim wait for a threaded code section to be executed without interruption. Locking is cumulative. See also sim.releaseLock"#,sim_acquire_lock,"acquireLock"->()), +(r#"Adds a drawing object that will be displayed in the scene. Drawing objects are containers that hold several items of a given type. This can be used for several different applications (simulation of paint, simulation of welding seam, display of 3D objects, etc.). Drawing objects created in a simulation script will be automatically removed at simulation end. See also sim.addDrawingObjectItem, sim.removeDrawingObject and the point cloud functionality."#,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), +(r#"Adds an item (or clears all items) to a previously inserted drawing object. See also sim.addDrawingObject and sim.removeDrawingObject"#,sim_add_drawing_object_item,"addDrawingObjectItem",(drawing_object_handle:i64,item_data:Vec)->i64), +(r#"Adds a non-central force to a shape object that is dynamically enabled. Added forces are cumulative, applied relative to the center of mass, and are reset to zero after sim.handleDynamics was called (or by using the following flag: sim.handleflag_resetforcetorque). See also sim.addForceAndTorque."#,sim_add_force,"addForce",(shape_handle:i64,position:Vec,force:Vec)->()), +(r#"Adds a force and/or torque to a shape object that is dynamically enabled. Forces are applied at the center of mass. Added forces and torques are cumulative, and are reset to zero after sim.handleDynamics was called (or by using the following flags: sim.handleflag_resetforce and/or sim.handleflag_resettorque). See also sim.addForce."#,sim_add_force_and_torque,"addForceAndTorque",(shape_handle:i64),opt(force:Vec,torque:Vec)->()), +(r#"Adds or updates a graph curve. A graph curve is persistent, but can be removed with sim.destroyGraphCurve. See also the other functions related to graphs."#,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), +(r#"Adds or updates a graph stream. A graph stream is persistent, but can be removed with sim.destroyGraphCurve. See also the other functions related to graphs."#,sim_add_graph_stream,"addGraphStream",(graph_handle:i64,stream_name:String,unit:String),opt(options:i64,color:Vec,cyclic_range:f64)->i64), +(r#" +Adds an item to a collection. See also the other functions related to collections. "#,sim_add_item_to_collection,"addItemToCollection",(collection_handle:i64,what:i64,object_handle:i64,options:i64)->()), +(r#"Adds a log message that will be output in the console or status bar."#,sim_add_log,"addLog",(verbosity_level:i64,log_message:String)->()), +(r#"Adds a particle object that will be simulated and displayed in the scene. Particle objects are containers that hold several items (particles) of a given type. This can be used for several different applications (e.g. simulation of air/water jets) See also sim.addParticleObjectItem and sim.removeParticleObject"#,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), +(r#"Adds an item (or clears all items) to a previously inserted particle object. See also sim.addParticleObject and sim.removeParticleObject"#,sim_add_particle_object_item,"addParticleObjectItem",(object_handle:i64,item_data:Vec)->()), +(r#""#,sim_add_referenced_handle,"addReferencedHandle",(object_handle:i64,referenced_handle:i64)->()), +(r#"Inserts a new script. Use with care when simulation is running. See also sim.associateScriptWithObject."#,sim_add_script,"addScript",(script_type:i64)->i64), +(r#"Adjusts parameters of a view. See also the sim.floatingViewAdd and sim.cameraFitToView functions."#,sim_adjust_view,"adjustView",(view_handle_or_index:i64,associated_viewable_object_handle:i64,options:i64),opt(view_label:String)->i64), +(r#"Reorients the bounding box of a shape, while keeping the shape frame in place. The shape's inertia properties are unaffected. See also sim.relocateShapeFrame"#,sim_align_shape_bb,"alignShapeBB",(shape_handle:i64,pose:Vec)->i64), +(r#"Converts CoppeliaSim's alpha-beta-gamma angles to Yaw-Pitch-Roll angles. See also sim.yawPitchRollToAlphaBetaGamma and the section about positions, orientations and transformations"#,sim_alpha_beta_gamma_to_yaw_pitch_roll,"alphaBetaGammaToYawPitchRoll",(alpha_angle:f64,beta_angle:f64,gamma_angle:f64)->(f64,f64,f64)), +(r#"Announces a change in the scene. This is required for the undo/redo function to operate properly when performing changes via the API. Only call this function directly after a change was made through a dialog element (e.g. a checkbox was checked/unchecked) and that change was reported to the scene (e.g. with sim.writeCustomDataBlock). What this call will do is following: the whole scene will be serialized (saved) to memory as a "scene image" and compared to a previously memorized "scene image". If both images are same, then the last image is discarded, otherwise only the changes between the two images are memorized. A call to this function has no effect (and doesn't generate any error) when called during simulation or when in edit mode."#,sim_announce_scene_content_change,"announceSceneContentChange"->i64), +(r#"Sets the associated object of a child script. Use with care when simulation is running. See also sim.addScript and sim.setScriptText. "#,sim_associate_script_with_object,"associateScriptWithObject",(script_handle:i64,object_handle:i64)->()), +(r#"Closes an auxiliary console window. See also sim.auxiliaryConsoleOpen."#,sim_auxiliary_console_close,"auxiliaryConsoleClose",(console_handle:i64)->i64), +(r#"Opens an auxiliary console window for text display. This console window is different from the application main console window. Console window handles are shared across all simulator scenes. See also sim.auxiliaryConsolePrint, sim.auxiliaryConsoleClose and sim.addLog."#,sim_auxiliary_console_open,"auxiliaryConsoleOpen",(title:String,max_lines:i64,mode:i64),opt(position:Vec,size:Vec,text_color:Vec,background_color:Vec)->i64), +(r#" +Prints to an auxiliary console window. See also sim.auxiliaryConsoleOpen. "#,sim_auxiliary_console_print,"auxiliaryConsolePrint",(console_handle:i64,text:String)->i64), +(r#"Shows or hides an auxiliary console window. See also sim.auxiliaryConsoleOpen and sim.auxiliaryConsoleClose."#,sim_auxiliary_console_show,"auxiliaryConsoleShow",(console_handle:i64,show_state:bool)->i64), +(r#"Broadcasts a message to all scripts, except for the emitting script. Messages are received synchronously via the sysCall_msg callback function"#,sim_broadcast_msg,"broadcastMsg",(message:serde_json::Value),opt(options:i64)->()), +(r#"Builds an identity transformation matrix. See also the other matrix/transformation functions"#,sim_build_identity_matrix,"buildIdentityMatrix"->Vec), +(r#"Builds a transformation matrix based on a position vector and Euler angles. See also the section about positions, orientations and transformations"#,sim_build_matrix,"buildMatrix",(position:Vec,euler_angles:Vec)->Vec), +(r#"Deprecated. See sim.poseToMatrix instead"#,sim_build_matrix_q,"buildMatrixQ",(position:Vec,quaternion:Vec)->Vec), +(r#"Builds a pose based on a position vector and Euler angles or axes. See also the section about positions, orientations and transformations"#,sim_build_pose,"buildPose",(position:Vec,euler_angles_or_axis:Vec),opt(mode:i64,axis2:Vec)->Vec), +(r#"Calls a script function (from a plugin, the main client application, or from another script). This represents a user callback inside of a script. The target script must be initialized for this call to succeed, e.g. when calling simulation scripts, then simulation must be running. See also sim.getScriptFunctions and sim.executeScriptString"#,sim_call_script_function,"callScriptFunction",(function_name:String,script_handle:i64),opt(in_arg:serde_json::Value)->serde_json::Value), +(r#"Shifts and adjusts a camera associated with a view to fill the view entirely with the specified objects or models. See also the sim.adjustView and sim.floatingViewAdd functions."#,sim_camera_fit_to_view,"cameraFitToView",(view_handle_or_index:i64),opt(object_handles:Vec,options:i64,scaling:f64)->i64), +(r#" +Changes the color of an entity, and returns its original color. Currently only takes into account collections and shapes. See also sim.restoreEntityColor. "#,sim_change_entity_color,"changeEntityColor",(entity_handle:i64,new_color:Vec),opt(color_component:i64)->Vec), +(r#"Checks whether two entities are colliding. The collidable flags of the entities are overridden if the entities are objects. If the entities are both the same collection (i.e. with the same collection handle), then same objects will not be checked against themselve"#,sim_check_collision,"checkCollision",(entity1_handle:i64,entity2_handle:i64)->(i64,Vec)), +(r#"Checks whether two entities are colliding, and will return all intersections between the two entities. The collidable flags of the entities are overridden if the entities are objects. See also sim.checkCollision."#,sim_check_collision_ex,"checkCollisionEx",(entity1_handle:i64,entity2_handle:i64)->(i64,Vec)), +(r#"Checks the minimum distance between two entities. The measurable flags of the entities are overridden if the entities are objects. If the entities are both the same collection (i.e. with the same collection handle), then same objects will not be checked against themselve."#,sim_check_distance,"checkDistance",(entity1_handle:i64,entity2_handle:i64),opt(threshold:f64)->(i64,Vec,Vec)), +(r#"Checks whether the provided points collide with the OC tree voxels. See also sim.insertVoxelsIntoOctree and the other OC tree related functions."#,sim_check_octree_point_occupancy,"checkOctreePointOccupancy",(octree_handle:i64,options:i64,points:Vec)->(i64,i64,i64,i64)), +(r#"Checks whether the proximity sensor detects the indicated entity. Detection is silent (no visual feedback) compared to sim.handleProximitySensor. Also, the detectable flags of the entity are overridden if the entity is an object. See also sim.readProximitySensor and sim.checkProximitySensorEx."#,sim_check_proximity_sensor,"checkProximitySensor",(sensor_handle:i64,entity_handle:i64)->(i64,f64,Vec,i64,Vec)), +(r#"Checks whether the proximity sensor detects the indicated entity. This is the extended functionality version of sim.checkProximitySensor. Detection is silent (no visual feedback) compared to sim.handleProximitySensor. Also, the detectable flags of the entity are overridden if the entity is an object. see also sim.readProximitySensor and sim.checkProximitySensorEx2."#,sim_check_proximity_sensor_ex,"checkProximitySensorEx",(sensor_handle:i64,entity_handle:i64,mode:i64,threshold:f64,max_angle:f64)->(i64,f64,Vec,i64,Vec)), +(r#"Checks whether the proximity sensor detects the indicated points, segments or triangles. Detection is silent (no visual feedback). See also sim.readProximitySensor and sim.checkProximitySensorEx."#,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)), +(r#"Checks whether the vision sensor detects the indicated entity. Detection is silent (no visual feedback) compared to sim.handleVisionSensor. The vision callback functions will be called on the acquired image. Also, the visibility state of the entity is overridden if the entity is an object. See also sim.readVisionSensor and sim.checkVisionSensorEx."#,sim_check_vision_sensor,"checkVisionSensor",(sensor_handle:i64,entity_handle:i64)->(i64,Vec,Vec)), +(r#"Checks whether the vision sensor detects the indicated entity. This is the extended functionality version of sim.checkVisionSensor. Detection is silent (no visual feedback) compared to sim.handleVisionSensor. The vision callback functions will be called on the acquired image. Also, the visibility state of the entity is overridden if the entity is an object. See also sim.readVisionSensor. "#,sim_check_vision_sensor_ex,"checkVisionSensorEx",(sensor_handle:i64,entity_handle:i64,return_image:bool)->Vec), +(r#"Clears a double signal (removes it). See also the other signal functions."#,sim_clear_float_signal,"clearFloatSignal",(signal_name:String)->()), +(r#"Clears an integer signal (removes it). See also the other signal functions."#,sim_clear_int32_signal,"clearInt32Signal",(signal_name:String)->()), +(r#"Clears a string signal (removes it). See also the other signal functions."#,sim_clear_string_signal,"clearStringSignal",(signal_name:String)->()), +(r#"Closes current scene, and switches to another open scene. If there is no other open scene, a new scene is then created. Can only be called from an add-on, or from the sanbox script, when called from Lua. See also sim.loadScene and sim.saveScene."#,sim_close_scene,"closeScene"->i64), +(r#"Combines two RGB images. See also sim.transformImage."#,sim_combine_rgb_images,"combineRgbImages",(img1:Vec,img1_res:Vec,img2:Vec,img2_res:Vec,operation:i64)->Vec), +(r#"Computes and applies the mass and inertia matrix for a shape, based on its convex representation. When calling this function while the simulation is running, one should then call sim.resetDynamicObject, for the changes to take effect. See also sim.getShapeMassAndInertia and sim.convexDecompose."#,sim_compute_mass_and_inertia,"computeMassAndInertia",(shape_handle:i64,density:f64)->i64), +(r#"Calculates the convex decomposition of a shape using the HACD or V-HACD algorithms. See also sim.getQHull, sim.getDecimatedMesh, sim.ungroupShape and sim.computeMassAndInertia."#,sim_convex_decompose,"convexDecompose",(shape_handle:i64,options:i64,int_params:Vec,float_params:Vec)->i64), +(r#"Copies and pastes objects. See also sim.removeObjects, sim.removeModel, sim.saveModel and sim.loadModel"#,sim_copy_paste_objects,"copyPasteObjects",(object_handles:Vec),opt(options:i64)->Vec), +(r#"Duplicates a table, i.e. makes a deep copy. See also the other packing/unpacking related functions."#,sim_copy_table,"copyTable",(original:Vec)->Vec), +(r#" +Creates a new collection. A collection created in a child script, a customization script or int the main script will be automatically destroyed when the script ends. See also the other functions related to collections."#,sim_create_collection,"createCollection",opt(options:i64)->i64), +(r#"Creates a dummy. "#,sim_create_dummy,"createDummy",(size:f64)->i64), +(r#"Creates a force sensor. "#,sim_create_force_sensor,"createForceSensor",(options:i64,int_params:Vec,float_params:Vec)->i64), +(r#"Creates a heightfield shape. See also sim.createPrimitiveShape, sim.createShape and sim.addParticleObject."#,sim_create_heightfield_shape,"createHeightfieldShape",(options:i64,shading_angle:f64,x_point_count:i64,y_point_count:i64,x_size:f64,heights:Vec)->i64), +(r#"Creates a joint. See also sim.setJointInterval."#,sim_create_joint,"createJoint",(joint_type:i64,joint_mode:i64,options:i64),opt(sizes:Vec)->i64), +(r#"Creates an empty OC tree. See also sim.removeObjects and the other OC tree related functions."#,sim_create_octree,"createOctree",(voxel_size:f64,options:i64,point_size:f64)->i64), +(r#"Creates a path."#,sim_create_path,"createPath",(ctrl_pts:Vec),opt(options:i64,subdiv:i64,smoothness:f64,orientation_mode:i64,up_vector:Vec)->i64), +(r#"Creates an empty point cloud. See also sim.removeObjects, sim.setPointCloudOptions and the other point cloud related functions."#,sim_create_point_cloud,"createPointCloud",(max_voxel_size:f64,max_pt_cnt_per_voxel:i64,options:i64,point_size:f64)->i64), +(r#"Creates a primitive shape. See also sim.createShape and sim.createHeightfieldShape"#,sim_create_primitive_shape,"createPrimitiveShape",(primitive_type:i64,sizes:Vec),opt(options:i64)->i64), +(r#"Creates a proximity sensor. "#,sim_create_proximity_sensor,"createProximitySensor",(sensor_type:i64,sub_type:i64,options:i64,int_params:Vec,float_params:Vec)->i64), +(r#"Creates a mesh shape. See also sim.createPrimitiveShape, sim.createHeightfieldShape and sim.getShapeMesh, and see sim.importMesh for a usage example."#,sim_create_shape,"createShape",(options:i64,shading_angle:f64,vertices:Vec,indices:Vec,normals:Vec,texture_coordinates:Vec,texture:Vec,texture_resolution:Vec)->i64), +(r#"Creates a planar shape, that will be textured with a new, or imported texture. See also sim.getTextureId, sim.readTexture, sim.writeTexture and sim.setShapeTexture."#,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)), +(r#"Creates a vision sensor. "#,sim_create_vision_sensor,"createVisionSensor",(options:i64,int_params:Vec,float_params:Vec)->i64), +(r#" +Removes a collection. See also the other functions related to collections."#,sim_destroy_collection,"destroyCollection",(collection_handle:i64)->()), +(r#"Destroys a graph stream or curve. See also the other functions related to graphs."#,sim_destroy_graph_curve,"destroyGraphCurve",(graph_handle:i64,curve_id:i64)->()), +(r#"Duplicates a graph stream or curve, and freezes it. See also the other functions related to graphs."#,sim_duplicate_graph_curve_to_static,"duplicateGraphCurveToStatic",(graph_handle:i64,curve_id:i64),opt(curve_name:String)->i64), +(r#"Executes some code in a specific script (from a plugin, the main client application, or from another script). The target script must be initialized for this call to succeed, e.g. when calling simulation scripts, then simulation must be running. See also sim.callScriptFunction. +Data exchange between a plugin and a script happens via a stack. Reading and writing arguments from/to the stack gives you a maximum of flexibility, and you wil be able to exchange also complex data structures. But it can also be tedious and error prone. Use instead the helper classes located in programming/include/simStack. +"#,sim_execute_script_string,"executeScriptString",(string_to_execute:String,script_handle:i64)->(i64,serde_json::Value)), +(r#"Exports a mesh to a file. See also sim.importMesh and sim.getShapeMesh"#,sim_export_mesh,"exportMesh",(fileformat:i64,path_and_filename:String,options:i64,scaling_factor:f64,vertices:Vec,indices:Vec)->()), +(r#"Adds a floating view to current page. See also the sim.floatingViewRemove, sim.adjustView and sim.cameraFitToView functions."#,sim_floating_view_add,"floatingViewAdd",(pos_x:f64,pos_y:f64,size_x:f64,size_y:f64,options:i64)->i64), +(r#"Removes a floating view previously added with sim.floatingViewAdd. "#,sim_floating_view_remove,"floatingViewRemove",(floating_view_handle:i64)->i64), +(r#"Generates an extrusion shape from a path. See also the other path related functions."#,sim_generate_shape_from_path,"generateShapeFromPath",(path:Vec,section:Vec),opt(options:i64,up_vector:Vec)->i64), +(r#"Generates a 3D text model."#,sim_generate_text_shape,"generateTextShape",(txt:String),opt(color:Vec,height:f64,centered:bool,alphabet_location:String)->i64), +(r#"Generates a time optimal trajectory, based on the TOPPRA library. See also the other path related functions."#,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)), +(r#"Generates alternative manipulator configurations, for a same end-effector pose, for a manipulator that has revolute joints with a range larger than 360 degrees. The original submitted configuration will be part of the returned configurations."#,sim_get_alternate_configs,"getAlternateConfigs",(joint_handles:Vec,input_config:Vec),opt(tip_handle:i64,low_limits:Vec,ranges:Vec)->Vec), +(r#"Retrieves all API functions and variables that match a specific word. Useful for script code auto-completion functionality. See also sim.getApiInfo. +"#,sim_get_api_func,"getApiFunc",(script_handle:i64,api_word:String)->Vec), +(r#"Returns the call tip (or info text) for an API function. See also sim.getApiFunc. +"#,sim_get_api_info,"getApiInfo",(script_handle:i64,api_word:String)->String), +(r#"Retrieves 3 values from an array parameter. See the array parameter identifiers. See also the other simulator parameter related functions."#,sim_get_array_param,"getArrayParam",(parameter:i64)->Vec), +(r#""#,sim_get_auto_yield_delay,"getAutoYieldDelay"->f64), +(r#"Retrieves a bool parameter. See the bool parameter identifiers. See also the other simulator parameter related functions."#,sim_get_bool_param,"getBoolParam",(parameter:i64)->bool), +(r#"Returns the position or distance along a path that is closest to a specified point in space. See also the other path related functions."#,sim_get_closest_pos_on_path,"getClosestPosOnPath",(path:Vec,path_lengths:Vec,abs_pt:Vec)->f64), +(r#"Retrieves the object handles that compose a collection. See also the other functions related to collections."#,sim_get_collection_objects,"getCollectionObjects",(collection_handle:i64)->Vec), +(r#"Returns the distance between two configurations points. See also the other path related functions."#,sim_get_config_distance,"getConfigDistance",(config_a:Vec,config_b:Vec),opt(metric:Vec,types:Vec)->f64), +(r#"Retrieves contact point information of a dynamic simulation pass. "#,sim_get_contact_info,"getContactInfo",(dynamic_pass:i64,object_handle:i64,index:i64)->(Vec,Vec,Vec,Vec)), +(r#"Retrieves a decimated mesh (i.e. a simplified mesh). See also sim.convexDecompose and sim.getQHull."#,sim_get_decimated_mesh,"getDecimatedMesh",(vertices_in:Vec,indices_in:Vec,decimation_percentage:f64)->(Vec,Vec)), +(r#" +Retrieves a bool value from the physics engine properties. See also the other engine properties setter and getter API functions."#,sim_get_engine_bool_param,"getEngineBoolParam",(param_id:i64,object_handle:i64)->bool), +(r#" +Retrieves a double value from the physics engine properties. See also the other engine properties setter and getter API functions."#,sim_get_engine_float_param,"getEngineFloatParam",(param_id:i64,object_handle:i64)->f64), +(r#" +Retrieves an int32 value from the physics engine properties. See also the other engine properties setter and getter API functions."#,sim_get_engine_int32_param,"getEngineInt32Param",(param_id:i64,object_handle:i64)->i64), +(r#"Retrieves the Euler angles from a transformation matrix. See also the section about positions, orientations and transformations"#,sim_get_euler_angles_from_matrix,"getEulerAnglesFromMatrix",(matrix:Vec)->Vec), +(r#"Retrieves the explicit handling flags for a scene object. See also sim.setExplicitHandling."#,sim_get_explicit_handling,"getExplicitHandling",(object_handle:i64)->i64), +(r#"Retrieves a string that describes additional environment or object properties, mainly used by extension plugins."#,sim_get_extension_string,"getExtensionString",(object_handle:i64,index:i64),opt(key:String)->String), +(r#"Retrieves a floating point parameter. See the floating-point parameter identifiers. See also the other simulator parameter related functions."#,sim_get_float_param,"getFloatParam",(parameter:i64)->f64), +(r#"Retrieves all events that allow to reconstruct a scene's (mostly) visual content remotely"#,sim_get_genesis_events,"getGenesisEvents"->Vec), +(r#""#,sim_get_graph_curve,"getGraphCurve",(graph_handle:i64,graph_type:i64,curve_index:i64)->(String,i64,Vec,Vec,Vec,Vec,i64,i64)), +(r#""#,sim_get_graph_info,"getGraphInfo",(graph_handle:i64)->(i64,Vec,Vec,i64)), +(r#"Retrieves an integer parameter. See the integer parameter identifiers. See also the other simulator parameter related functions."#,sim_get_int32_param,"getInt32Param",(parameter:i64)->i64), +(r#""#,sim_get_is_real_time_simulation,"getIsRealTimeSimulation"->i64), +(r#"Retrieves joint dependency information, when the joint is in dependent mode. See also sim.setJointDependency and sim.getJointMode."#,sim_get_joint_dependency,"getJointDependency",(joint_handle:i64)->(i64,f64,f64)), +(r#"Retrieves the force or torque applied to a joint along/about its active axis. This function retrieves meaningful information only if the joint is prismatic or revolute, and is dynamically enabled. With the Bullet, MuJoCo and Newton engine, this function returns the force or torque applied to the joint motor (torques from joint limits are not taken into account). With the ODE and Vortex engine, this function returns the total force or torque applied to a joint along/about its z-axis. See also sim.setJointTargetForce and sim.readForceSensor."#,sim_get_joint_force,"getJointForce",(joint_handle:i64)->f64), +(r#"Retrieves the interval parameters of a joint. See also sim.setJointInterval."#,sim_get_joint_interval,"getJointInterval",(object_handle:i64)->(bool,Vec)), +(r#"Retrieves the operation mode of a joint. See also sim.setJointMode and sim.getObjectInt32Param with sim.jointintparam_dynctrlmode"#,sim_get_joint_mode,"getJointMode",(joint_handle:i64)->(i64,i64)), +(r#"Retrieves the linear/angular position of a joint. This function cannot be used with spherical joints (use sim.getObjectChildPose instead). See also sim.setJointPosition"#,sim_get_joint_position,"getJointPosition",(object_handle:i64)->f64), +(r#"Retrieves the force or torque that a joint can exert. See also sim.setJointTargetForce and sim.getJointTargetVelocity."#,sim_get_joint_target_force,"getJointTargetForce",(joint_handle:i64)->f64), +(r#"Retrieves the target linear/angular position of a joint. See also sim.setJointTargetPosition"#,sim_get_joint_target_position,"getJointTargetPosition",(object_handle:i64)->f64), +(r#"Retrieves the target linear/angular velocity of a non-spherical joint. See also sim.setJointTargetVelocity"#,sim_get_joint_target_velocity,"getJointTargetVelocity",(object_handle:i64)->f64), +(r#" +Retrieves the type of a joint +"#,sim_get_joint_type,"getJointType",(object_handle:i64)->i64), +(r#"Retrieves the linear or angular velocity of a joint. The velocity is a measured velocity (i.e. from one simulation step to the next), and is available for all joints in the scene."#,sim_get_joint_velocity,"getJointVelocity",(joint_handle:i64)->f64), +(r#"Retrieves and clears the information string generated by last API call"#,sim_get_last_info,"getLastInfo"->String), +(r#" +Retrieves various parameters of a light object. See also sim.setLightParameters. "#,sim_get_light_parameters,"getLightParameters",(light_handle:i64)->(i64,Vec,Vec,Vec)), +(r#"Retrieves the object handle of the dummy linked to this one. See also sim.setLinkDummy."#,sim_get_link_dummy,"getLinkDummy",(dummy_handle:i64)->i64), +(r#"Retrieves persistent data block tags that match a specific pattern. See also sim.getPersistentDataTags"#,sim_get_matching_persistent_data_tags,"getMatchingPersistentDataTags",(pattern:String)->Vec), +(r#"Inverts a transformation matrix. See also the section about positions, orientations and transformations"#,sim_get_matrix_inverse,"getMatrixInverse",(matrix:Vec)->Vec), +(r#"Retrieves the properties of a model. See also sim.setModelProperty, sim.getObjectProperty and sim.getObjectSpecialProperty."#,sim_get_model_property,"getModelProperty",(object_handle:i64)->i64), +(r#"Retrieves a named bool parameter. Accepted values are true, false, on, off, 1 or 0. See also the other simulator named parameter related functions."#,sim_get_named_bool_param,"getNamedBoolParam",(name:String)->bool), +(r#"Retrieves a named double parameter. See also the other simulator named parameter related functions."#,sim_get_named_float_param,"getNamedFloatParam",(name:String)->f64), +(r#"Retrieves a named int parameter. See also the other simulator named parameter related functions."#,sim_get_named_int32_param,"getNamedInt32Param",(name:String)->i64), +(r#"Retrieves a named string or buffer parameter. See also the other simulator named parameter related functions."#,sim_get_named_string_param,"getNamedStringParam",(param_name:String)->Vec), +(r#"Retrieves the navigation and selection mode for the mouse. See also sim.setNavigationMode."#,sim_get_navigation_mode,"getNavigationMode"->i64), +(r#"Retrieves an object handle based on its path and alias. See also sim.isHandle, and sim.getObjectUid."#,sim_get_object,"getObject",(path:String),opt(options:serde_json::Value)->i64), +(r#"Retrieves the alias or path of an object based on its handle. See also sim.setObjectAlias."#,sim_get_object_alias,"getObjectAlias",(object_handle:i64),opt(options:i64)->String), +(r#""#,sim_get_object_alias_relative,"getObjectAliasRelative",(handle:i64,base_handle:i64),opt(options:i64)->String), +(r#"Retrieves the handle of an object's child object. See also sim.getObjectParent and sim.getObjectsInTree."#,sim_get_object_child,"getObjectChild",(object_handle:i64,index:i64)->i64), +(r#"Retrieves the intrinsic or internal transformation of an object. For a joint, this is the transformation caused by the joint movement, mainly. For joints and force sensors, this will also include a possible error transformation caused by the physics engine (a physics engine can cause joints and force sensors to come apart, when constraints can't be perfectly resolved). See also sim.setObjectChildPose and the section about positions, orientations and transformations"#,sim_get_object_child_pose,"getObjectChildPose",(object_handle:i64)->Vec), +(r#" +Retrieves the color of a scene object. See also other rendering related functions. "#,sim_get_object_color,"getObjectColor",(object_handle:i64,index:i64,color_component:i64)->Vec), +(r#"Retrieves a floating-point array parameter of a scene object. See also the other object parameter related functions"#,sim_get_object_float_array_param,"getObjectFloatArrayParam",(object_handle:i64,parameter_id:i64)->Vec), +(r#"Retrieves a floating-point parameter of a scene object. See also the other object parameter related functions"#,sim_get_object_float_param,"getObjectFloatParam",(object_handle:i64,parameter_id:i64)->f64), +(r#"Retrieves an object handle based on its unique identifier. See also sim.getObjectUid."#,sim_get_object_from_uid,"getObjectFromUid",(uid:i64),opt(options:serde_json::Value)->()), +(r#"Retrieves an int32 parameter of a scene object. See also the other object parameter related functions"#,sim_get_object_int32_param,"getObjectInt32Param",(object_handle:i64,parameter_id:i64)->i64), +(r#"Retrieves the transformation matrix of an object. See also sim.setObjectMatrix and the section about positions, orientations and transformations"#,sim_get_object_matrix,"getObjectMatrix",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(r#"Retrieves the orientation (Euler angles) of an object. See also sim.setObjectOrientation and the section about positions, orientations and transformations"#,sim_get_object_orientation,"getObjectOrientation",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(r#"Retrieves the handle of an object's parent object. See also sim.setObjectParent and sim.getObjectChild."#,sim_get_object_parent,"getObjectParent",(object_handle:i64)->i64), +(r#"Retrieves the pose of an object. See also sim.setObjectPose and the section about positions, orientations and transformations"#,sim_get_object_pose,"getObjectPose",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(r#"Retrieves the position of an object. See also sim.setObjectPosition and the section about positions, orientations and transformations"#,sim_get_object_position,"getObjectPosition",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(r#"Retrieves the main properties of a scene object. See also sim.setObjectProperty, sim.getObjectSpecialProperty and sim.getModelProperty."#,sim_get_object_property,"getObjectProperty",(object_handle:i64)->i64), +(r#"Retrieves the quaternion of an object. See also sim.setObjectQuaternion and the section about positions, orientations and transformations"#,sim_get_object_quaternion,"getObjectQuaternion",(object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(r#"Retrieves the handles of selected objects. See also sim.setObjectSel"#,sim_get_object_sel,"getObjectSel"->Vec), +(r#"Retrieves the size factor of a scene object. The size factor is different from the real object size. Use this to be able to adapt to scaling operations. See also the other size and scaling functions."#,sim_get_object_size_factor,"getObjectSizeFactor",(object_handle:i64)->f64), +(r#"Retrieves the special properties of a scene object. See also sim.setObjectSpecialProperty, sim.getObjectProperty and sim.getModelProperty."#,sim_get_object_special_property,"getObjectSpecialProperty",(object_handle:i64)->i64), +(r#"Retrieves a string parameter of a scene object. See also the other object parameter related functions"#,sim_get_object_string_param,"getObjectStringParam",(object_handle:i64,parameter_id:i64)->Vec), +(r#" +Retrieves the type of an object +"#,sim_get_object_type,"getObjectType",(object_handle:i64)->i64), +(r#"Retrieves the unique identifier of an object: throughout a CoppeliaSim session, there won't be two identical unique identifiers. Unique identifiers are however not persistent (i.e. are not saved with the object). See also sim.getObjectfromUid."#,sim_get_object_uid,"getObjectUid",(object_handle:i64)->i64), +(r#"Retrieves the linear and/or angular velocity of an object, in absolute coordinates. The velocity is a measured velocity (i.e. from one simulation step to the next), and is available for all objects in the scene. See also sim.getVelocity."#,sim_get_object_velocity,"getObjectVelocity",(object_handle:i64)->(Vec,Vec)), +(r#"Retrieves object handles. Use this in a loop where index starts at 0 and is incremented to get all object handles in the scene. See also sim.getObjectsInTree."#,sim_get_objects,"getObjects",(index:i64,object_type:i64)->i64), +(r#"Retrieves object handles in a given hierarchy tree. See also sim.getObjects."#,sim_get_objects_in_tree,"getObjectsInTree",(tree_base_handle:i64),opt(object_type:i64,options:i64)->Vec), +(r#"Retrieves voxel positions from an OC tree. See also the other OC tree related functions."#,sim_get_octree_voxels,"getOctreeVoxels",(octree_handle:i64)->Vec), +(r#"Retrieves the current page index (view). See also sim.setPage."#,sim_get_page,"getPage"->i64), +(r#"Returns an interpolated configuration from a path. See also the other path related functions."#,sim_get_path_interpolated_config,"getPathInterpolatedConfig",(path:Vec,path_lengths:Vec,t:f64),opt(method:serde_json::Value,types:Vec)->Vec), +(r#"Returns the lengths of a path in 1, 2 or 3D Cartesian space, even if more coordinates are provided. Each path point will have a corresponding length value (taken as the distance from the path's first point, along the path). See also the other path related functions."#,sim_get_path_lengths,"getPathLengths",(path:Vec,dof:i64),opt(dist_callback:String)->(Vec,f64)), +(r#"Retrieves all persistent data block tags or names. See also sim.getMatchingPersistentDataTags and sim.persistentDataRead"#,sim_get_persistent_data_tags,"getPersistentDataTags"->Vec), +(r#"Returns auxiliary information about a loaded plugin. See also sim.setPluginInfo and sim.getPluginName. +"#,sim_get_plugin_info,"getPluginInfo",(plugin_name:String,info_type:i64)->String), +(r#"Retrieves a plugin name based on an index"#,sim_get_plugin_name,"getPluginName",(index:i64)->String), +(r#"Gets various properties of a point cloud. See also sim.setPointCloudOptions and the other point cloud related functions."#,sim_get_point_cloud_options,"getPointCloudOptions",(point_cloud_handle:i64)->(f64,i64,i64,f64)), +(r#"Retrieves point positions from a point cloud. See also the other point cloud related functions."#,sim_get_point_cloud_points,"getPointCloudPoints",(point_cloud_handle:i64)->Vec), +(r#"Inverts a pose. See also the section about positions, orientations and transformations"#,sim_get_pose_inverse,"getPoseInverse",(pose:Vec)->Vec), +(r#"Retrieves the convex hull mesh from the specified vertices. See also sim.convexDecompose and sim.getDecimatedMesh."#,sim_get_q_hull,"getQHull",(vertices_in:Vec)->(Vec,Vec)), +(r#"Deprecated. See sim.matrixToPose instead"#,sim_get_quaternion_from_matrix,"getQuaternionFromMatrix",(matrix:Vec)->Vec), +(r#"Generates a random value in the range between 0 and 1. The value is generated from an individual generator attached to the calling script (i.e. scripts do not share a common generator as is the case with Lua's math.random function). sim.getRandom has however also been wrapped inside of two new Lua functions, in order to mimic Lua's math.random and math.randomseed: + +--lua + +function math.random2(lower, upper) + local r = sim.getRandom() + if lower then + local b = 1 + local d + if upper then + b = lower + d = upper - b + else + d = lower - b + end + local e = d / (d + 1) + r = b + math.floor(r * d / e) + end + return r +end + +function math.randomseed2(seed) + sim.getRandom(seed) +end +"#,sim_get_random,"getRandom",opt(seed:i64)->f64), +(r#" +Retrieves a list of custom handles, linking a given scene object to other scene objects. See also sim.setReferencedHandles. "#,sim_get_referenced_handles,"getReferencedHandles",(object_handle:i64)->Vec), +(r#"Retrieves an axis and rotation angle that brings one pose or transformation matrix onto another one. The translation part of the poses/matrices is ignored. This function, when used in combination with sim.rotateAroundAxis, can be used to build interpolations between transformation matrices. See also the section about positions, orientations and transformations"#,sim_get_rotation_axis,"getRotationAxis",(matrix_start:Vec,matrix_goal:Vec)->(Vec,f64)), +(r#"Generates a scaled-up or scaled down version of the input image. See also sim.transformImage, sim.loadImage, sim.saveImage and sim.setVisionSensorImg."#,sim_get_scaled_image,"getScaledImage",(image_in:Vec,resolution_in:Vec,desired_resolution_out:Vec,options:i64)->(Vec,Vec)), +(r#"Retrieves the handle of a script."#,sim_get_script,"getScript",(script_type:i64),opt(object_handle:i64,script_name:String)->i64), +(r#"Retrieves a map of another script functions, that can be called. See also sim.callScriptFunction"#,sim_get_script_functions,"getScriptFunctions",(script_handle:i64)->serde_json::Value), +(r#"Retrieves an int32 parameter of a script. See also the other functions related to script parameters."#,sim_get_script_int32_param,"getScriptInt32Param",(script_handle:i64,parameter_id:i64)->i64), +(r#"Retrieves a string parameter of a script. See also the other functions related to script parameters."#,sim_get_script_string_param,"getScriptStringParam",(script_handle:i64,parameter_id:i64)->Vec), +(r#""#,sim_get_setting_bool,"getSettingBool",(key:String)->bool), +(r#""#,sim_get_setting_float,"getSettingFloat",(key:String)->f64), +(r#""#,sim_get_setting_int32,"getSettingInt32",(key:String)->i64), +(r#""#,sim_get_setting_string,"getSettingString",(key:String)->String), +(r#" +Returns the size of a shape's bounding box. See also the other size and scaling functions."#,sim_get_shape_bb,"getShapeBB",(shape_handle:i64)->Vec), +(r#" +Retrieves the color of a shape. See also other rendering related functions. "#,sim_get_shape_color,"getShapeColor",(shape_handle:i64,color_name:String,color_component:i64)->(i64,Vec)), +(r#"Retrieves geometric information related to a shape. See also sim.getShapeMesh."#,sim_get_shape_geom_info,"getShapeGeomInfo",(shape_handle:i64)->(i64,i64,Vec)), +(r#"Retrieves the inertia information from a shape. See also sim.setShapeInertia, sim.getShapeMass and sim.computeMassAndInertia."#,sim_get_shape_inertia,"getShapeInertia",(shape_handle:i64)->(Vec,Vec)), +(r#"Deprecated. Use sim.getShapeMass and sim.getShapeInertia instead."#,sim_get_shape_mass_and_inertia,"getShapeMassAndInertia",(shape_handle:i64)->f64), +(r#"Retrieves a shape's mesh information. See also sim.getShapeViz, sim.createShape and sim.exportMesh for a usage example."#,sim_get_shape_mesh,"getShapeMesh",(shape_handle:i64)->(Vec,Vec,Vec)), +(r#"Retrieves the texture ID of a texture that is applied to a specific shape. See also sim.getTextureId and sim.setShapeTexture."#,sim_get_shape_texture_id,"getShapeTextureId",(shape_handle:i64)->i64), +(r#"Retrieves a shape's visual information."#,sim_get_shape_viz,"getShapeViz",(shape_handle:i64,item_index:i64)->serde_json::Value), +(r#"Returns the signal name at the given index. Use this function in a loop until return is nullptr to read all set signals. See also the other signal functions."#,sim_get_signal_name,"getSignalName",(signal_index:i64,signal_type:i64)->String), +(r#"Retrieves current simulation state. See also the simulation state diagram."#,sim_get_simulation_state,"getSimulationState"->i64), +(r#"Convenience function that returns true when the simulation is about to stop or stopped."#,sim_get_simulation_stopping,"getSimulationStopping"->bool), +(r#"Retrieves the current simulation time"#,sim_get_simulation_time,"getSimulationTime"->f64), +(r#"Retrieves the simulation time step (the simulation time (i.e. not real-time) that passes at each main script simulation pass). This value might not be constant for a given simulation."#,sim_get_simulation_time_step,"getSimulationTimeStep"->f64), +(r#"Retrieves and removes the next message in the C/C++ or Lua message queues. Use this in a while-loop until all messages have been extracted. While the C/C++ interface has one single message queue, each Lua script has its own message queue. The C/C++ version of this function should only be called from the CoppeliaSim client application. A given message queue cannot hold more than 64 messages, unread messages will be discarded."#,sim_get_simulator_message,"getSimulatorMessage"->(i64,Vec,Vec)), +(r#"Lua only. Retrieves and clears the last generated stack traceback for a script. See also simGetLastError and sim.getScript."#,sim_get_stack_traceback,"getStackTraceback",opt(script_handle:i64)->String), +(r#"Retrieves a string parameter. See the string parameter identifiers. See also the other simulator parameter related functions."#,sim_get_string_param,"getStringParam",(parameter:i64)->String), +(r#"Retrieves the system time."#,sim_get_system_time,"getSystemTime"->f64), +(r#"Retrieves the texture ID of a specific texture. See also sim.readTexture, sim.writeTexture and sim.createTexture."#,sim_get_texture_id,"getTextureId",(texture_name:String)->(i64,Vec)), +(r#""#,sim_get_thread_id,"getThreadId"->i64), +(r#"Lua only. Returns all variables, except those set by CoppeliaSim."#,sim_get_user_variables,"getUserVariables"->Vec), +(r#"Retrieves the linear and/or angular velocity of the center of mass of a non-static shape. Data is provided by the selected physics engine. See also sim.getObjectVelocity."#,sim_get_velocity,"getVelocity",(shape_handle:i64)->(Vec,Vec)), +(r#"Reads the depth buffer of a vision sensor. The returned data doesn't make sense if sim.handleVisionSensor wasn't called previously (sim.handleVisionSensor is called by default in the main script if the vision sensor is not tagged as explicit handling). See also other vision sensor related API functions"#,sim_get_vision_sensor_depth,"getVisionSensorDepth",(sensor_handle:i64),opt(options:i64,pos:Vec,size:Vec)->(Vec,Vec)), +(r#"Reads the image of a vision sensor. The returned data doesn't make sense if sim.handleVisionSensor wasn't called previously (sim.handleVisionSensor is called by default in the main script if the vision sensor is not tagged as explicit handling). See also sim.saveImage and other vision sensor related API functions"#,sim_get_vision_sensor_img,"getVisionSensorImg",(sensor_handle:i64),opt(options:i64,rgba_cut_off:f64,pos:Vec,size:Vec)->(Vec,Vec)), +(r#"Returns the resolution of the vision sensor"#,sim_get_vision_sensor_res,"getVisionSensorRes",(sensor_handle:i64)->()), +(r#"Groups (or merges) several shapes into a compound shape (or simple shape). See also sim.ungroupShape, sim.alignShapeBB and sim.relocateShapeFrame"#,sim_group_shapes,"groupShapes",(shape_handles:Vec),opt(merge:bool)->i64), +(r#"Lua only. Calls a specific function in add-ons. sim.handleAddOnScripts should only be called from the main script."#,sim_handle_add_on_scripts,"handleAddOnScripts",(call_type:i64)->i64), +(r#"Lua only. Calls a specific system callback function in child scripts. Child scripts will be executed in a precise order. This function should only be called from the main script."#,sim_handle_child_scripts,"handleChildScripts",(call_type:i64)->i64), +(r#"Handles the dynamics functionality in a scene. This function is not available to add-ons."#,sim_handle_dynamics,"handleDynamics",(delta_time:f64)->i64), +(r#"Lua only. Calls a specific system callback function in child scripts and customization scripts. Child- and customiization scripts will be executed in a precise order. This function should only be called from the main script."#,sim_handle_embedded_scripts,"handleEmbeddedScripts",(call_type:i64)->i64), +(r#"Handles a graph object (i.e. records another value for each curve, given that such value was provided via sim.setGraphStreamValue. See also the other functions related to graphs."#,sim_handle_graph,"handleGraph",(object_handle:i64,simulation_time:f64)->()), +(r#""#,sim_handle_joint_motion,"handleJointMotion"->()), +(r#"Handles (performs sensing, etc. of) a registered proximity sensor object. See also sim.readProximitySensor, sim.checkProximitySensor, sim.checkProximitySensorEx and sim.resetProximitySensor."#,sim_handle_proximity_sensor,"handleProximitySensor",(sensor_handle:i64)->(i64,f64,Vec,i64,Vec)), +(r#"Lua only. Calls a specific function in the sandbox script. sim.handleSandboxScript should only be called from the main script."#,sim_handle_sandbox_script,"handleSandboxScript",(call_type:i64)->()), +(r#"Handles various functionality (e.g. camera tracking during simulation, object velocity calculation, etc.). Should only be called from the main script, as the first instruction in the sensing section. See also sim.handleSimulationStart."#,sim_handle_sensing_start,"handleSensingStart"->()), +(r#"Initializes various functionality (e.g. camera tracking during simulation, object velocity calculation, etc.). Should only be called from the main script, as the first instruction in the initialization section. See also sim.handleSensingStart."#,sim_handle_simulation_start,"handleSimulationStart"->()), +(r#"Handles (performs sensing, etc. of) a vision sensor object. It will (1) clear previous computed image processing data, (2) read an image and (3) perform image processing via the vision callback functions (if the vision sensor is using an external input only (1) will be performed). See also sim.readVisionSensor, sim.checkVisionSensor, sim.checkVisionSensorEx and sim.resetVisionSensor."#,sim_handle_vision_sensor,"handleVisionSensor",(sensor_handle:i64)->(i64,Vec,Vec)), +(r#"Imports a mesh from a file. See also sim.exportMesh, sim.importShape and sim.createShape"#,sim_import_mesh,"importMesh",(fileformat:i64,path_and_filename:String,options:i64,identical_vertice_tolerance:f64,scaling_factor:f64)->(Vec,Vec)), +(r#"Imports a shape from a file (first imports meshes, then groups/merges them into a shape). See also sim.importMesh."#,sim_import_shape,"importShape",(fileformat:i64,path_and_filename:String,options:i64,identical_vertice_tolerance:f64,scaling_factor:f64)->i64), +(r#"Initializes/reinitializes a script. Cannot be called from within the script being reinitialized."#,sim_init_script,"initScript",(script_handle:i64)->bool), +(r#"Inserts an object into an OC tree, as voxels. Each voxel will store a color and a tag value. See also sim.subtractObjectFromOctree, sim.insertVoxelsIntoOctree and the other OC tree related functions."#,sim_insert_object_into_octree,"insertObjectIntoOctree",(octree_handle:i64,object_handle:i64,options:i64),opt(color:Vec,tag:i64)->i64), +(r#"Inserts an object into a point cloud, as points. See also sim.insertPointsIntoPointCloud and the other point cloud related functions."#,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), +(r#"Inserts points into a point cloud. See also sim.removePointsFromPointCloud and the other point cloud related functions."#,sim_insert_points_into_point_cloud,"insertPointsIntoPointCloud",(point_cloud_handle:i64,options:i64,points:Vec),opt(color:Vec,duplicate_tolerance:f64)->i64), +(r#"Inserts voxels into an OC tree. Each voxel will store a color and a tag value. See also sim.removeVoxelsFromOctree and the other OC tree related functions."#,sim_insert_voxels_into_octree,"insertVoxelsIntoOctree",(octree_handle:i64,options:i64,points:Vec),opt(color:Vec,tag:Vec)->i64), +(r#"Computes the interpolated transformation matrix between matrixIn1 and matrixIn2. Quaternions are used internally. See also the section about positions, orientations and transformations"#,sim_interpolate_matrices,"interpolateMatrices",(matrix_in1:Vec,matrix_in2:Vec,interpol_factor:f64)->Vec), +(r#"Computes the interpolated pose between poseIn1 and poseIn2. See also the section about positions, orientations and transformations"#,sim_interpolate_poses,"interpolatePoses",(pose_in1:Vec,pose_in2:Vec,interpol_factor:f64)->Vec), +(r#"Removes points from a point cloud, that do not intersect with the provided points (i.e. the result in the point cloud will be the intersection between the two sets of points). When a point cloud doesn't use an OC tree calculation structure, then this operation cannot be performed. See also sim.insertPointsIntoPointCloud, sim.setPointCloudOptions and the other point cloud related functions."#,sim_intersect_points_with_point_cloud,"intersectPointsWithPointCloud",(point_cloud_handle:i64,options:i64,points:Vec,tolerance:f64)->i64), +(r#"Deprecated (yes, what an irony!). Returns 0"#,sim_is_deprecated,"isDeprecated",(func_or_const:String)->i64), +(r#"Checks whether a scene object is dynamically enabled, i.e. is being handled and simulated by the physics engine. Note that until the physics engine has parsed the scene in the first simulation step (i.e. the first time sim.handleDynamics is called), no object will be dynamically enabled."#,sim_is_dynamically_enabled,"isDynamicallyEnabled",(object_handle:i64)->bool), +(r#"Checks whether a general object handle is still valid. When a general object is destroyed (e.g. programmatically or via the user interface), then its related handle is not valid anymore and will trigger an error when used. Use this function to avoid triggering an error. See also sim.getObject."#,sim_is_handle,"isHandle",(object_handle:i64)->bool), +(r#"Launches an executable. Similar to os.execute or io.popen, but is system independent."#,sim_launch_executable,"launchExecutable",(filename:String),opt(parameters:String,show_status:i64)->()), +(r#"Loads an image from file or memory. See also sim.saveImage, sim.getScaledImage, sim.transformImage and sim.setVisionSensorImg."#,sim_load_image,"loadImage",(options:i64,filename:String)->(Vec,Vec)), +(r#"Loads a previously saved model, and selects it. See also sim.saveModel, sim.loadScene, and sim.setBoolParam with sim.boolparam_scene_and_model_load_messages."#,sim_load_model,"loadModel",(filename:String)->i64), +(r#"Loads a previously saved scene.See also sim.saveScene, sim.loadModel, simCloseScene and sim.setBoolParam with sim.boolparam_scene_and_model_load_messages. "#,sim_load_scene,"loadScene",(filename:String)->()), +(r#"Converts a transformation matrix to a pose. See also the section about positions, orientations and transformations"#,sim_matrix_to_pose,"matrixToPose",(matrix:Vec)->Vec), +(r#"Creates, modifies or destroys module menu entries. Those are user selectable items located in [Menu bar > Modules]. When selected, the corresponding script will have its sysCall_moduleEntry callback function triggered, or sim_message_eventcallback_moduleentry triggered."#,sim_module_entry,"moduleEntry",(handle:i64),opt(label:String,state:i64)->i64), +(r#"Generates joint movement data using the Ruckig online trajectory generator. This function can only be called from scripts running in a thread, since this is a blocking operation. See also sim.moveToPose, and sim.ruckigPos."#,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)), +(r#"Generates object movement data using the Ruckig online trajectory generator, by performing interpolations between two poses. The function can operate by handling 4 movement variables (x,y,z and angle between the two poses), or a single movement variable (t, which requires a metric to be specified for distance calculation between the two poses). This function can only be called from a script running in a thread, since this is a blocking operation. See also sim.moveToConfig, and sim.ruckigPos."#,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)), +(r#"Multiplies two transformation matrices. See also the section about positions, orientations and transformations"#,sim_multiply_matrices,"multiplyMatrices",(matrix_in1:Vec,matrix_in2:Vec)->Vec), +(r#"Multiplies two poses. See also the section about positions, orientations and transformations"#,sim_multiply_poses,"multiplyPoses",(pose_in1:Vec,pose_in2:Vec)->Vec), +(r#"Multiplies a vector with a pose or a matrix (e.g. v=m*v). See also the section about positions, orientations and transformations"#,sim_multiply_vector,"multiplyVector",(matrix:Vec,in_vectors:Vec)->Vec), +(r#"Packs a table of double floating-point numbers into a string. See also sim.unpackDoubleTable and the other packing/unpacking functions."#,sim_pack_double_table,"packDoubleTable",(double_numbers:Vec),opt(start_double_index:i64,double_count:i64)->Vec), +(r#"Packs a table of floating-point numbers into a string. See also sim.unpackFloatTable and the other packing/unpacking functions."#,sim_pack_float_table,"packFloatTable",(float_numbers:Vec),opt(start_float_index:i64,float_count:i64)->Vec), +(r#" +Packs a table of int32 numbers into a string. See also sim.unpackInt32Table and the other packing/unpacking functions."#,sim_pack_int32_table,"packInt32Table",(int32_numbers:Vec),opt(start_int32_index:i64,int32_count:i64)->Vec), +(r#"Packs a table into a buffer. The table may contain other nested tables, nil, bool, number or string values. All other types (e.g. functions) will be considered as string or nil values. You can also use sim.packTable to quickly compare two tables or to perform a deep copy of a table. See also sim.unpackTable, the other stack functions and the other packing/unpacking functions."#,sim_pack_table,"packTable",(a_table:Vec),opt(scheme:i64)->Vec), +(r#" +Packs a table of uint16 numbers into a string. See also sim.unpackUInt16Table and the other packing/unpacking functions. "#,sim_pack_u_int16_table,"packUInt16Table",(uint16_numbers:Vec),opt(start_uint16_index:i64,uint16_count:i64)->Vec), +(r#" +Packs a table of uint32 numbers into a string. See also sim.unpackUInt32Table and the other packing/unpacking functions."#,sim_pack_u_int32_table,"packUInt32Table",(uint32_numbers:Vec),opt(start_u_int32_index:i64,uint32_count:i64)->Vec), +(r#"Packs a table of uint8 numbers into a string. See also sim.unpackUInt8Table and the other packing/unpacking functions."#,sim_pack_u_int8_table,"packUInt8Table",(uint8_numbers:Vec),opt(start_uint8_index:i64,uint8count:i64)->Vec), +(r#"Requests a pause of a simulation. See also sim.startSimulation, sim.stopSimulation and sim.getSimulationState. See also the simulation state diagram."#,sim_pause_simulation,"pauseSimulation"->i64), +(r#"Reads a block of persistent data. See also sim.persistentDataWrite, sim.getPersistentDataTags, sim.getStringSignal, sim.getInt32Signal, sim.getFloatSignal and sim.readCustomDataBlock."#,sim_persistent_data_read,"persistentDataRead",(data_tag:String)->Vec), +(r#"Writes a persistent data block. Persistent data, valid across all opened simulator scenes, remains until the simulator ends, or until it is cleared by writing an empty data block. If the options flag is set appropriately, then persistent data can also be stored on file, and be automatically reloaded next time CoppeliaSim starts. See also sim.persistentDataRead, sim.setStringSignal, sim.setInt32Signal, sim.setFloatSignal and sim.writeCustomDataBlock."#,sim_persistent_data_write,"persistentDataWrite",(data_tag:String,data_value:Vec),opt(options:i64)->()), +(r#"Converts a pose to a transformation matrix. See also the section about positions, orientations and transformations"#,sim_pose_to_matrix,"poseToMatrix",(pose:Vec)->Vec), +(r#"Pushes a user-triggered event. Messages are received asynchronously via the sysCall_event callback function and via the plugin sim_message_eventcallback_events message call"#,sim_push_user_event,"pushUserEvent",(event:String,handle:i64,uid:i64,event_data:serde_json::Value),opt(options:i64)->()), +(r#"Triggers a quit signal that will eventually quits the application"#,sim_quit_simulator,"quitSimulator"->()), +(r#"Reads custom data that is stored inside of an object or the scene. Reads also custom data for the application's currrent session. See also the other custom data block related functions and the data packing/unpacking functions."#,sim_read_custom_data_block,"readCustomDataBlock",(object_handle:i64,tag_name:String)->Vec), +(r#""#,sim_read_custom_data_block_ex,"readCustomDataBlockEx",(handle:i64,tag_name:String),opt(options:serde_json::Value)->()), +(r#"Reads the tags of all custom data that is stored inside of an object, a scene, or the application. See also sim.readCustomDataBlock."#,sim_read_custom_data_block_tags,"readCustomDataBlockTags",(object_handle:i64)->Vec), +(r#"Reads custom table data that is stored inside of an object or the scene. Reads also custom table data for the application's currrent session. See also the other custom data block related functions."#,sim_read_custom_table_data,"readCustomTableData",(handle:i64,tag_name:String),opt(options:serde_json::Value)->()), +(r#"Reads the force and torque applied to a force sensor (filtered values are read). See also sim.getJointForce."#,sim_read_force_sensor,"readForceSensor",(object_handle:i64)->(i64,Vec,Vec)), +(r#"Reads the state of a proximity sensor. This function doesn't perform detection, it merely reads the result from a previous call to sim.handleProximitySensor (sim.handleProximitySensor is called in the default main script). See also sim.checkProximitySensor, sim.checkProximitySensorEx and sim.resetProximitySensor."#,sim_read_proximity_sensor,"readProximitySensor",(sensor_handle:i64)->(i64,f64,Vec,i64,Vec)), +(r#"Retrieves the RGB data (or a portion of it) related to a specific texture. See also sim.getTextureId, sim.writeTexture and sim.createTexture."#,sim_read_texture,"readTexture",(texture_id:i64,options:i64),opt(pos_x:i64,pos_y:i64,size_x:i64,size_y:i64)->Vec), +(r#"Reads the state of a vision sensor. This function doesn't perform detection, it merely reads the result from a previous call to sim.handleVisionSensor (sim.handleVisionSensor is called in the default main script). See also sim.checkVisionSensor, sim.checkVisionSensorEx and sim.resetVisionSensor."#,sim_read_vision_sensor,"readVisionSensor",(sensor_handle:i64)->(i64,Vec,Vec)), +(r#"Refreshes CoppeliaSim's internal dialogs. Calling sim.refreshDialogs will not trigger a sim.message_eventcallback_refreshdialogs message"#,sim_refresh_dialogs,"refreshDialogs",(refresh_degree:i64)->i64), +(r#"Counterpart function to sim.acquireLock. Unlocking is cumulative"#,sim_release_lock,"releaseLock"->()), +(r#"Repositions and reorients the reference frame of a shape, while keeping the mesh in place. The shape's inertia properties are unaffected. See also sim.alignShapeBB"#,sim_relocate_shape_frame,"relocateShapeFrame",(shape_handle:i64,pose:Vec)->i64), +(r#"Removes a previously added drawing object. See also sim.addDrawingObject and sim.addDrawingObjectItem"#,sim_remove_drawing_object,"removeDrawingObject",(drawing_object_handle:i64)->()), +(r#"Removes a model from the scene. See also sim.removeObjects. +Object destruction always tries to destroy attached scripts before destroying the object itself. If a script tries to destroy the object it is attached to, then the object will first be destroyed, and the script destruction will be delayed. +"#,sim_remove_model,"removeModel",(object_handle:i64)->i64), +(r#"Removes one or several objects from the scene. See also sim.removeModel. +Object destruction always tries to destroy attached scripts before destroying the object itself. If a script tries to destroy the object it is attached to, then the object will first be destroyed, and the script destruction will be delayed. +"#,sim_remove_objects,"removeObjects",(object_handles:Vec)->()), +(r#"Removes a previously added particle object. See also sim.addParticleObject and sim.addParticleObjectItem"#,sim_remove_particle_object,"removeParticleObject",(particle_object_handle:i64)->()), +(r#"Removes points from a point cloud. When a point cloud doesn't use an OC tree calculation structure, then individual points cannot be removed, only all points can be removed in that case. See also sim.insertPointsIntoPointCloud, sim.setPointCloudOptions and the other point cloud related functions."#,sim_remove_points_from_point_cloud,"removePointsFromPointCloud",(point_cloud_handle:i64,options:i64,points:Vec,tolerance:f64)->i64), +(r#""#,sim_remove_referenced_objects,"removeReferencedObjects",(object_handle:i64)->()), +(r#"Removes a script. Not all script types can be removed, and it will also depend on whether simulation is running or not. See also sim.addScript."#,sim_remove_script,"removeScript",(script_handle:i64)->()), +(r#"Removes voxels from an OC tree. See also sim.insertVoxelsIntoOctree and the other OC tree related functions."#,sim_remove_voxels_from_octree,"removeVoxelsFromOctree",(octree_handle:i64,options:i64,points:Vec)->i64), +(r#"Returns a resampled path. See also the other path related functions."#,sim_resample_path,"resamplePath",(path:Vec,path_lengths:Vec,final_config_cnt:i64),opt(method:serde_json::Value,types:Vec)->Vec), +(r#"Dynamically resets an object that is dynamically simulated. This means that the object representation in the dynamics engine is removed, and added again. This can be useful when the set-up of a dynamically simulated chain needs to be modified during simulation (e.g. joint or shape attachement position/orientation changed)."#,sim_reset_dynamic_object,"resetDynamicObject",(object_handle:i64)->()), +(r#"Resets a graph object (i.e. clears all its data streams). See also the other functions related to graphs."#,sim_reset_graph,"resetGraph",(object_handle:i64)->()), +(r#"Clears the detection state, detection color, detection segments, etc. of a proximity sensor object. See also sim.handleProximitySensor."#,sim_reset_proximity_sensor,"resetProximitySensor",(object_handle:i64)->()), +(r#"Clears the detection state, etc. of a proximity sensor object. See also sim.handleVisionSensor."#,sim_reset_vision_sensor,"resetVisionSensor",(sensor_handle:i64)->()), +(r#" +Restores the color of an entity, previously modified with sim.changeEntityColor."#,sim_restore_entity_color,"restoreEntityColor",(original_color_data:Vec)->()), +(r#"Rotates a pose or transformation matrix around a random axis in space. This function, when used in combination with sim.getRotationAxis, can be used to build interpolations between poses or transformation matrices. See also the section about positions, orientations and transformations"#,sim_rotate_around_axis,"rotateAroundAxis",(matrix_in:Vec,axis:Vec,axis_pos:Vec,angle:f64)->Vec), +(r#"Executes a call to the Ruckig online trajectory generator. The Ruckig online trajectory generator provides instantaneous trajectory generation capabilities for motion control systems. This function prepares a position-based trajectory generation object, that can then be calculated with sim.ruckigStep. When this object is not needed anymore, remove it with sim.ruckigRemove. See also sim.ruckigVel, sim.moveToPose and sim.moveToConfig."#,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), +(r#"Removes an object previously created via sim.ruckigPos or sim.ruckigVel."#,sim_ruckig_remove,"ruckigRemove",(handle:i64)->()), +(r#"Executes a call to the Ruckig online trajectory generator. The Ruckig online trajectory generator provides instantaneous trajectory generation capabilities for motion control systems. This function steps forward a trajectory generation algorithm previously prepared via sim.ruckigPos or sim.ruckigVel."#,sim_ruckig_step,"ruckigStep",(handle:i64,cycle_time:f64)->(i64,Vec,f64)), +(r#"Executes a call to the Ruckig online trajectory generator. The Ruckig online trajectory generator provides instantaneous trajectory generation capabilities for motion control systems. This function prepares a velocity-based trajectory generation object, that can then be calculated with sim.ruckigStep. When this object is not needed anymore, remove it with sim.ruckigRemove. See also sim.ruckigPos."#,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), +(r#"Saves an image to file or to memory. See also sim.loadImage, sim.getScaledImage and sim.getVisionSensorImg."#,sim_save_image,"saveImage",(image:Vec,resolution:Vec,options:i64,filename:String,quality:i64)->Vec), +(r#"Saves a model (an object marked as "Object is model base" and all other objects in its hierarchy tree). Any existing file with same name will be overwritten. See also sim.loadModel, and sim.saveScene."#,sim_save_model,"saveModel",(model_base_handle:i64,filename:String)->()), +(r#"Saves a scene. Any existing file with same name will be overwritten. See also sim.loadScene, simCloseScene, and sim.saveModel."#,sim_save_scene,"saveScene",(filename:String)->()), +(r#" +Scales specified objects in a non-isometric fashion, if possible. Only non-compound shapes can be non-isometrically scaled. Some primitive shapes can have some constraints between their axes. See also the other size and scaling functions."#,sim_scale_object,"scaleObject",(object_handle:i64,x_scale:f64,y_scale:f64,z_scale:f64),opt(options:i64)->()), +(r#" +Scales specified objects. All related values are automatically scaled appropriately (e.g. masses, forces, etc.). See also the other size and scaling functions."#,sim_scale_objects,"scaleObjects",(object_handles:Vec,scaling_factor:f64,scale_positions_too:bool)->()), +(r#" +Lua only. Reads how many bytes are waiting to be read on a serial port (RS-232). See also sim.serialRead. "#,sim_serial_check,"serialCheck",(port_handle:i64)->i64), +(r#" +Lua only. Closes a serial port (RS-232). See also sim.serialOpen. "#,sim_serial_close,"serialClose",(port_handle:i64)->()), +(r#"Lua only. Opens a serial port (RS-232) for communication. When called from a script, the function can only be called when the simulation is running (and in that case the port is automatically closed at simulation stop). See also sim.serialClose, sim.serialSend, sim.serialCheck and sim.serialRead."#,sim_serial_open,"serialOpen",(port_string:String,baudrate:i64)->i64), +(r#"Lua only. Reads from a previously opened serial port (RS-232). The C version of the function cannot be blocking. See also sim.serialCheck and sim.serialSend."#,sim_serial_read,"serialRead",(port_handle:i64,data_length_to_read:i64,blocking_operation:bool),opt(closing_string:Vec,timeout:f64)->Vec), +(r#"Lua only. Writes data to a previously opened serial port (RS-232). See also sim.serialRead."#,sim_serial_send,"serialSend",(port_handle:i64,data:Vec)->i64), +(r#"Sets 3 values of an array parameter. See also the other simulator parameter related functions."#,sim_set_array_param,"setArrayParam",(parameter:i64,array_of_values:Vec)->()), +(r#"Allows specifying a thread interruption or yield delay, that will be automatically enforced by the system (preemptive threading). By default this value is 2 ms. For complete control over thread yielding, see also the other thread related functions."#,sim_set_auto_yield_delay,"setAutoYieldDelay",(dt:f64)->()), +(r#"Sets a bool parameter. See also the other simulator parameter related functions."#,sim_set_bool_param,"setBoolParam",(parameter:i64,bool_state:bool)->()), +(r#" +Sets a bool-type physics engine property. You might have to call sim.resetDynamicObject for changes to take effect. See also the other engine properties setter and getter API functions."#,sim_set_engine_bool_param,"setEngineBoolParam",(param_id:i64,object_handle:i64,bool_param:bool)->()), +(r#" +Sets a double-type physics engine property. You might have to call sim.resetDynamicObject for changes to take effect. See also the other engine properties setter and getter API functions."#,sim_set_engine_float_param,"setEngineFloatParam",(param_id:i64,object_handle:i64,float_param:f64)->()), +(r#" +Sets an int32-type physics engine property. You might have to call sim.resetDynamicObject for changes to take effect. See also the other engine properties setter and getter API functions."#,sim_set_engine_int32_param,"setEngineInt32Param",(param_id:i64,object_handle:i64,int32_param:i64)->()), +(r#"Sets the explicit handling flags for a scene object. See also sim.getExplicitHandling."#,sim_set_explicit_handling,"setExplicitHandling",(object_handle:i64,explicit_handling_flags:i64)->()), +(r#"Sets a floating point parameter. See also the other simulator parameter related functions."#,sim_set_float_param,"setFloatParam",(parameter:i64,float_state:f64)->()), +(r#"Sets the value of a double signal. A signal created in a child script, a customization script or int the main script will be automatically cleared when the script ends. See also the other signal functions."#,sim_set_float_signal,"setFloatSignal",(signal_name:String,signal_value:f64)->()), +(r#"Applies a transformation to a graph stream. See also the other functions related to graphs."#,sim_set_graph_stream_transformation,"setGraphStreamTransformation",(graph_handle:i64,stream_id:i64,tr_type:i64),opt(mult:f64,off:f64,mov_avg_period:i64)->()), +(r#"Sets the next value to be recorded for a graph stream. See also the other functions related to graphs."#,sim_set_graph_stream_value,"setGraphStreamValue",(graph_handle:i64,stream_id:i64,value:f64)->()), +(r#"Sets an integer parameter. See also the other simulator parameter related functions."#,sim_set_int32_param,"setInt32Param",(parameter:i64,int_state:i64)->()), +(r#"Sets the value of an integer signal. A signal created in a child script, a customization script or int the main script will be automatically cleared when the script ends. See also the other signal functions."#,sim_set_int32_signal,"setInt32Signal",(signal_name:String,signal_value:i64)->()), +(r#"Sets a joint dependent of another joint. The dependent joint should first be set into dependent mode via sim.setJointMode. See also sim.getJointDependency."#,sim_set_joint_dependency,"setJointDependency",(joint_handle:i64,master_joint_handle:i64,offset:f64,mult_coeff:f64)->()), +(r#"Sets the interval parameters of a joint (i.e. range values). The attributes or interval parameters might have no effect, depending on the joint-type. See also sim.getJointInterval."#,sim_set_joint_interval,"setJointInterval",(object_handle:i64,cyclic:bool,interval:Vec)->()), +(r#"Sets the operation mode of a joint. See also sim.getJointMode and sim.setJointDependency."#,sim_set_joint_mode,"setJointMode",(joint_handle:i64,joint_mode:i64,options:i64)->()), +(r#"Sets the linear/angular position of a joint. Cannot be used with spherical joints (use sim.setObjectChildPose instead). See also sim.getJointPosition and sim.setJointTargetPosition"#,sim_set_joint_position,"setJointPosition",(object_handle:i64,position:f64)->()), +(r#"Sets the force or torque that a joint can exert. See also sim.getJointTargetForce, sim.getJointForce and sim.setJointTargetVelocity."#,sim_set_joint_target_force,"setJointTargetForce",(object_handle:i64,force_or_torque:f64),opt(signed_value:bool)->()), +(r#"Sets the target linear/angular position of a joint. When in kinematic mode, the joint will move according to a motion profile that respects maximum velocity, acceleration and jerk values. In dynamic and position/custom control mode, the controller is instructed about the desired position. See also sim.getJointTargetPosition and sim.setJointPosition."#,sim_set_joint_target_position,"setJointTargetPosition",(object_handle:i64,target_position:f64),opt(motion_params:Vec)->()), +(r#"Sets the target linear/angular velocity of a non-spherical joint. When in kinematic mode, the joint will move according to a motion profile that respects maximum acceleration and jerk values. In dynamic and velocity control mode, the controller is instructed about the desired velocity. See also sim.getJointTargetVelocity."#,sim_set_joint_target_velocity,"setJointTargetVelocity",(object_handle:i64,target_velocity:f64),opt(motion_params:Vec)->()), +(r#"Sets various parameters of a light object. See also sim.getLightParameters."#,sim_set_light_parameters,"setLightParameters",(light_handle:i64,state:i64,reserved:Vec,diffuse_part:Vec,specular_part:Vec)->()), +(r#"Defines (or breaks) a dummy-dummy link pair. Useful to create dynamic loop closure constraints on the fly (among others). See also sim.getLinkDummy."#,sim_set_link_dummy,"setLinkDummy",(dummy_handle:i64,link_dummy_handle:i64)->()), +(r#"Sets the properties of a model. See also sim.getModelProperty, sim.setObjectProperty and sim.setObjectSpecialProperty."#,sim_set_model_property,"setModelProperty",(object_handle:i64,property:i64)->()), +(r#""#,sim_set_named_bool_param,"setNamedBoolParam",(name:String,value:bool)->()), +(r#""#,sim_set_named_float_param,"setNamedFloatParam",(name:String,value:f64)->()), +(r#""#,sim_set_named_int32_param,"setNamedInt32Param",(name:String,value:i64)->()), +(r#"Sets a named string or buffer parameter. See also the other simulator named parameter related functions."#,sim_set_named_string_param,"setNamedStringParam",(param_name:String,string_param:Vec)->()), +(r#"Sets the navigation and selection mode for the mouse. See also sim.getNavigationMode."#,sim_set_navigation_mode,"setNavigationMode",(navigation_mode:i64)->()), +(r#"Sets the alias of an object. See also sim.getObjectAlias."#,sim_set_object_alias,"setObjectAlias",(object_handle:i64,object_alias:String)->()), +(r#"Can be used to set a spherical joint's rotational transformation (the translational part is ignored). See also sim.getObjectChildPose and the section about positions, orientations and transformations"#,sim_set_object_child_pose,"setObjectChildPose",(object_handle:i64,pose:Vec)->()), +(r#" +Sets the color of a scene object. See also other rendering related functions. "#,sim_set_object_color,"setObjectColor",(object_handle:i64,index:i64,color_component:i64,rgb_data:Vec)->bool), +(r#"Sets a floating-point array parameter of a scene object. See also the other object parameter related functions"#,sim_set_object_float_array_param,"setObjectFloatArrayParam",(object_handle:i64,parameter_id:i64,params:Vec)->()), +(r#"Sets a floating-point parameter of a scene object. See also the other object parameter related functions"#,sim_set_object_float_param,"setObjectFloatParam",(object_handle:i64,parameter_id:i64,parameter:f64)->()), +(r#"Sets an int32 parameter of a scene object. See also the other object parameter related functions"#,sim_set_object_int32_param,"setObjectInt32Param",(object_handle:i64,parameter_id:i64,parameter:i64)->()), +(r#"Sets the transformation matrix of an object. Dynamically simulated objects, together with their hierarchy tree, will be dynamically reset (this however does not apply to static shapes). See also sim.getObjectMatrix and the section about positions, orientations and transformations"#,sim_set_object_matrix,"setObjectMatrix",(object_handle:i64,matrix:Vec),opt(relative_to_object_handle:i64)->()), +(r#"Sets the orientation (Euler angles) of an object. Dynamically simulated objects, together with their hierarchy tree, will be dynamically reset (this however does not apply to static shapes). See also sim.getObjectOrientation and the section about positions, orientations and transformations"#,sim_set_object_orientation,"setObjectOrientation",(object_handle:i64,euler_angles:Vec),opt(relative_to_object_handle:i64)->()), +(r#"Sets an object's parent object. Dynamically simulated objects, together with their hierarchy tree, will be dynamically reset (this however does not apply to static shapes). See also sim.getObjectParent."#,sim_set_object_parent,"setObjectParent",(object_handle:i64,parent_object_handle:i64),opt(keep_in_place:bool)->()), +(r#"Sets the pose of an object. Dynamically simulated objects, together with their hierarchy tree, will be dynamically reset (this however does not apply to static shapes). See also sim.getObjectPose and the section about positions, orientations and transformations"#,sim_set_object_pose,"setObjectPose",(object_handle:i64,pose:Vec),opt(relative_to_object_handle:i64)->()), +(r#"Sets the position (x, y and z-coordinates) of an object. Dynamically simulated objects, together with their hierarchy tree, will be dynamically reset (this however does not apply to static shapes). See also sim.getObjectPosition and the section about positions, orientations and transformations"#,sim_set_object_position,"setObjectPosition",(object_handle:i64,position:Vec),opt(relative_to_object_handle:i64)->()), +(r#"Sets the properties of a scene object. See also sim.getObjectProperty, sim.setObjectSpecialProperty and sim.setModelProperty."#,sim_set_object_property,"setObjectProperty",(object_handle:i64,property:i64)->()), +(r#"Sets the quaternion of an object. Dynamically simulated objects, together with their hierarchy tree, will be dynamically reset (this however does not apply to static shapes). See also sim.getObjectQuaternion and the section about positions, orientations and transformations"#,sim_set_object_quaternion,"setObjectQuaternion",(object_handle:i64,quaternion:Vec),opt(relative_to_object_handle:i64)->()), +(r#"Sets the object selection state. See also sim.getObjectSel"#,sim_set_object_sel,"setObjectSel",(object_handles:Vec)->()), +(r#"Sets the special properties of a scene object. See also sim.getObjectSpecialProperty, sim.setObjectProperty and sim.setModelProperty."#,sim_set_object_special_property,"setObjectSpecialProperty",(object_handle:i64,property:i64)->()), +(r#"Sets a string parameter of a scene object. See also the other object parameter related functions"#,sim_set_object_string_param,"setObjectStringParam",(object_handle:i64,parameter_id:i64,parameter:Vec)->()), +(r#"Switches between pages (main scene views). See also sim.getPage."#,sim_set_page,"setPage",(page_index:i64)->()), +(r#"Attaches additional information to a loaded plugin. See also sim.getPluginInfo. +"#,sim_set_plugin_info,"setPluginInfo",(plugin_name:String,info_type:i64,info:String)->()), +(r#"Sets various properties of a point cloud. See also sim.getPointCloudOptions and the other point cloud related functions."#,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)->()), +(r#" +Attaches a list of custom handles to a given scene object. Those custom handles are handles of other scene objects, that are linked to the given scene object (for whatever purpose). The advantage of storing references to other objects with this function is that CoppeliaSim will take care of correctly adjusting the references if needed: For instance, imagine objectA storing the handle of objectB via this function. If objectB is deleted, then the stored handle will become -1. If objectA and objectB are duplicated at the same time, then the duplicate of objectA will store the handle of the duplicate of objectB. Optionally, if sim.handleflag_keeporiginal is specified, then linking to original objects is guaranteed, e.g. in above example, after a duplication of objectA, the duplicate of objectA will store the handle of the original objectB (if objectB still exists). See also sim.getReferencedHandles. "#,sim_set_referenced_handles,"setReferencedHandles",(object_handle:i64,referenced_handles:Vec)->()), +(r#"Sets an int32 parameter of a script. See also the other functions related to script parameters."#,sim_set_script_int32_param,"setScriptInt32Param",(script_handle:i64,parameter_id:i64,parameter:i64)->()), +(r#"Sets a string parameter of a script. See also the other functions related to script parameters."#,sim_set_script_string_param,"setScriptStringParam",(script_handle:i64,parameter_id:i64,parameter:Vec)->()), +(r#"Sets the size of a shape's bounding box, effectively scaling the shape. Non-isometric scaling is not always possible. See also the other size and scaling functions."#,sim_set_shape_bb,"setShapeBB",(shape_handle:i64,size:Vec)->()), +(r#" +Sets the color of a shape. See also other rendering related functions. "#,sim_set_shape_color,"setShapeColor",(shape_handle:i64,color_name:String,color_component:i64,rgb_data:Vec)->()), +(r#"Applies a new inertia matrix to a shape. If simulation is running, the shape will be dynamically reset (similar to calling sim.resetDynamicObject right after). See also sim.getShapeInertia, sim.setShapeMass and sim.computeMassAndInertia."#,sim_set_shape_inertia,"setShapeInertia",(shape_handle:i64,inertia_matrix:Vec,transformation_matrix:Vec)->()), +(r#"Applies a new mass value to a shape. If simulation is running, the shape will be dynamically reset (similar to calling sim.resetDynamicObject right after). See also sim.getShapeMass, sim.setShapeInertia and sim.computeMassAndInertia."#,sim_set_shape_mass,"setShapeMass",(shape_handle:i64,mass:f64)->()), +(r#"Sets the material (used by the physics engines) of a specific shape. You might have to also call sim.resetDynamicObject for changes to take effect."#,sim_set_shape_material,"setShapeMaterial",(shape_handle:i64,material_id_or_shape_handle:i64)->()), +(r#"Applies (or removes) a texture to a shape. See also sim.getTextureId, sim.getShapeTextureId, sim.createTexture and simApplyTexture."#,sim_set_shape_texture,"setShapeTexture",(shape_handle:i64,texture_id:i64,mapping_mode:i64,options:i64,uv_scaling:Vec),opt(position:Vec,orientation:Vec)->()), +(r#"Enables or disables the stepping operation mode for a threaded script. If enabled, then the current script will have to trigger each simulation step explicitly, via sim.step. Is applied cumulatively, i.e. if the stepping operation mode is enabled n times, it needs to be disabled n times to return to the initial state. For complete control over threaded scripts, see also the other thread related functions + +(Lua specific: in stepping operation mode, automatic thread interruptions, i.e. preemptive threading, is supressed) +"#,sim_set_stepping,"setStepping",(enabled:bool)->i64), +(r#"Sets a string parameter. See also the other simulator parameter related functions."#,sim_set_string_param,"setStringParam",(parameter:i64,string_state:String)->()), +(r#"Sets the value of a string signal. A signal created in a child script, a customization script or int the main script will be automatically cleared when the script ends. See also the other signal functions."#,sim_set_string_signal,"setStringSignal",(signal_name:String,signal_value:Vec)->()), +(r#"Writes the image of a vision sensor (and applies any image processing via the vision callback functions). Make sure the vision sensor is flagged as external input. See also the other vision sensor related API functions"#,sim_set_vision_sensor_img,"setVisionSensorImg",(sensor_handle:i64,image:Vec),opt(options:i64,pos:Vec,size:Vec)->()), +(r#"Requests a start of a simulation (or a resume of a paused simulation). See also sim.pauseSimulation, sim.stopSimulation and sim.getSimulationState. See also the simulation state diagram."#,sim_start_simulation,"startSimulation"->i64), +(r#"Triggers the next simulation step, when in stepping operation mode. When simulation is running, then sim.step will only return once the simulation time has changed. See also sim.setStepping."#,sim_step,"step"->()), +(r#"Requests a stop of the running simulation. See also sim.startSimulation, sim.pauseSimulation and sim.getSimulationState. See also the simulation state diagram."#,sim_stop_simulation,"stopSimulation"->i64), +(r#"Removes an object from an OC tree, as voxel subtractions. See also sim.insertObjectIntoOctree, sim.removeVoxelsFromOctree and the other OC tree related functions."#,sim_subtract_object_from_octree,"subtractObjectFromOctree",(octree_handle:i64,object_handle:i64,options:i64)->i64), +(r#"Removes an object from a point cloud, as a subtraction. See also sim.insertPointsIntoPointCloud, sim.insertObjectIntoPointCloud, sim.removePointsFromPointCloud and the other point cloud related functions."#,sim_subtract_object_from_point_cloud,"subtractObjectFromPointCloud",(point_cloud_handle:i64,object_handle:i64,options:i64,tolerance:f64)->i64), +(r#""#,sim_test_cb,"testCB",(a:i64,cb:String,b:i64)->i64), +(r#"Closes a text edition window previously opened with sim.textEditorOpen."#,sim_text_editor_close,"textEditorClose",(handle:i64)->(String,Vec,Vec)), +(r#"Retieves information from a text edition window previously opened with sim.textEditorOpen."#,sim_text_editor_get_info,"textEditorGetInfo",(handle:i64)->(String,Vec,Vec,bool)), +(r#"Opens a text edition window. See simOpenTextEditor for the C version of this function. See also sim.textEditorClose, sim.textEditorShow and sim.textEditorGetInfo."#,sim_text_editor_open,"textEditorOpen",(init_text:String,properties:String)->i64), +(r#"Shows or hides a text edition window previously opened with sim.textEditorOpen."#,sim_text_editor_show,"textEditorShow",(handle:i64,show_state:bool)->()), +(r#"Modifies a buffer than contains packed data. See also the data packing/unpacking functions."#,sim_transform_buffer,"transformBuffer",(in_buffer:Vec,in_format:i64,multiplier:f64,offset:f64,out_format:i64)->Vec), +(r#"Transforms an image in various ways. See also sim.loadImage, sim.getScaledImage, sim.transformBuffer and sim.combineRgbImages."#,sim_transform_image,"transformImage",(image:Vec,resolution:Vec,options:i64)->()), +(r#"Ungroups a compound shape into several shapes. See also sim.groupShapes, sim.convexDecompose, sim.getQHull, sim.getDecimatedMesh, sim.alignShapeBB and sim.relocateShapeFrame"#,sim_ungroup_shape,"ungroupShape",(shape_handle:i64)->Vec), +(r#"Unpacks a string (or part of it) into a table of double floating-point numbers. See also sim.packDoubleTable and the other packing/unpacking functions."#,sim_unpack_double_table,"unpackDoubleTable",(data:Vec),opt(start_double_index:i64,double_count:i64,additional_byte_offset:i64)->Vec), +(r#"Unpacks a string (or part of it) into a table of floating-point numbers. See also sim.packFloatTable and the other packing/unpacking functions."#,sim_unpack_float_table,"unpackFloatTable",(data:Vec),opt(start_float_index:i64,float_count:i64,additional_byte_offset:i64)->Vec), +(r#"Unpacks a string (or part of it) into a table of int32 numbers. See also sim.packInt32Table and the other packing/unpacking functions."#,sim_unpack_int32_table,"unpackInt32Table",(data:Vec),opt(start_int32_index:i64,int32_count:i64,additional_byte_offset:i64)->Vec), +(r#"Unpacks a buffer into a table. See also sim.packTable, the other stack functions and the other packing/unpacking functions."#,sim_unpack_table,"unpackTable",(buffer:Vec)->serde_json::Value), +(r#"Unpacks a string (or part of it) into a table of uint16 numbers. See also sim.packUInt16Table and the other packing/unpacking functions."#,sim_unpack_u_int16_table,"unpackUInt16Table",(data:Vec),opt(start_uint16_index:i64,uint16_count:i64,additional_byte_offset:i64)->Vec), +(r#"Unpacks a string (or part of it) into a table of uint32 numbers. See also sim.packUInt32Table and the other packing/unpacking functions."#,sim_unpack_u_int32_table,"unpackUInt32Table",(data:Vec),opt(start_uint32_index:i64,uint32_count:i64,additional_byte_offset:i64)->Vec), +(r#"Unpacks a string (or part of it) into a table of uint8 numbers. See also sim.packUInt8Table and the other packing/unpacking functions."#,sim_unpack_u_int8_table,"unpackUInt8Table",(data:Vec),opt(start_uint8_index:i64,uint8count:i64)->Vec), +(r#""#,sim_visit_tree,"visitTree",(root_handle:i64,visitor_func:String),opt(options:serde_json::Value)->()), +(r#"Waits for a certain amount of time. See also sim.waitForSignal."#,sim_wait,"wait",(dt:f64),opt(simulation_time:bool)->f64), +(r#"Waits for a signal. This function will first check whether an integer, double, double or string signal with that name is present (in that order). The function only returns when the signal is present (defined). See also the other signal functions and sim.wait."#,sim_wait_for_signal,"waitForSignal",(sig_name:String)->serde_json::Value), +(r#"Adds or removes custom data to be stored and saved together with an object, or the scene. If the tag name ends with the string "@tmp", then the data will not be saved during a scene or model save operation. The data can also be saved globally for the application (for the current CoppeliaSim session). See also the other custom data block related functions and the data packing/unpacking functions. If you wish to store a reference to another object, have a look at sim.setReferencedHandles."#,sim_write_custom_data_block,"writeCustomDataBlock",(object_handle:i64,tag_name:String,data:Vec)->()), +(r#""#,sim_write_custom_data_block_ex,"writeCustomDataBlockEx",(handle:i64,tag_name:String,data:String),opt(options:serde_json::Value)->()), +(r#"Adds or removes custom table data to be stored and saved together with an object, or the scene. If the tag name ends with the string "@tmp", then the data will not be saved during a scene or model save operation. The data can also be saved globally for the application (for the current CoppeliaSim session). See also the other custom data block related functions."#,sim_write_custom_table_data,"writeCustomTableData",(handle:i64,tag_name:String,the_table:serde_json::Value),opt(options:serde_json::Value)->()), +(r#"Overwrites a specific texture (or a portion of it) with RGB data. See also sim.getTextureId, sim.readTexture and sim.createTexture."#,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)->()), +(r#"Converts Yaw-Pitch-Roll angles to CoppeliaSim's alpha-beta-gamma angles. See also sim.alphaBetaGammaToYawPitchRoll and the section about positions, orientations and transformations"#,sim_yaw_pitch_roll_to_alpha_beta_gamma,"yawPitchRollToAlphaBetaGamma",(yaw_angle:f64,pitch_angle:f64,roll_angle:f64)->(f64,f64,f64)), +(r#""#,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 0caa255..b8acf8c 100644 --- a/src/remote_api_objects/sim/sim_ik_api.rs +++ b/src/remote_api_objects/sim/sim_ik_api.rs @@ -1,82 +1,83 @@ use crate::RemoteApiClientInterface; +#[doc=r#"API functions for creating kinematics tasks. All units, unless otherwise indicated, are specified in meters and radians."#] 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),opt(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),opt(relative_to_object_handle:i64)->Vec), -(sim_ik_get_object_transformation,"getObjectTransformation",(environment_handle:i64,object_handle:i64),opt(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,matrix:Vec),opt(relative_to_object_handle:i64)->()), -(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,pose:Vec),opt(relative_to_object_handle:i64)->()), -(sim_ik_set_object_transformation,"setObjectTransformation",(environment_handle:i64,object_handle:i64,position:Vec,euler_or_quaternion:Vec),opt(relative_to_object_handle:i64)->()), -(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)->()) +(r#"Adds a new IK element to an IK group."#,sim_ik_add_element,"addElement",(environment_handle:i64,ik_group_handle:i64,tip_dummy_handle:i64)->i64), +(r#"Convenience function to quickly generate an IK element from a kinematic chain in the scene"#,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)), +(r#"Computes the Jacobian and error vector for an IK group"#,sim_ik_compute_group_jacobian,"computeGroupJacobian",(environment_handle:i64,ik_group_handle:i64)->(Vec,Vec)), +(r#"Computes the Jacobian and error vector for a kinematic chain"#,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)), +(r#"Creates a visual representation of an IK chain."#,sim_ik_create_debug_overlay,"createDebugOverlay",(environment_handle:i64,tip_handle:i64),opt(base_handle:i64)->i64), +(r#"Creates a dummy object."#,sim_ik_create_dummy,"createDummy",(environment_handle:i64),opt(dummy_name:String)->i64), +(r#"Creates an new IK environment."#,sim_ik_create_environment,"createEnvironment",opt(flags:i64)->i64), +(r#"Creates an IK group."#,sim_ik_create_group,"createGroup",(environment_handle:i64),opt(ik_group_name:String)->i64), +(r#"Creates a joint object."#,sim_ik_create_joint,"createJoint",(environment_handle:i64,joint_type:i64),opt(joint_name:String)->i64), +(r#"Checks whether an IK group exists, based on its name."#,sim_ik_does_group_exist,"doesGroupExist",(environment_handle:i64,ik_group_name:String)->bool), +(r#"Checks whether an object exists, based on its name."#,sim_ik_does_object_exist,"doesObjectExist",(environment_handle:i64,object_name:String)->bool), +(r#"Duplicates an IK environment. Useful when operating on an environment while leaving the original environment unchanged."#,sim_ik_duplicate_environment,"duplicateEnvironment",(environment_handle:i64)->i64), +(r#"Removes the visual representation of an IK chain."#,sim_ik_erase_debug_overlay,"eraseDebugOverlay",(debug_object:i64)->()), +(r#"Erases an IK environment."#,sim_ik_erase_environment,"eraseEnvironment",(environment_handle:i64)->()), +(r#"Erases an object."#,sim_ik_erase_object,"eraseObject",(environment_handle:i64,object_handle:i64)->()), +(r#"Searches for a manipulator configuration that matches the target dummy/dummies position/orientation in space. Search is randomized. One should call simIK.getAlternateConfigs for each returned configuration, if some revolute joints of the manipulator have a range of more than 360 degrees, in order to generate some equivalent poses but alternate configurations. The IK environment remains unchanged."#,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), +(r#"Generates a path that drives the IK tip onto its IK target, in a straight line (i.e. shortest path in Cartesian space). The function returns a path in the configuration space if the operation was successful. A reason for a non-successful operation can be: there are some forbidden poses/configurations on the way, or some of the configuration points cannot be reached (e.g. out of reach, or due to joint limits). The IK environment remains unchanged."#,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), +(r#"Useful when called after simIK.findConfig: generates alternative manipulator configurations, for a same end-effector pose, for a manipulator that has revolute joints with a range larger than 360 degrees. The original submitted configuration will be part of the returned configurations. The IK environment remains unchanged."#,sim_ik_get_alternate_configs,"getAlternateConfigs",(environment_handle:i64,joint_handles:Vec),opt(low_limits:Vec,ranges:Vec)->Vec), +(r#"Retrieves the base object of an IK element."#,sim_ik_get_element_base,"getElementBase",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->(i64,i64)), +(r#"Retrieves the constraints of an IK element."#,sim_ik_get_element_constraints,"getElementConstraints",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->i64), +(r#"Retrieves various flags of an IK element."#,sim_ik_get_element_flags,"getElementFlags",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->i64), +(r#"Retrieves the precision settings of an IK element."#,sim_ik_get_element_precision,"getElementPrecision",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->Vec), +(r#"Retrieves the desired linear and angular resolution weights of an IK element."#,sim_ik_get_element_weights,"getElementWeights",(environment_handle:i64,ik_group_handle:i64,element_handle:i64)->Vec), +(r#""#,sim_ik_get_failure_description,"getFailureDescription",(reason:i64)->String), +(r#"Retrieves calculation properties for an IK group."#,sim_ik_get_group_calculation,"getGroupCalculation",(environment_handle:i64,ik_group_handle:i64)->(i64,f64,i64)), +(r#"Retrieves flags of an IK group."#,sim_ik_get_group_flags,"getGroupFlags",(environment_handle:i64,ik_group_handle:i64)->i64), +(r#"Retrieves the handle of an IK group based on its name."#,sim_ik_get_group_handle,"getGroupHandle",(environment_handle:i64,ik_group_name:String)->i64), +(r#"Checks which joints of an IK group hit a limit last time that IK group was handled"#,sim_ik_get_group_joint_limit_hits,"getGroupJointLimitHits",(environment_handle:i64,ik_group_handle:i64)->(Vec,Vec)), +(r#"Returns the joint handles involved in the IK group calculation, i.e. one handle per Jacobian column (except with revolute joints that have 3 corresponding Jacobian columns)"#,sim_ik_get_group_joints,"getGroupJoints",(environment_handle:i64,ik_group_handle:i64)->Vec), +(r#"Retrieves information about a possible joint dependency."#,sim_ik_get_joint_dependency,"getJointDependency",(environment_handle:i64,joint_handle:i64)->(i64,f64,f64)), +(r#"Retrieves the joint limits."#,sim_ik_get_joint_interval,"getJointInterval",(environment_handle:i64,joint_handle:i64)->(bool,Vec)), +(r#"Retrieves the limit margin of a joint, i.e. the threshold that will be used to counteract on joint limit violation during IK resolution, if the appropriate IK group flag was set"#,sim_ik_get_joint_limit_margin,"getJointLimitMargin",(environment_handle:i64,joint_handle:i64)->f64), +(r#"Retrieves the intrinsic transformation matrix of a joint."#,sim_ik_get_joint_matrix,"getJointMatrix",(environment_handle:i64,joint_handle:i64)->Vec), +(r#"Retrieves the maximum step size of a joint."#,sim_ik_get_joint_max_step_size,"getJointMaxStepSize",(environment_handle:i64,joint_handle:i64)->f64), +(r#"Retrieves the joint mode."#,sim_ik_get_joint_mode,"getJointMode",(environment_handle:i64,joint_handle:i64)->i64), +(r#"Retrieves the position (linear or angular) of a joint."#,sim_ik_get_joint_position,"getJointPosition",(environment_handle:i64,joint_handle:i64)->f64), +(r#"Retrieves the screw lead of a revolute joint."#,sim_ik_get_joint_screw_lead,"getJointScrewLead",(environment_handle:i64,joint_handle:i64)->f64), +(r#"Retrieves the intrinsic transformation of a joint."#,sim_ik_get_joint_transformation,"getJointTransformation",(environment_handle:i64,joint_handle:i64)->(Vec,Vec,Vec)), +(r#"Retrieves the joint type."#,sim_ik_get_joint_type,"getJointType",(environment_handle:i64,joint_handle:i64)->i64), +(r#"Retrieves the IK weight of a joint, i.e. the weight it has during IK resolution."#,sim_ik_get_joint_weight,"getJointWeight",(environment_handle:i64,joint_handle:i64)->f64), +(r#"Retrieves the handle of an object based on its name."#,sim_ik_get_object_handle,"getObjectHandle",(environment_handle:i64,object_name:String)->i64), +(r#"Retrieves the transformation matrix of an object. If the object is a joint object, the matrix does not include the joint's intrinsic transformation."#,sim_ik_get_object_matrix,"getObjectMatrix",(environment_handle:i64,object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(r#"Retrieves an object's parent handle."#,sim_ik_get_object_parent,"getObjectParent",(environment_handle:i64,object_handle:i64)->i64), +(r#"Retrieves the pose (position and quaternion) of an object. If the object is a joint object, the pose does not include the joint's intrinsic transformation."#,sim_ik_get_object_pose,"getObjectPose",(environment_handle:i64,object_handle:i64),opt(relative_to_object_handle:i64)->Vec), +(r#"Retrieves the transformation (position and quaternion/euler angles) of an object. If the object is a joint object, the transformation does not include the joint's intrinsic transformation."#,sim_ik_get_object_transformation,"getObjectTransformation",(environment_handle:i64,object_handle:i64),opt(relative_to_object_handle:i64)->(Vec,Vec,Vec)), +(r#"Retrieves the type of an object."#,sim_ik_get_object_type,"getObjectType",(environment_handle:i64,object_handle:i64)->i64), +(r#"Allows to loop through all objects in the environment."#,sim_ik_get_objects,"getObjects",(environment_handle:i64,index:i64)->(i64,String,bool,i64)), +(r#"Retrieves the handle of the target dummy associated with a tip dummy"#,sim_ik_get_target_dummy,"getTargetDummy",(environment_handle:i64,dummy_handle:i64)->i64), +(r#"Handles (i.e. computes/resolves) an IK group. Convenience function for simIK.handleIkGroups(ikEnv,{ikGroupHandle},..)"#,sim_ik_handle_group,"handleGroup",(environment_handle:i64,ik_group:i64),opt(options:serde_json::Value)->(i64,i64,Vec)), +(r#"Handles (i.e. computes/resolves) one or several IK groups"#,sim_ik_handle_groups,"handleGroups",(environment_handle:i64,ik_groups:Vec),opt(options:serde_json::Value)->(i64,i64,Vec)), +(r#"Loads kinematic content previously exported in the CoppeliaSim application. Make sure that the environment is empty before calling this function."#,sim_ik_load,"load",(environment_handle:i64,data:String)->()), +(r#"Saves the kinematic content of an IK environment."#,sim_ik_save,"save",(environment_handle:i64)->String), +(r#"Sets the base object of an IK element."#,sim_ik_set_element_base,"setElementBase",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,base_handle:i64),opt(constraints_base_handle:i64)->()), +(r#"Sets the constraints of an IK element."#,sim_ik_set_element_constraints,"setElementConstraints",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,constraints:i64)->()), +(r#"Sets various flags of an IK element."#,sim_ik_set_element_flags,"setElementFlags",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,flags:i64)->()), +(r#"Sets the desired precision of an IK element."#,sim_ik_set_element_precision,"setElementPrecision",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,precision:Vec)->()), +(r#"Sets the desired linear and angular resolution weights of an IK element."#,sim_ik_set_element_weights,"setElementWeights",(environment_handle:i64,ik_group_handle:i64,element_handle:i64,weights:Vec)->()), +(r#"Sets calculation properties for an IK group."#,sim_ik_set_group_calculation,"setGroupCalculation",(environment_handle:i64,ik_group_handle:i64,method:i64,damping:f64,max_iterations:i64)->()), +(r#"Sets flags of an IK group."#,sim_ik_set_group_flags,"setGroupFlags",(environment_handle:i64,ik_group_handle:i64,flags:i64)->()), +(r#"Sets information about a possible dependent joint."#,sim_ik_set_joint_dependency,"setJointDependency",(environment_handle:i64,joint_handle:i64,master_joint_handle:i64),opt(offset:f64,mult:f64,callback:String)->()), +(r#"Sets the joint limits."#,sim_ik_set_joint_interval,"setJointInterval",(environment_handle:i64,joint_handle:i64,cyclic:bool),opt(interval:Vec)->()), +(r#"Sets the limit margin of a joint, i.e. the threshold that will be used to counteract on joint limit violation during IK resolution, if the appropriate IK group flag was set"#,sim_ik_set_joint_limit_margin,"setJointLimitMargin",(environment_handle:i64,joint_handle:i64,margin:f64)->()), +(r#"Sets the maximum step size of a joint."#,sim_ik_set_joint_max_step_size,"setJointMaxStepSize",(environment_handle:i64,joint_handle:i64,step_size:f64)->()), +(r#"Sets the joint mode."#,sim_ik_set_joint_mode,"setJointMode",(environment_handle:i64,joint_handle:i64,joint_mode:i64)->()), +(r#"Sets the position (linear or angular) of a joint."#,sim_ik_set_joint_position,"setJointPosition",(environment_handle:i64,joint_handle:i64,position:f64)->()), +(r#"Sets the screw lead, in case of a revolute joint."#,sim_ik_set_joint_screw_lead,"setJointScrewLead",(environment_handle:i64,joint_handle:i64,lead:f64)->()), +(r#"Sets the IK weight of a joint, i.e. the weight it has during IK resolution."#,sim_ik_set_joint_weight,"setJointWeight",(environment_handle:i64,joint_handle:i64,weight:f64)->()), +(r#"Sets the transformation matrix of an object. If the object is a joint object, the matrix does not include the joint's intrinsic transformation."#,sim_ik_set_object_matrix,"setObjectMatrix",(environment_handle:i64,object_handle:i64,matrix:Vec),opt(relative_to_object_handle:i64)->()), +(r#"Sets the parent of an object."#,sim_ik_set_object_parent,"setObjectParent",(environment_handle:i64,object_handle:i64,parent_object_handle:i64),opt(keep_in_place:bool)->()), +(r#"Sets the pose (position and quaternion) of an object. If the object is a joint object, the pose does not include the joint's intrinsic transformation."#,sim_ik_set_object_pose,"setObjectPose",(environment_handle:i64,object_handle:i64,pose:Vec),opt(relative_to_object_handle:i64)->()), +(r#"Sets the transformation (position and quaternion/Euler angles) of an object. If the object is a joint object, the transformation does not include the joint's intrinsic transformation."#,sim_ik_set_object_transformation,"setObjectTransformation",(environment_handle:i64,object_handle:i64,position:Vec,euler_or_quaternion:Vec),opt(relative_to_object_handle:i64)->()), +(r#"Sets the rotation transformation matrix of a spherical joint."#,sim_ik_set_spherical_joint_matrix,"setSphericalJointMatrix",(environment_handle:i64,joint_handle:i64,matrix:Vec)->()), +(r#"Sets the rotation transformation of a spherical joint."#,sim_ik_set_spherical_joint_rotation,"setSphericalJointRotation",(environment_handle:i64,joint_handle:i64,euler_or_quaternion:Vec)->()), +(r#"Associates a tip dummy with a target dummy, or removes that association. If the tip dummy is already associated with another target dummy, then first remove that association before setting another one"#,sim_ik_set_target_dummy,"setTargetDummy",(environment_handle:i64,dummy_handle:i64,target_dummy_handle:i64)->()), +(r#"Convenience function to apply the scene state to its ik environment counterpart. Use together with simIK.addElementFromScene."#,sim_ik_sync_from_sim,"syncFromSim",(environment_handle:i64,ik_groups:Vec)->()), +(r#"Convenience function to apply inverse kinematic values computed in the IK world, to the scene. Use together with simIK.addElementFromScene."#,sim_ik_sync_to_sim,"syncToSim",(environment_handle:i64,ik_groups:Vec)->()) } } \ No newline at end of file diff --git a/src/remote_api_objects/sim/tests.rs b/src/remote_api_objects/sim/tests.rs index 842cbda..20df5c7 100644 --- a/src/remote_api_objects/sim/tests.rs +++ b/src/remote_api_objects/sim/tests.rs @@ -184,7 +184,7 @@ fn test_sim_ik_example() { let mut sim = MockRemoteAPIClient::new_sucess(); sim.uuid = "fdea473e-ef12-43e0-bd41-8248ea153e17".into(); - sim.require(Module::SimIK).unwrap(); + sim.require(Plugin::SimIK).unwrap(); assert_payload!(sim,b"\xa6dfunctzmqRemoteApi.requiredargs\x81esimIKduuidx$fdea473e-ef12-43e0-bd41-8248ea153e17cver\x02dlangdrusteargsL\x01"); sim.sim_ik_create_environment(None).unwrap(); diff --git a/src/zmq_protocol/zmq_request.rs b/src/zmq_protocol/zmq_request.rs index 33e4837..593ed40 100644 --- a/src/zmq_protocol/zmq_request.rs +++ b/src/zmq_protocol/zmq_request.rs @@ -1,14 +1,19 @@ use ciborium::{cbor, value::Value}; use serde::Serialize; +/// should return the request in by bytes +/// The bytes is cbor encoted data pub trait RawRequest { fn to_raw_request(&self) -> Vec; } - +// the PROTOCOL version pub const VERSION: i32 = 2; +// The LANG should always be "rust" pub const LANG: &str = "rust"; #[derive(Debug, Serialize)] +/// The Request Prototol is defined here: +/// [PROTOCOL](https://github.com/CoppeliaRobotics/zmqRemoteApi/blob/master/PROTOCOL.md) pub struct ZmqRequest { pub func: String, pub args: Vec, diff --git a/src/zmq_protocol/zmq_response.rs b/src/zmq_protocol/zmq_response.rs index 5db0fb7..98af002 100644 --- a/src/zmq_protocol/zmq_response.rs +++ b/src/zmq_protocol/zmq_response.rs @@ -3,27 +3,33 @@ use serde_json::Value; #[derive(Deserialize, Debug)] #[serde(untagged)] +/// Coppeleia's server can return 3 kinds of reponse: +/// An error: ErrorResponse +/// The Function Response: FunctionResponse +/// An Object: ObjectResponse +/// More information see the +/// [PROTOCOL](https://github.com/CoppeliaRobotics/zmqRemoteApi/blob/master/PROTOCOL.md) pub enum ZmqResponse { Error(ErrorResponse), Object(ObjectResponse), Function(FunctionResponse), } -//#[derive(Deserialize, Debug)] -//pub struct ArrayResponse { -// #[serde(rename = "ret")] -// pub array: Vec, -//} #[derive(Deserialize, Debug)] +/// When an Error occurs in the simulation, the sever will send an ErrorResponse pub struct ErrorResponse { #[serde(rename = "err")] pub message: String, } #[derive(Deserialize, Debug)] +/// When the server sends data to client, like a object handle id, or the value of any sensors +/// the server will send ObjectResponse pub struct ObjectResponse { pub ret: Value, } #[derive(Deserialize, Debug)] +/// When an Callback is passed or the server wants to the client wait, then a FunctionResponse +/// is Returned pub struct FunctionResponse { #[serde(rename = "func")] pub function_name: String,