├── README.md ├── VREP model ├── space_robot_3link.ttt └── space_robot_double_3link.ttt ├── experiment ├── hyper_parameters.py ├── run.py └── visualize.py ├── remoteApi-3.4.0-x64.dll ├── remoteApi-3.4.0-x64.dylib ├── remoteApi-3.4.0-x64.so ├── requirements.txt ├── softqlearning ├── algorithms │ ├── rl_algorithm.py │ └── sql.py ├── environment │ ├── space_robot_3link.py │ └── space_robot_double_3links.py ├── misc │ ├── kernel.py │ ├── nn.py │ ├── plotter.py │ ├── sampler.py │ └── tf_utils.py ├── policies │ ├── nn_policy.py │ └── stochastic_policy.py ├── replay_buffers │ ├── replay_buffer.py │ └── simple_replay_buffer.py └── value_functions │ └── value_function.py ├── version.py ├── vrep.py └── vrepConst.py /README.md: -------------------------------------------------------------------------------- 1 | # Soft Q-learning for Space Robots 2 | 3 | Code accompanying the paper: 4 | C. Yan, Q. Zhang, Z. Liu, X. Wang and B. Liang, "Control of Free-Floating Space Robots to Capture Targets UsingSoft Q-Learning," *2018 IEEE International Conference on Robotics and Biomimetics (ROBIO)*, Kuala Lumpur,Malaysia, 2018, pp. 654-660. (doi: 10.1109/ROBIO.2018.8665049) 5 | 6 | Based on [Haarnoja](https://github.com/haarnoja/softqlearning), this framework provides an implementation of Soft Q-learning algorithm for controlling space robots to capture targets, 7 | and supports running experiments on V-REP simulation environments. 8 | 9 | ## Getting Started 10 | 11 | 1. You will first need to clone [rllab](https://github.com/rll/rllab), and have its path added to your PYTHONPATH environment variable. 12 | 13 | 2. Install requirements: `pip install -r requirements.txt` 14 | 15 | 3. Install and run [V-REP](https://www.coppeliarobotics.com/downloads). Load the V-REP model. 16 | 17 | - Some example V-REP models(.ttt) are available in the `VREP MODEL` file. 18 | - Adding the flag `-h` to run V-REP in a headless mode. 19 | 20 | ## Examples 21 | **Note:** Before you start running any commands below, always make sure that the V-REP simulator is on (whether in headless mode or not), and the environment you have in the command should be the same as what you have in the V-REP simulator. 22 | 23 | ### Loading and Training Agents 24 | To load a pre-trained model and train the agent, run: 25 | ``` 26 | python experiment/run.py --env=SpaceRobot3link --load_model= 27 | ``` 28 | - `SpaceRobot3link` can be replaced with `SpaceRobotDouble3link`, where `SpaceRobot3link` specifies the space robot with a single 3-DoF manipulator and `SpaceRobotDouble3link` specifies the space robot with dual 3-DoF manipulators. If you remove the flag, `--env` will be `SpaceRobot3link` by default. 29 | - `` specifies the directory of `.ckpt` file that contains the pre-trained model. If you remove the flag, training will start from scratch. 30 | - The log(.txt) and model(.ckpt) will be saved to the `../data` directory by default. 31 | 32 | ### Visualizing Agents 33 | To simulate the agent, run: 34 | ``` 35 | python experiment/visualize.py --env=SpaceRobot3link --model= 36 | ``` 37 | - This will simulate the agent saved at `` (the directory of `.ckpt` file that contains the trained model). 38 | - The log(.txt) files generated in the simulation will be saved to `../viz_data` directory by default. 39 | -------------------------------------------------------------------------------- /VREP model/space_robot_3link.ttt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ycz0512/SoftQLearning4SpaceRobots/d8166f411dfd71025913bf261c351f7e31e6a8b5/VREP model/space_robot_3link.ttt -------------------------------------------------------------------------------- /VREP model/space_robot_double_3link.ttt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ycz0512/SoftQLearning4SpaceRobots/d8166f411dfd71025913bf261c351f7e31e6a8b5/VREP model/space_robot_double_3link.ttt -------------------------------------------------------------------------------- /experiment/hyper_parameters.py: -------------------------------------------------------------------------------- 1 | SHARED_PARAMS = { 2 | 'policy_lr': 1E-4, 3 | 'qf_lr': 1E-4, 4 | 'discount': 0.99, 5 | 'Q_layer_size': [128, 128], 6 | 'policy_layer_size': [200, 200], 7 | 'batch_size': 256, 8 | 'max_pool_size': 1E6, 9 | 'min_pool_size': 1000, 10 | 'epoch_length': 1000, 11 | 'pkl_gap': 5, 12 | 'n_train_repeat': 1, 13 | 'kernel_particles': 32, 14 | 'kernel_update_ratio': 0.5, 15 | 'value_n_particles': 32, 16 | 'td_target_update_interval': 1000, 17 | 'model_save_path': '../data', 18 | 'viz_log_path': '../viz_data', 19 | } 20 | 21 | 22 | ENV_PARAMS = { 23 | 'max_path_length': 200, 24 | 'n_epochs': 500, 25 | 'reward_scale': 30, 26 | 'final_phase_reward_scaler': 1.5, 27 | 'reward_factor_w1': 1E-3, 28 | 'reward_factor_wlog': 1.0, 29 | 'reward_factor_w2': 0.01, 30 | 'alpha': 1E-6, 31 | 'distance_tolerance': 0.04, 32 | 'torques_norm_tolerance': 0.1, 33 | 'max_torque': 2, 34 | 'squash': True 35 | } 36 | 37 | AVAILABLE_ENVS = ['SpaceRobot3link', 'SpaceRobotDouble3link'] 38 | DEFAULT_ENV = 'SpaceRobot3link' 39 | -------------------------------------------------------------------------------- /experiment/run.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | from softqlearning.algorithms.sql import SQL 3 | from softqlearning.misc.kernel import adaptive_isotropic_gaussian_kernel 4 | from softqlearning.replay_buffers.simple_replay_buffer import SimpleReplayBuffer 5 | from softqlearning.value_functions.value_function import NNQFunction 6 | from softqlearning.policies.stochastic_policy import StochasticNNPolicy 7 | from softqlearning.misc.sampler import SimpleSampler 8 | from softqlearning.environment.space_robot_3link import SpaceRobot3link 9 | from softqlearning.environment.space_robot_double_3links import SpaceRobotDouble3link 10 | from experiment.hyper_parameters import SHARED_PARAMS, ENV_PARAMS, AVAILABLE_ENVS, DEFAULT_ENV 11 | 12 | 13 | parser = argparse.ArgumentParser(description='Train control policies.') 14 | parser.add_argument('--env', type=str, choices=AVAILABLE_ENVS, default=DEFAULT_ENV) 15 | parser.add_argument('--load_model', type=str, default='') 16 | arg_parser = parser.parse_args() 17 | 18 | if arg_parser.env == 'SpaceRobot3link': 19 | env = SpaceRobot3link() 20 | elif arg_parser.env == 'SpaceRobotDouble3link': 21 | env = SpaceRobotDouble3link() 22 | else: 23 | raise NotImplementedError 24 | 25 | pool = SimpleReplayBuffer( 26 | env_spec=env.spec, 27 | max_replay_buffer_size=SHARED_PARAMS['max_pool_size'] 28 | ) 29 | 30 | sampler = SimpleSampler( 31 | max_path_length=ENV_PARAMS['max_path_length'], 32 | min_pool_size=SHARED_PARAMS['min_pool_size'], 33 | batch_size=SHARED_PARAMS['batch_size'] 34 | ) 35 | 36 | base_kwargs = dict( 37 | epoch_length=SHARED_PARAMS['epoch_length'], 38 | n_epochs=ENV_PARAMS['n_epochs'], 39 | n_train_repeat=SHARED_PARAMS['n_train_repeat'], 40 | eval_render=False, 41 | eval_n_episodes=1, 42 | sampler=sampler 43 | ) 44 | 45 | qf = NNQFunction( 46 | env_spec=env.spec, 47 | hidden_layer_sizes=SHARED_PARAMS['Q_layer_size'] 48 | ) 49 | 50 | policy = StochasticNNPolicy( 51 | env_spec=env.spec, 52 | hidden_layer_sizes=SHARED_PARAMS['policy_layer_size'], 53 | squash=ENV_PARAMS['squash'] 54 | ) 55 | 56 | algorithm = SQL( 57 | base_kwargs=base_kwargs, 58 | env=env, 59 | pool=pool, 60 | qf=qf, 61 | policy=policy, 62 | kernel_fn=adaptive_isotropic_gaussian_kernel, 63 | kernel_n_particles=SHARED_PARAMS['kernel_particles'], 64 | kernel_update_ratio=SHARED_PARAMS['kernel_update_ratio'], 65 | value_n_particles=SHARED_PARAMS['value_n_particles'], 66 | td_target_update_interval=SHARED_PARAMS['td_target_update_interval'], 67 | qf_lr=SHARED_PARAMS['qf_lr'], 68 | policy_lr=SHARED_PARAMS['policy_lr'], 69 | discount=SHARED_PARAMS['discount'], 70 | reward_scale=ENV_PARAMS['reward_scale'], 71 | save_full_state=False) 72 | 73 | if arg_parser.load_model is not '': 74 | load_path = arg_parser.load_model 75 | else: 76 | load_path = None 77 | 78 | algorithm.train(load=load_path) 79 | -------------------------------------------------------------------------------- /experiment/visualize.py: -------------------------------------------------------------------------------- 1 | import tensorflow as tf 2 | import numpy as np 3 | import argparse 4 | import time 5 | import os 6 | 7 | from softqlearning.misc.nn import feedforward_net 8 | from softqlearning.environment.space_robot_3link import SpaceRobot3link 9 | from softqlearning.environment.space_robot_double_3links import SpaceRobotDouble3link 10 | from experiment.hyper_parameters import SHARED_PARAMS, ENV_PARAMS, AVAILABLE_ENVS, DEFAULT_ENV 11 | 12 | 13 | viz_log_path = SHARED_PARAMS['viz_log_path'] 14 | if not os.path.exists(viz_log_path): 15 | os.mkdir(viz_log_path) 16 | 17 | parser = argparse.ArgumentParser(description='Train control policies.') 18 | parser.add_argument('--env', type=str, choices=AVAILABLE_ENVS, default=DEFAULT_ENV) 19 | parser.add_argument('--model', type=str, default='') 20 | arg_parser = parser.parse_args() 21 | 22 | if arg_parser.env == 'SpaceRobot3link': 23 | env = SpaceRobot3link() 24 | elif arg_parser.env == 'SpaceRobotDouble3link': 25 | env = SpaceRobotDouble3link() 26 | else: 27 | raise NotImplementedError 28 | 29 | action_dim = env.action_dims 30 | observation_dim = env.obs_dims 31 | squash = ENV_PARAMS['squash'] 32 | layer_size = SHARED_PARAMS['policy_layer_size'] + [action_dim] 33 | 34 | 35 | def controller(obs): 36 | """ 37 | trained policy / controller 38 | :param obs: s_t [1, observation_dim] 39 | :return: a_t [1, action_dim] 40 | """ 41 | single_latent = np.random.normal(size=(1, action_dim)) 42 | 43 | raw_action = sess.run(raw_actions, feed_dict={observation_ph: obs, 44 | latent_ph: single_latent}) 45 | tan_action = sess.run(tan_actions, feed_dict={observation_ph: obs, 46 | latent_ph: single_latent}) 47 | 48 | return tan_action if squash else raw_action 49 | 50 | 51 | # stochastic policy network 52 | with tf.variable_scope('policy', reuse=False): 53 | observation_ph = tf.placeholder(tf.float32, shape=[None, observation_dim]) 54 | latent_ph = tf.placeholder(tf.float32, shape=[None, action_dim]) 55 | 56 | raw_actions = feedforward_net((observation_ph, latent_ph), layer_sizes=layer_size, 57 | activation_fn=tf.nn.relu, output_nonlinearity=None) 58 | tan_actions = tf.tanh(raw_actions) 59 | 60 | saver = tf.train.Saver() 61 | 62 | with tf.Session() as sess: 63 | # restore the trained model 64 | ckpt = tf.train.get_checkpoint_state(SHARED_PARAMS['model_save_path']) 65 | saver.restore(sess, arg_parser.model) 66 | 67 | # TODO: roll-out with the trained policy in V-REP 68 | observation = np.expand_dims(env.reset(), axis=0) # s_0, shape[1, 18] 69 | 70 | for t in range(ENV_PARAMS['max_path_length']): 71 | action = controller(observation) # action shape[1, 3] 72 | with open(viz_log_path + '/torques.txt', 'a+') as f: 73 | for a_t in action[0]: 74 | f.write(str(a_t) + ' ') 75 | f.write('\n') 76 | 77 | next_obs, reward, terminal, env_info = env.step(*action) # *action, shape[3] 78 | with open(viz_log_path + '/angle.txt', 'a+') as f: 79 | for s_t in next_obs[0: 3]: 80 | f.write(str(s_t) + ' ') 81 | f.write('\n') 82 | with open(viz_log_path + '/angle_velocity.txt', 'a+') as f: 83 | for s_t in next_obs[3: 6]: 84 | f.write(str(s_t) + ' ') 85 | f.write('\n') 86 | with open(viz_log_path + '/reward_t.txt', 'a+') as f: 87 | f.write(str(reward) + '\n') 88 | 89 | observation = np.expand_dims(next_obs, axis=0) # next_obs, shape[3] / observation, shape[1, 3] 90 | 91 | if terminal: 92 | for i in range(5): 93 | env.grip() 94 | time.sleep(1) 95 | break 96 | 97 | env.terminate() 98 | -------------------------------------------------------------------------------- /remoteApi-3.4.0-x64.dll: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ycz0512/SoftQLearning4SpaceRobots/d8166f411dfd71025913bf261c351f7e31e6a8b5/remoteApi-3.4.0-x64.dll -------------------------------------------------------------------------------- /remoteApi-3.4.0-x64.dylib: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ycz0512/SoftQLearning4SpaceRobots/d8166f411dfd71025913bf261c351f7e31e6a8b5/remoteApi-3.4.0-x64.dylib -------------------------------------------------------------------------------- /remoteApi-3.4.0-x64.so: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ycz0512/SoftQLearning4SpaceRobots/d8166f411dfd71025913bf261c351f7e31e6a8b5/remoteApi-3.4.0-x64.so -------------------------------------------------------------------------------- /requirements.txt: -------------------------------------------------------------------------------- 1 | 2 | # dependencies: 3 | path.py 4 | Mako 5 | Flask 6 | matplotlib 7 | six 8 | 9 | 10 | # pip 11 | cffi 12 | gtimer 13 | nose2 14 | psutil 15 | plotly 16 | PyPrind 17 | PyOpenGL 18 | cloudpickle 19 | cached_property 20 | 21 | joblib==0.12 22 | Theano==1.0.2 23 | Lasagne==0.2.dev1 24 | numpy==1.14.5 25 | tensorflow>=1.12.0,<2.0.0 26 | mkl-service==1.1.2 27 | mkl==2017.0.4 28 | -------------------------------------------------------------------------------- /softqlearning/algorithms/rl_algorithm.py: -------------------------------------------------------------------------------- 1 | import abc 2 | import gtimer as gt 3 | import tensorflow as tf 4 | import numpy as np 5 | from rllab.misc import logger 6 | from rllab.algos.base import Algorithm 7 | from experiment.hyper_parameters import SHARED_PARAMS 8 | from softqlearning.misc import tf_utils 9 | from softqlearning.misc.sampler import rollouts 10 | 11 | save_path = SHARED_PARAMS['model_save_path'] 12 | 13 | 14 | class RLAlgorithm(Algorithm): 15 | """Abstract RLAlgorithm. 16 | 17 | Implements the _train and _evaluate methods to be used 18 | by classes inheriting from RLAlgorithm. 19 | """ 20 | 21 | def __init__( 22 | self, 23 | sampler, 24 | n_epochs=1000, 25 | n_train_repeat=1, 26 | epoch_length=1000, 27 | eval_n_episodes=10, 28 | eval_render=False, 29 | ): 30 | """ 31 | Args: 32 | n_epochs (`int`): Number of epochs to run the training for. 33 | n_train_repeat (`int`): Number of times to repeat the training 34 | for single time step. 35 | epoch_length (`int`): Epoch length. 36 | eval_n_episodes (`int`): Number of rollouts to evaluate. 37 | eval_render (`int`): Whether or not to render the evaluation 38 | environment. 39 | """ 40 | self.sampler = sampler 41 | 42 | self._n_epochs = n_epochs 43 | self._n_train_repeat = n_train_repeat 44 | self._epoch_length = epoch_length 45 | 46 | self._eval_n_episodes = eval_n_episodes 47 | self._eval_render = eval_render 48 | 49 | self.env = None 50 | self.policy = None 51 | self.pool = None 52 | 53 | def _train(self, env, policy, pool, load=None): 54 | """Perform RL training. 55 | 56 | Args: 57 | env (`V-REP`): Environment used for training 58 | policy (`Policy`): Policy used for training 59 | pool (`PoolBase`): Sample pool to add samples to 60 | """ 61 | self._init_training() 62 | self.sampler.initialize(env, policy, pool) 63 | 64 | with tf_utils.get_default_session().as_default() as sess: 65 | if load is not None: 66 | saver = tf.train.Saver() 67 | saver.restore(sess, load) 68 | print('pre-trained model restored ...') 69 | gt.rename_root('RLAlgorithm') 70 | gt.reset() 71 | gt.set_def_unique(False) 72 | 73 | for epoch in gt.timed_for( 74 | range(self._n_epochs + 1), save_itrs=True): 75 | logger.push_prefix('Epoch #%d | ' % epoch) 76 | 77 | for t in range(self._epoch_length): 78 | self.sampler.sample() 79 | if not self.sampler.batch_ready(): 80 | continue 81 | gt.stamp('sample') 82 | 83 | for i in range(self._n_train_repeat): 84 | self._do_training( 85 | iteration=t + epoch * self._epoch_length, 86 | batch=self.sampler.random_batch()) 87 | gt.stamp('train') 88 | 89 | self._evaluate(policy, env) 90 | print('@ epoch %d : ' % epoch) 91 | gt.stamp('eval') 92 | 93 | params = self.get_snapshot(epoch) 94 | logger.save_itr_params(epoch, params) 95 | 96 | time_itrs = gt.get_times().stamps.itrs 97 | time_eval = time_itrs['eval'][-1] 98 | time_total = gt.get_times().total 99 | time_train = time_itrs.get('train', [0])[-1] 100 | time_sample = time_itrs.get('sample', [0])[-1] 101 | 102 | logger.record_tabular('time-train', time_train) 103 | logger.record_tabular('time-eval', time_eval) 104 | logger.record_tabular('time-sample', time_sample) 105 | logger.record_tabular('time-total', time_total) 106 | logger.record_tabular('epoch', epoch) 107 | 108 | self.sampler.log_diagnostics() 109 | 110 | logger.dump_tabular(with_prefix=False) 111 | logger.pop_prefix() 112 | 113 | if epoch % SHARED_PARAMS['pkl_gap'] == 0: 114 | saver = tf.train.Saver() 115 | saver.save(sess, save_path=save_path+'/model-'+str(epoch)+'.ckpt') 116 | print('Model saved ...') 117 | 118 | self.sampler.terminate() 119 | 120 | def _evaluate(self, policy, evaluation_env): 121 | """Perform evaluation for the current policy.""" 122 | 123 | if self._eval_n_episodes < 1: 124 | return 125 | 126 | # TODO: max_path_length should be a property of environment. 127 | paths = rollouts(evaluation_env, policy, self.sampler._max_path_length, 128 | self._eval_n_episodes) 129 | 130 | total_returns = [path['rewards'].sum() for path in paths] 131 | episode_lengths = [len(p['rewards']) for p in paths] 132 | 133 | logger.record_tabular('return-average', np.mean(total_returns)) 134 | logger.record_tabular('episode-length-avg', np.mean(episode_lengths)) 135 | 136 | if self.sampler.batch_ready(): 137 | batch = self.sampler.random_batch() 138 | self.log_diagnostics(batch) 139 | 140 | @abc.abstractmethod 141 | def log_diagnostics(self, batch): 142 | raise NotImplementedError 143 | 144 | @abc.abstractmethod 145 | def get_snapshot(self, epoch): 146 | raise NotImplementedError 147 | 148 | @abc.abstractmethod 149 | def _do_training(self, iteration, batch): 150 | raise NotImplementedError 151 | 152 | @abc.abstractmethod 153 | def _init_training(self): 154 | raise NotImplementedError 155 | -------------------------------------------------------------------------------- /softqlearning/algorithms/sql.py: -------------------------------------------------------------------------------- 1 | import numpy as np 2 | import tensorflow as tf 3 | 4 | from rllab.misc import logger 5 | from rllab.misc.overrides import overrides 6 | from softqlearning.misc.kernel import adaptive_isotropic_gaussian_kernel 7 | from softqlearning.misc import tf_utils 8 | from softqlearning.algorithms.rl_algorithm import RLAlgorithm 9 | 10 | EPS = 1e-6 11 | 12 | 13 | def assert_shape(tensor, expected_shape): 14 | tensor_shape = tensor.shape.as_list() 15 | assert len(tensor_shape) == len(expected_shape) 16 | assert all([a == b for a, b in zip(tensor_shape, expected_shape)]) 17 | 18 | 19 | class SQL(RLAlgorithm): 20 | """Soft Q-learning (SQL). 21 | 22 | Example: 23 | See `examples/mujoco_all_sql.py`. 24 | 25 | Reference: 26 | [1] Tuomas Haarnoja, Haoran Tang, Pieter Abbeel, and Sergey Levine, 27 | "Reinforcement Learning with Deep Energy-Based Policies," International 28 | Conference on Machine Learning, 2017. https://arxiv.org/abs/1702.08165 29 | """ 30 | 31 | def __init__( 32 | self, 33 | base_kwargs, 34 | env, 35 | pool, 36 | qf, 37 | policy, 38 | plotter=None, 39 | policy_lr=1E-3, 40 | qf_lr=1E-3, 41 | value_n_particles=16, 42 | td_target_update_interval=1, 43 | kernel_fn=adaptive_isotropic_gaussian_kernel, 44 | kernel_n_particles=16, 45 | kernel_update_ratio=0.5, 46 | discount=0.99, 47 | reward_scale=1, 48 | use_saved_qf=False, 49 | use_saved_policy=False, 50 | save_full_state=False, 51 | train_qf=True, 52 | train_policy=True, 53 | ): 54 | """ 55 | Args: 56 | base_kwargs (dict): Dictionary of base arguments that are directly 57 | passed to the base `RLAlgorithm` constructor. 58 | env (`rllab.Env`): rllab environment object. 59 | pool (`PoolBase`): Replay buffer to add gathered samples to. 60 | qf (`NNQFunction`): Q-function approximator. 61 | policy: (`rllab.NNPolicy`): A policy function approximator. 62 | plotter (`QFPolicyPlotter`): Plotter instance to be used for 63 | visualizing Q-function during training. 64 | qf_lr (`float`): Learning rate used for the Q-function approximator. 65 | value_n_particles (`int`): The number of action samples used for 66 | estimating the value of next state. 67 | td_target_update_interval (`int`): How often the target network is 68 | updated to match the current Q-function. 69 | kernel_fn (function object): A function object that represents 70 | a kernel function. 71 | kernel_n_particles (`int`): Total number of particles per state 72 | used in SVGD updates. 73 | kernel_update_ratio ('float'): The ratio of SVGD particles used for 74 | the computation of the inner/outer empirical expectation. 75 | discount ('float'): Discount factor. 76 | reward_scale ('float'): A factor that scales the raw rewards. 77 | Useful for adjusting the temperature of the optimal Boltzmann 78 | distribution. 79 | use_saved_qf ('boolean'): If true, use the initial parameters provided 80 | in the Q-function instead of reinitializing. 81 | use_saved_policy ('boolean'): If true, use the initial parameters provided 82 | in the policy instead of reinitializing. 83 | save_full_state ('boolean'): If true, saves the full algorithm 84 | state, including the replay buffer. 85 | """ 86 | super(SQL, self).__init__(**base_kwargs) 87 | 88 | self.env = env 89 | self.pool = pool 90 | self.qf = qf 91 | self.policy = policy 92 | self.plotter = plotter 93 | 94 | self._qf_lr = qf_lr 95 | self._policy_lr = policy_lr 96 | self._discount = discount 97 | self._reward_scale = reward_scale 98 | 99 | self._value_n_particles = value_n_particles 100 | self._qf_target_update_interval = td_target_update_interval 101 | 102 | self._kernel_fn = kernel_fn 103 | self._kernel_n_particles = kernel_n_particles 104 | self._kernel_update_ratio = kernel_update_ratio 105 | 106 | self._save_full_state = save_full_state 107 | self._train_qf = train_qf 108 | self._train_policy = train_policy 109 | 110 | self._env_spec = self.env.spec 111 | self._observation_dim = self._env_spec.observation_space.flat_dim 112 | self._action_dim = self._env_spec.action_space.flat_dim 113 | 114 | self._create_placeholders() 115 | 116 | self._training_ops = [] 117 | self._target_ops = [] 118 | 119 | self._create_td_update() 120 | self._create_svgd_update() 121 | self._create_target_ops() 122 | 123 | self.n = 0 124 | 125 | if use_saved_qf: 126 | saved_qf_params = qf.get_param_values() 127 | if use_saved_policy: 128 | saved_policy_params = policy.get_param_values() 129 | 130 | self._sess = tf_utils.get_default_session() 131 | self._sess.run(tf.global_variables_initializer()) 132 | 133 | if use_saved_qf: 134 | self.qf.set_param_values(saved_qf_params) 135 | if use_saved_policy: 136 | self.policy.set_param_values(saved_policy_params) 137 | 138 | def _create_placeholders(self): 139 | """Create all necessary placeholders.""" 140 | 141 | self._observations_ph = tf.placeholder( 142 | tf.float32, 143 | shape=[None, self._observation_dim], 144 | name='observations') 145 | 146 | self._next_observations_ph = tf.placeholder( 147 | tf.float32, 148 | shape=[None, self._observation_dim], 149 | name='next_observations') 150 | 151 | self._actions_pl = tf.placeholder( 152 | tf.float32, shape=[None, self._action_dim], name='actions') 153 | 154 | self._next_actions_ph = tf.placeholder( 155 | tf.float32, shape=[None, self._action_dim], name='next_actions') 156 | 157 | self._rewards_pl = tf.placeholder( 158 | tf.float32, shape=[None], name='rewards') 159 | 160 | self._terminals_pl = tf.placeholder( 161 | tf.float32, shape=[None], name='terminals') 162 | 163 | def _create_td_update(self): 164 | """Create a minimization operation for Q-function update.""" 165 | 166 | with tf.variable_scope('target'): 167 | # The value of the next state is approximated with uniform samples. 168 | target_actions = tf.random_uniform( 169 | (1, self._value_n_particles, self._action_dim), -1, 1) 170 | q_value_targets = self.qf.output_for( 171 | observations=self._next_observations_ph[:, None, :], 172 | actions=target_actions) 173 | assert_shape(q_value_targets, [None, self._value_n_particles]) 174 | 175 | self._q_values = self.qf.output_for( 176 | self._observations_ph, self._actions_pl, reuse=True) 177 | assert_shape(self._q_values, [None]) 178 | 179 | # Equation 10: 180 | next_value = tf.reduce_logsumexp(q_value_targets, axis=1) 181 | assert_shape(next_value, [None]) 182 | 183 | # Importance weights add just a constant to the value. 184 | next_value -= tf.log(tf.cast(self._value_n_particles, tf.float32)) 185 | next_value += self._action_dim * np.log(2) 186 | 187 | # \hat Q in Equation 11: 188 | ys = tf.stop_gradient(self._reward_scale * self._rewards_pl + ( 189 | 1 - self._terminals_pl) * self._discount * next_value) 190 | assert_shape(ys, [None]) 191 | 192 | # Equation 11: 193 | bellman_residual = 0.5 * tf.reduce_mean((ys - self._q_values)**2) 194 | 195 | if self._train_qf: 196 | td_train_op = tf.train.AdamOptimizer(self._qf_lr).minimize( 197 | loss=bellman_residual, var_list=self.qf.get_params_internal()) 198 | self._training_ops.append(td_train_op) 199 | 200 | self._bellman_residual = bellman_residual 201 | 202 | def _create_svgd_update(self): 203 | """Create a minimization operation for policy update (SVGD).""" 204 | 205 | actions = self.policy.actions_for( 206 | observations=self._observations_ph, 207 | n_action_samples=self._kernel_n_particles, 208 | reuse=True) 209 | assert_shape(actions, 210 | [None, self._kernel_n_particles, self._action_dim]) 211 | 212 | # SVGD requires computing two empirical expectations over actions 213 | # (see Appendix C1.1.). To that end, we first sample a single set of 214 | # actions, and later split them into two sets: `fixed_actions` are used 215 | # to evaluate the expectation indexed by `i` and `updated_actions` 216 | # the expectation indexed by `j`. 217 | n_updated_actions = int( 218 | self._kernel_n_particles * self._kernel_update_ratio) 219 | n_fixed_actions = self._kernel_n_particles - n_updated_actions 220 | 221 | fixed_actions, updated_actions = tf.split( 222 | actions, [n_fixed_actions, n_updated_actions], axis=1) 223 | fixed_actions = tf.stop_gradient(fixed_actions) 224 | assert_shape(fixed_actions, [None, n_fixed_actions, self._action_dim]) 225 | assert_shape(updated_actions, 226 | [None, n_updated_actions, self._action_dim]) 227 | 228 | svgd_target_values = self.qf.output_for( 229 | self._observations_ph[:, None, :], fixed_actions, reuse=True) 230 | 231 | # Target log-density. Q_soft in Equation 13: 232 | squash_correction = tf.reduce_sum( 233 | tf.log(1 - fixed_actions**2 + EPS), axis=-1) 234 | log_p = svgd_target_values + squash_correction 235 | 236 | grad_log_p = tf.gradients(log_p, fixed_actions)[0] 237 | grad_log_p = tf.expand_dims(grad_log_p, axis=2) 238 | grad_log_p = tf.stop_gradient(grad_log_p) 239 | assert_shape(grad_log_p, [None, n_fixed_actions, 1, self._action_dim]) 240 | 241 | kernel_dict = self._kernel_fn(xs=fixed_actions, ys=updated_actions) 242 | 243 | # Kernel function in Equation 13: 244 | kappa = tf.expand_dims(kernel_dict["output"], dim=3) 245 | assert_shape(kappa, [None, n_fixed_actions, n_updated_actions, 1]) 246 | 247 | # Stein Variational Gradient in Equation 13: 248 | action_gradients = tf.reduce_mean( 249 | kappa * grad_log_p + kernel_dict["gradient"], reduction_indices=1) 250 | assert_shape(action_gradients, 251 | [None, n_updated_actions, self._action_dim]) 252 | 253 | # Propagate the gradient through the policy network (Equation 14). 254 | gradients = tf.gradients( 255 | updated_actions, 256 | self.policy.get_params_internal(), 257 | grad_ys=action_gradients) 258 | 259 | surrogate_loss = tf.reduce_sum([ 260 | tf.reduce_sum(w * tf.stop_gradient(g)) 261 | for w, g in zip(self.policy.get_params_internal(), gradients) 262 | ]) 263 | 264 | if self._train_policy: 265 | optimizer = tf.train.AdamOptimizer(self._policy_lr) 266 | svgd_training_op = optimizer.minimize( 267 | loss=-surrogate_loss, 268 | var_list=self.policy.get_params_internal()) 269 | self._training_ops.append(svgd_training_op) 270 | 271 | def _create_target_ops(self): 272 | """Create tensorflow operation for updating the target Q-function.""" 273 | if not self._train_qf: 274 | return 275 | 276 | source_params = self.qf.get_params_internal() 277 | target_params = self.qf.get_params_internal(scope='target') 278 | 279 | self._target_ops = [ 280 | tf.assign(tgt, src) 281 | for tgt, src in zip(target_params, source_params) 282 | ] 283 | 284 | # TODO: do not pass, policy, and pool to `__init__` directly. 285 | def train(self, load=None): 286 | self._train(self.env, self.policy, self.pool, load=load) 287 | 288 | @overrides 289 | def _init_training(self): 290 | self._sess.run(self._target_ops) 291 | 292 | @overrides 293 | def _do_training(self, iteration, batch): 294 | """Run the operations for updating training and target ops.""" 295 | 296 | feed_dict = self._get_feed_dict(batch) 297 | self._sess.run(self._training_ops, feed_dict) 298 | 299 | if iteration % self._qf_target_update_interval == 0 and self._train_qf: 300 | self._sess.run(self._target_ops) 301 | 302 | def _get_feed_dict(self, batch): 303 | """Construct a TensorFlow feed dictionary from a sample batch.""" 304 | 305 | feeds = { 306 | self._observations_ph: batch['observations'], 307 | self._actions_pl: batch['actions'], 308 | self._next_observations_ph: batch['next_observations'], 309 | self._rewards_pl: batch['rewards'], 310 | self._terminals_pl: batch['terminals'], 311 | } 312 | 313 | return feeds 314 | 315 | @overrides 316 | def log_diagnostics(self, batch): 317 | """Record diagnostic information. 318 | 319 | Records the mean and standard deviation of Q-function and the 320 | squared Bellman residual of the s (mean squared Bellman error) 321 | for a sample batch. 322 | 323 | Also call the `draw` method of the plotter, if plotter is defined. 324 | """ 325 | 326 | feeds = self._get_feed_dict(batch) 327 | qf, bellman_residual = self._sess.run( 328 | [self._q_values, self._bellman_residual], feeds) 329 | 330 | logger.record_tabular('qf-avg', np.mean(qf)) 331 | logger.record_tabular('mean-sq-bellman-error', bellman_residual) 332 | 333 | self.n += 1 334 | 335 | @overrides 336 | def get_snapshot(self, epoch): 337 | """Return loggable snapshot of the SQL algorithm. 338 | 339 | If `self._save_full_state == True`, returns snapshot including the 340 | replay buffer. If `self._save_full_state == False`, returns snapshot 341 | of policy, Q-function, and environment instances. 342 | """ 343 | 344 | state = { 345 | 'epoch': epoch, 346 | 'policy': self.policy, 347 | 'qf': self.qf, 348 | 'env': self.env, 349 | } 350 | 351 | if self._save_full_state: 352 | state.update({'replay_buffer': self.pool}) 353 | 354 | return state 355 | -------------------------------------------------------------------------------- /softqlearning/environment/space_robot_3link.py: -------------------------------------------------------------------------------- 1 | import vrep 2 | import numpy as np 3 | 4 | from experiment.hyper_parameters import ENV_PARAMS 5 | 6 | 7 | class BundleType(object): 8 | """ 9 | This class bundles many fields, similar to a record or a mutable 10 | namedtuple. 11 | """ 12 | def __init__(self, variables): 13 | for var, val in variables.items(): 14 | object.__setattr__(self, var, val) 15 | 16 | # Freeze fields so new ones cannot be set. 17 | def __setattr__(self, key, value): 18 | if not hasattr(self, key): 19 | raise AttributeError("%r has no attribute %s" % (self, key)) 20 | object.__setattr__(self, key, value) 21 | 22 | 23 | class EnvSpec(BundleType): 24 | """ Collection of iteration variables. """ 25 | def __init__(self): 26 | variables = { 27 | 'action_space': None, # object. 28 | 'observation_space': None, # object. 29 | } 30 | BundleType.__init__(self, variables) 31 | 32 | 33 | class Dimension(BundleType): 34 | """ Collection of iteration variables. """ 35 | def __init__(self): 36 | variables = { 37 | 'flat_dim': None, # object. 38 | } 39 | BundleType.__init__(self, variables) 40 | 41 | 42 | class SpaceRobot3link(object): 43 | 44 | def __init__(self): 45 | self.handles = {} 46 | self.action_dims = 3 47 | self.obs_dims = 18 48 | 49 | self.env_spec = EnvSpec() 50 | self.env_spec.action_space = Dimension() 51 | self.env_spec.observation_space = Dimension() 52 | self.env_spec.action_space.flat_dim = self.action_dims 53 | self.env_spec.observation_space.flat_dim = self.obs_dims 54 | 55 | self.joint_target_velocities = np.ones(self.action_dims) * 10000 # make it gigantic enough to be the torque mode 56 | self.cur_obs = None # current observation s_t 57 | self.num_episode = 1 58 | self.t = 1 # the current time t for a trajectory. 59 | 60 | self._max_episode_length = ENV_PARAMS['max_path_length'] # t = {0, 1, ..., T}, T < max_episode_length. 61 | self.w1 = ENV_PARAMS['reward_factor_w1'] 62 | self.w_log = ENV_PARAMS['reward_factor_wlog'] 63 | self.w2 = ENV_PARAMS['reward_factor_w2'] 64 | self.alpha = ENV_PARAMS['alpha'] 65 | self.tol_1 = ENV_PARAMS['distance_tolerance'] 66 | self.tol_2 = ENV_PARAMS['torques_norm_tolerance'] 67 | self._max_torque = ENV_PARAMS['max_torque'] 68 | self.final_phase_scaler = ENV_PARAMS['final_phase_reward_scaler'] 69 | 70 | @property 71 | def spec(self): 72 | return self.env_spec 73 | 74 | def _init_vrep(self): # get clientID 75 | vrep.simxFinish(-1) # end all running communication threads 76 | clientID = vrep.simxStart('127.0.0.1', 19997, True, False, 5000, 0) # get the clientID to communicate with the current V-REP 77 | self.clientID = clientID 78 | 79 | if self.clientID != -1: # clientID = -1 means connection failed.(time-out) 80 | print('\n' + 'Connected to remote V-REP server.') 81 | else: 82 | print('\n' + 'Connection time-out !') 83 | raise Exception('Connection Failed !') 84 | 85 | vrep.simxSynchronous(self.clientID, True) # enable synchronous operation to V-REP 86 | 87 | def _get_handles(self): # get handles of objects in V-REP 88 | joint_names = ['Joint_1', 'Joint_2', 'Joint_3', 'Gjoint_1', 'Gjoint_2'] # object joint names in V-REP 89 | joint_handles = [vrep.simxGetObjectHandle(self.clientID, joint_names[i], vrep.simx_opmode_blocking)[1] 90 | for i in range(len(joint_names))] # retrieve object joint handles based on its name as a list 91 | 92 | base_handles = [vrep.simxGetObjectHandle(self.clientID, 'Base', vrep.simx_opmode_blocking)[1]] 93 | 94 | point_names = ['EE_point', 'EE_target_point'] # object EE_point names in V-REP 95 | point_handles = [vrep.simxGetObjectHandle(self.clientID, point, vrep.simx_opmode_blocking)[1] 96 | for point in point_names] # retrieve object EE_point handles as a list based on its name 97 | 98 | # handles dict 99 | self.handles['joint'] = joint_handles 100 | self.handles['base'] = base_handles 101 | self.handles['points'] = point_handles 102 | 103 | def _configure_initial_state(self, condition=0): 104 | # TODO: if we want to train the policy and Q-function under different initial configurations. 105 | pass 106 | 107 | def _get_observation(self): # get current observations s_t 108 | state = np.zeros(self.obs_dims) 109 | # state is [θ1, θ2, θ3, ω1, ω2, ω3, Base_α, Base_β, Base_γ, 110 | # Base_x, Base_y, Base_z, Vx, Vy, Vz, dα, dβ, dγ] 111 | 112 | Joint_angle = [vrep.simxGetJointPosition(self.clientID, self.handles['joint'][i], vrep.simx_opmode_blocking)[1] 113 | for i in range(3)] # retrieve the rotation angle as [θ1, θ2, θ3] 114 | state[0: 3] = Joint_angle 115 | 116 | Joint_velocity = [vrep.simxGetObjectFloatParameter(self.clientID, self.handles['joint'][i], 2012, vrep.simx_opmode_blocking)[1] 117 | for i in range(3)] # retrieve the joint velocity as [ω1, ω2, ω3] 118 | state[3: 6] = Joint_velocity 119 | 120 | Base_pose = [vrep.simxGetObjectOrientation(self.clientID, self.handles['base'][0], 121 | -1, vrep.simx_opmode_blocking)[1]] 122 | state[6: 9] = Base_pose[0] # retrieve the orientation of Base as [Base_α, Base_β, Base_γ] 123 | 124 | Base_position = [vrep.simxGetObjectPosition(self.clientID, self.handles['base'][0], 125 | -1, vrep.simx_opmode_blocking)[1]] 126 | state[9: 12] = Base_position[0] # retrieve the position of Base as [Base_x, Base_y, Base_z] 127 | 128 | _, Base_Vel, Base_Ang_Vel = vrep.simxGetObjectVelocity(self.clientID, self.handles['base'][0], 129 | vrep.simx_opmode_blocking) 130 | state[12: 15] = Base_Vel # retrieve the linear velocity of Base as [Vx, Vy, Vz] 131 | state[15: 18] = Base_Ang_Vel # retrieve the angular velocity of Base as [dα, dβ, dγ] 132 | 133 | state = np.asarray(state) 134 | 135 | return state 136 | 137 | def _set_joint_effort(self, U): # set torque U = [u1, u2, u3] to 3 joints in V-REP 138 | torque = [vrep.simxGetJointForce(self.clientID, self.handles['joint'][i], vrep.simx_opmode_blocking)[1] 139 | for i in range(self.action_dims)] # retrieve the current torque from the joints as [jt1, jt2, jt3] 140 | 141 | if len(U) != self.action_dims: 142 | raise Exception('the dimension of action is wrong.') 143 | 144 | # Give the torque and targeted velocity to joints. 145 | for i in range(self.action_dims): 146 | 147 | if U[i] > self._max_torque: # limit the torque of each joint under max_torque 148 | U[i] = self._max_torque 149 | 150 | if np.sign(torque[i]) * np.sign(U[i]) < 0: 151 | self.joint_target_velocities[i] *= -1 152 | 153 | _ = vrep.simxSetJointTargetVelocity(self.clientID, self.handles['joint'][i], 154 | self.joint_target_velocities[i], 155 | vrep.simx_opmode_blocking) 156 | # Just in case 157 | if _ != 0: 158 | print('set target velocity error %s' % _) 159 | raise Exception('failed to set target velocity to joints.') 160 | 161 | _ = vrep.simxSetJointForce(self.clientID, self.handles['joint'][i], 162 | abs(U[i]), vrep.simx_opmode_blocking) 163 | # Just in case 164 | if _ != 0: 165 | print('set torques error %s' % _) 166 | raise Exception('failed to set torques to joints.') 167 | 168 | def grip(self): # gripper close 169 | for i in range(3, 5): 170 | _ = vrep.simxSetJointTargetPosition(self.clientID, self.handles['joint'][i], 0, vrep.simx_opmode_blocking) 171 | # Just in case 172 | if _ != 0: 173 | print('set target position error %s' % _) 174 | raise Exception('failed to set target position to joints.') 175 | 176 | vrep.simxSynchronousTrigger(self.clientID) 177 | 178 | def _reward(self, U): # get the current reward 179 | # TODO: define the immediate reward function 180 | # want to minimize the distance between EE_point and EE_target_position 181 | EE_position = vrep.simxGetObjectPosition(self.clientID, self.handles['points'][0], 182 | -1, vrep.simx_opmode_blocking)[1] 183 | EE_target_position = vrep.simxGetObjectPosition(self.clientID, self.handles['points'][1], 184 | -1, vrep.simx_opmode_blocking)[1] 185 | distance_square = np.sum(np.subtract(EE_position, EE_target_position)**2) 186 | 187 | # don't want the given torque to be too large 188 | U_norm = np.sum(U**2) 189 | 190 | reward = - self.w1 * distance_square - self.w_log * np.log(distance_square+self.alpha) - self.w2 * U_norm 191 | 192 | # TODO: define the function for judging whether the simulation should be stopped. 193 | terminal_flag = False 194 | if np.sqrt(distance_square) < self.tol_1 and U_norm < self.tol_2: 195 | terminal_flag = True 196 | 197 | # TODO: define the function to specify the env information. 198 | env_info = {} 199 | 200 | return reward, terminal_flag, env_info 201 | 202 | def reset(self): # reset the env 203 | if self.num_episode != 1: 204 | self.terminate() 205 | print('Episode Ended ...') 206 | 207 | self._init_vrep() 208 | self._get_handles() 209 | self._configure_initial_state() 210 | vrep.simxStartSimulation(self.clientID, vrep.simx_opmode_blocking) 211 | print('_________________________ Start Episode %d _________________________' % self.num_episode) 212 | self.t = 1 213 | self.num_episode += 1 214 | self.cur_obs = self._get_observation() # get current observation s_t 215 | 216 | return self.cur_obs 217 | 218 | def step(self, action): # execute one step in env 219 | self._set_joint_effort(action) 220 | 221 | # send a synchronization trigger signal to inform V-REP to execute the next simulation step 222 | vrep.simxSynchronousTrigger(self.clientID) 223 | vrep.simxGetPingTime(self.clientID) 224 | 225 | Reward, ter_flag, env_info = self._reward(action) # ter_flag: True if finish the task 226 | 227 | # TODO: define the scaled reward 228 | if self.t < self._max_episode_length * 0.8: 229 | scaled_reward = (self.t / self._max_episode_length) * Reward 230 | else: 231 | scaled_reward = (self.final_phase_scaler * self.t / self._max_episode_length) * Reward 232 | 233 | self.t += 1 234 | 235 | next_observation = self._get_observation() 236 | self.cur_obs = next_observation 237 | 238 | return next_observation, scaled_reward, ter_flag, env_info 239 | 240 | def terminate(self): # end simulation 241 | vrep.simxStopSimulation(self.clientID, vrep.simx_opmode_blocking) 242 | vrep.simxGetPingTime(self.clientID) 243 | vrep.simxFinish(self.clientID) 244 | -------------------------------------------------------------------------------- /softqlearning/environment/space_robot_double_3links.py: -------------------------------------------------------------------------------- 1 | import vrep 2 | import numpy as np 3 | 4 | from experiment.hyper_parameters import ENV_PARAMS 5 | 6 | 7 | class BundleType(object): 8 | """ 9 | This class bundles many fields, similar to a record or a mutable 10 | namedtuple. 11 | """ 12 | def __init__(self, variables): 13 | for var, val in variables.items(): 14 | object.__setattr__(self, var, val) 15 | 16 | # Freeze fields so new ones cannot be set. 17 | def __setattr__(self, key, value): 18 | if not hasattr(self, key): 19 | raise AttributeError("%r has no attribute %s" % (self, key)) 20 | object.__setattr__(self, key, value) 21 | 22 | 23 | class EnvSpec(BundleType): 24 | """ Collection of iteration variables. """ 25 | def __init__(self): 26 | variables = { 27 | 'action_space': None, # object. 28 | 'observation_space': None, # object. 29 | } 30 | BundleType.__init__(self, variables) 31 | 32 | 33 | class Dimension(BundleType): 34 | """ Collection of iteration variables. """ 35 | def __init__(self): 36 | variables = { 37 | 'flat_dim': None, # object. 38 | } 39 | BundleType.__init__(self, variables) 40 | 41 | 42 | class SpaceRobotDouble3link(object): 43 | 44 | def __init__(self): 45 | self.handles = {} 46 | self.action_dims = 6 47 | self.obs_dims = 24 48 | 49 | self.env_spec = EnvSpec() 50 | self.env_spec.action_space = Dimension() 51 | self.env_spec.observation_space = Dimension() 52 | self.env_spec.action_space.flat_dim = self.action_dims 53 | self.env_spec.observation_space.flat_dim = self.obs_dims 54 | 55 | self.joint_target_velocities = np.ones(self.action_dims) * 10000 # make it gigantic enough to be the torque mode 56 | self.cur_obs = None # current observation s_t 57 | self.num_episode = 1 58 | self.t = 1 # the current time t for a trajectory. 59 | 60 | self._max_episode_length = ENV_PARAMS['max_path_length'] # t = {0, 1, ..., T}, T < max_episode_length. 61 | self.w1 = ENV_PARAMS['reward_factor_w1'] 62 | self.w_log = ENV_PARAMS['reward_factor_wlog'] 63 | self.w2 = ENV_PARAMS['reward_factor_w2'] 64 | self.alpha = ENV_PARAMS['alpha'] 65 | self.tol_1 = ENV_PARAMS['distance_tolerance'] 66 | self.tol_2 = ENV_PARAMS['torques_norm_tolerance'] 67 | self._max_torque = ENV_PARAMS['max_torque'] 68 | self.final_phase_scaler = ENV_PARAMS['final_phase_reward_scaler'] 69 | 70 | @property 71 | def spec(self): 72 | return self.env_spec 73 | 74 | def _init_vrep(self): # get clientID 75 | vrep.simxFinish(-1) # end all running communication threads 76 | clientID = vrep.simxStart('127.0.0.1', 19997, True, False, 5000, 0) # get the clientID to communicate with the current V-REP 77 | self.clientID = clientID 78 | 79 | if self.clientID != -1: # clientID = -1 means connection failed.(time-out) 80 | print('\n' + 'Connected to remote V-REP server.') 81 | else: 82 | print('\n' + 'Connection time-out !') 83 | raise Exception('Connection Failed !') 84 | 85 | vrep.simxSynchronous(self.clientID, True) # enable synchronous operation to V-REP 86 | 87 | def _get_handles(self): # get handles of objects in V-REP 88 | joint_names = ['Joint_1', 'Joint_2', 'Joint_3', 'Joint_4', 'Joint_5', 'Joint_6', 89 | 'Gjoint_1', 'Gjoint_2', 'Gjoint_3', 'Gjoint_4'] # object joint names in V-REP 90 | joint_handles = [vrep.simxGetObjectHandle(self.clientID, joint_names[i], vrep.simx_opmode_blocking)[1] 91 | for i in range(len(joint_names))] # retrieve object joint handles based on its name as a list 92 | 93 | base_handles = [vrep.simxGetObjectHandle(self.clientID, 'Base', vrep.simx_opmode_blocking)[1]] 94 | 95 | point_names = ['EE_point_1', 'EE_target_point1', 'EE_point_2', 'EE_target_point2'] # object EE_point names in V-REP 96 | point_handles = [vrep.simxGetObjectHandle(self.clientID, point, vrep.simx_opmode_blocking)[1] 97 | for point in point_names] # retrieve object EE_point handles as a list based on its name 98 | 99 | # handles dict 100 | self.handles['joint'] = joint_handles 101 | self.handles['base'] = base_handles 102 | self.handles['points'] = point_handles 103 | 104 | def _configure_initial_state(self, condition=0): 105 | # TODO: if we want to train the policy and Q-function under different initial configurations. 106 | pass 107 | 108 | def _get_observation(self): # get current observations s_t 109 | state = np.zeros(self.obs_dims) 110 | # state is [θ1, θ2, θ3, θ4, θ5, θ6, ω1, ω2, ω3, ω4, ω5, ω6, 111 | # Base_x, Base_y, Base_z, Base_α, Base_β, Base_γ, 112 | # Vx, Vy, Vz, dα, dβ, dγ] 113 | 114 | Joint_angle = [vrep.simxGetJointPosition(self.clientID, self.handles['joint'][i], 115 | vrep.simx_opmode_blocking)[1] 116 | for i in range(6)] # retrieve the rotation angle as [θ1, θ2, θ3, θ4, θ5, θ6] 117 | state[0: 6] = Joint_angle 118 | 119 | Joint_velocity = [vrep.simxGetObjectFloatParameter(self.clientID, self.handles['joint'][i], 120 | 2012, vrep.simx_opmode_blocking)[1] 121 | for i in range(6)] # retrieve the joint velocity as [ω1, ω2, ω3, ω4, ω5, ω6] 122 | state[6: 12] = Joint_velocity 123 | 124 | Base_position = [vrep.simxGetObjectPosition(self.clientID, self.handles['base'][0], 125 | -1, vrep.simx_opmode_blocking)[1]] 126 | state[12: 15] = Base_position[0] # retrieve the position of Base as [Base_x, Base_y, Base_z] 127 | 128 | Base_pose = [vrep.simxGetObjectOrientation(self.clientID, self.handles['base'][0], 129 | -1, vrep.simx_opmode_blocking)[1]] 130 | state[15: 18] = Base_pose[0] # retrieve the orientation of Base as [Base_α, Base_β, Base_γ] 131 | 132 | _, Base_Vel, Base_Ang_Vel = vrep.simxGetObjectVelocity(self.clientID, self.handles['base'][0], 133 | vrep.simx_opmode_blocking) 134 | state[18: 21] = Base_Vel # retrieve the linear velocity of Base as [Vx, Vy, Vz] 135 | state[21: 24] = Base_Ang_Vel # retrieve the angular velocity of Base as [dα, dβ, dγ] 136 | 137 | state = np.asarray(state) 138 | 139 | return state 140 | 141 | def _set_joint_effort(self, U): # set torque U = [u1, u2, u3, u4, u5, u6] to 6 joints in V-REP 142 | torque = [vrep.simxGetJointForce(self.clientID, self.handles['joint'][i], vrep.simx_opmode_blocking)[1] 143 | for i in range(self.action_dims)] # retrieve the current torque from the joints as [jt1, jt2, jt3, jt4, jt5, jt6] 144 | 145 | if len(U) != self.action_dims: 146 | raise Exception('the dimension of action is wrong.') 147 | 148 | # Give the torque and targeted velocity to joints. 149 | for i in range(self.action_dims): 150 | 151 | if U[i] > self._max_torque: # limit the torque of each joint under max_torque 152 | U[i] = self._max_torque 153 | 154 | if np.sign(torque[i]) * np.sign(U[i]) < 0: 155 | self.joint_target_velocities[i] *= -1 156 | 157 | _ = vrep.simxSetJointTargetVelocity(self.clientID, self.handles['joint'][i], 158 | self.joint_target_velocities[i], 159 | vrep.simx_opmode_blocking) 160 | # Just in case 161 | if _ != 0: 162 | print('set target velocity error %s' % _) 163 | raise Exception('failed to set target velocity to joints.') 164 | 165 | _ = vrep.simxSetJointForce(self.clientID, self.handles['joint'][i], 166 | abs(U[i]), vrep.simx_opmode_blocking) 167 | # Just in case 168 | if _ != 0: 169 | print('set torques error %s' % _) 170 | raise Exception('failed to set torques to joints.') 171 | 172 | def grip1(self): # gripper 1 close 173 | for i in range(6, 8): 174 | _ = vrep.simxSetJointTargetPosition(self.clientID, self.handles['joint'][i], 0, vrep.simx_opmode_blocking) 175 | # Just in case 176 | if _ != 0: 177 | print('set target position error %s' % _) 178 | raise Exception('failed to set target position to joints.') 179 | 180 | vrep.simxSynchronousTrigger(self.clientID) 181 | 182 | def grip2(self): # gripper 2 close 183 | for i in range(8, 10): 184 | _ = vrep.simxSetJointTargetPosition(self.clientID, self.handles['joint'][i], 0, vrep.simx_opmode_blocking) 185 | # Just in case 186 | if _ != 0: 187 | print('set target position error %s' % _) 188 | raise Exception('failed to set target position to joints.') 189 | 190 | vrep.simxSynchronousTrigger(self.clientID) 191 | 192 | def _reward(self, U): # get the current reward 193 | # TODO: define the immediate reward function 194 | # want to minimize the distance between EE_point and EE_target_position 195 | EE1_position = vrep.simxGetObjectPosition(self.clientID, self.handles['points'][0], 196 | -1, vrep.simx_opmode_blocking)[1] 197 | EE2_position = vrep.simxGetObjectPosition(self.clientID, self.handles['points'][2], 198 | -1, vrep.simx_opmode_blocking)[1] 199 | EE_target1_position = vrep.simxGetObjectPosition(self.clientID, self.handles['points'][1], 200 | -1, vrep.simx_opmode_blocking)[1] 201 | EE_target2_position = vrep.simxGetObjectPosition(self.clientID, self.handles['points'][3], 202 | -1, vrep.simx_opmode_blocking)[1] 203 | distance1_square = np.sum(np.subtract(EE1_position, EE_target1_position)**2) 204 | distance2_square = np.sum(np.subtract(EE2_position, EE_target2_position)**2) 205 | 206 | # TODO: define distance loss 207 | distance_square = distance1_square + distance2_square 208 | 209 | # don't want the given torque to be too large 210 | U_norm = np.sum(U**2) 211 | 212 | reward = - self.w1 * distance_square - self.w_log * np.log(distance_square+self.alpha) - self.w2 * U_norm 213 | 214 | # TODO: define the function for judging whether the simulation should be stopped. 215 | terminal_flag = False 216 | if np.sqrt(distance_square) < self.tol_1 and U_norm < self.tol_2: 217 | terminal_flag = True 218 | 219 | # TODO: define the function to specify the env information. 220 | env_info = {} 221 | 222 | return reward, terminal_flag, env_info 223 | 224 | def reset(self): # reset the env 225 | if self.num_episode != 1: 226 | self.terminate() 227 | print('Episode Ended ...') 228 | 229 | self._init_vrep() 230 | self._get_handles() 231 | self._configure_initial_state() 232 | vrep.simxStartSimulation(self.clientID, vrep.simx_opmode_blocking) 233 | print('_________________________ Start Episode %d _________________________' % self.num_episode) 234 | self.t = 1 235 | self.num_episode += 1 236 | self.cur_obs = self._get_observation() # get current observation s_t 237 | 238 | return self.cur_obs 239 | 240 | def step(self, action): # execute one step in env 241 | self._set_joint_effort(action) 242 | 243 | # torque = [vrep.simxGetJointForce(self.clientID, self.handles['joint'][i], vrep.simx_opmode_blocking)[1] 244 | # for i in range(self.action_dims)] # retrieve the current torque from the joints as [jt1, jt2, jt3, jt4, jt5, jt6] 245 | # print('now=', torque, 'U=', action) 246 | 247 | # send a synchronization trigger signal to inform V-REP to execute the next simulation step 248 | vrep.simxSynchronousTrigger(self.clientID) 249 | vrep.simxGetPingTime(self.clientID) 250 | 251 | Reward, ter_flag, env_info = self._reward(action) # ter_flag: True if finish the task 252 | 253 | # TODO: define the scaled reard 254 | if self.t < self._max_episode_length * 0.8: 255 | scaled_reward = (self.t / self._max_episode_length) * Reward 256 | else: 257 | scaled_reward = (self.final_phase_scaler * self.t / self._max_episode_length) * Reward 258 | 259 | self.t += 1 260 | 261 | next_observation = self._get_observation() 262 | self.cur_obs = next_observation 263 | 264 | return next_observation, scaled_reward, ter_flag, env_info 265 | 266 | def terminate(self): # end simulation 267 | vrep.simxStopSimulation(self.clientID, vrep.simx_opmode_blocking) 268 | vrep.simxGetPingTime(self.clientID) 269 | vrep.simxFinish(self.clientID) 270 | -------------------------------------------------------------------------------- /softqlearning/misc/kernel.py: -------------------------------------------------------------------------------- 1 | from distutils.version import StrictVersion 2 | 3 | import numpy as np 4 | import tensorflow as tf 5 | 6 | 7 | def adaptive_isotropic_gaussian_kernel(xs, ys, h_min=1e-3): 8 | """Gaussian kernel with dynamic bandwidth. 9 | 10 | The bandwidth is adjusted dynamically to match median_distance / log(Kx). 11 | See [2] for more information. 12 | 13 | Args: 14 | xs(`tf.Tensor`): A tensor of shape (N x Kx x D) containing N sets of Kx 15 | particles of dimension D. This is the first kernel argument. 16 | ys(`tf.Tensor`): A tensor of shape (N x Ky x D) containing N sets of Ky 17 | particles of dimension D. This is the second kernel argument. 18 | h_min(`float`): Minimum bandwidth. 19 | 20 | Returns: 21 | `dict`: Returned dictionary has two fields: 22 | 'output': A `tf.Tensor` object of shape (N x Kx x Ky) representing 23 | the kernel matrix for inputs `xs` and `ys`. 24 | 'gradient': A 'tf.Tensor` object of shape (N x Kx x Ky x D) 25 | representing the gradient of the kernel with respect to `xs`. 26 | 27 | Reference: 28 | [2] Qiang Liu,Dilin Wang, "Stein Variational Gradient Descent: A General 29 | Purpose Bayesian Inference Algorithm," Neural Information Processing 30 | Systems (NIPS), 2016. 31 | """ 32 | Kx, D = xs.get_shape().as_list()[-2:] 33 | Ky, D2 = ys.get_shape().as_list()[-2:] 34 | assert D == D2 35 | 36 | leading_shape = tf.shape(xs)[:-2] 37 | 38 | # Compute the pairwise distances of left and right particles. 39 | diff = tf.expand_dims(xs, -2) - tf.expand_dims(ys, -3) 40 | # ... x Kx x Ky x D 41 | 42 | if StrictVersion(tf.__version__) < StrictVersion('1.5.0'): 43 | dist_sq = tf.reduce_sum(diff**2, axis=-1, keep_dims=False) 44 | else: 45 | dist_sq = tf.reduce_sum(diff**2, axis=-1, keepdims=False) 46 | # ... x Kx x Ky 47 | 48 | # Get median. 49 | input_shape = tf.concat((leading_shape, [Kx * Ky]), axis=0) 50 | values, _ = tf.nn.top_k( 51 | input=tf.reshape(dist_sq, input_shape), 52 | k=(Kx * Ky // 2 + 1), # This is exactly true only if Kx*Ky is odd. 53 | sorted=True) # ... x floor(Ks*Kd/2) 54 | 55 | medians_sq = values[..., -1] # ... (shape) (last element is the median) 56 | 57 | h = medians_sq / np.log(Kx) # ... (shape) 58 | h = tf.maximum(h, h_min) 59 | h = tf.stop_gradient(h) # Just in case. 60 | h_expanded_twice = tf.expand_dims(tf.expand_dims(h, -1), -1) 61 | # ... x 1 x 1 62 | 63 | kappa = tf.exp(-dist_sq / h_expanded_twice) # ... x Kx x Ky 64 | 65 | # Construct the gradient 66 | h_expanded_thrice = tf.expand_dims(h_expanded_twice, -1) 67 | # ... x 1 x 1 x 1 68 | kappa_expanded = tf.expand_dims(kappa, -1) # ... x Kx x Ky x 1 69 | 70 | kappa_grad = -2 * diff / h_expanded_thrice * kappa_expanded 71 | # ... x Kx x Ky x D 72 | 73 | return {"output": kappa, "gradient": kappa_grad} 74 | -------------------------------------------------------------------------------- /softqlearning/misc/nn.py: -------------------------------------------------------------------------------- 1 | import tensorflow as tf 2 | 3 | from rllab.core.serializable import Serializable 4 | from sandbox.rocky.tf.core.parameterized import Parameterized 5 | 6 | from softqlearning.misc import tf_utils 7 | 8 | 9 | def feedforward_net(inputs, 10 | layer_sizes, 11 | activation_fn=tf.nn.relu, 12 | output_nonlinearity=None): 13 | def bias(n_units): 14 | return tf.get_variable( 15 | name='bias', shape=n_units, initializer=tf.zeros_initializer()) 16 | 17 | def linear(x, n_units, postfix=None): 18 | input_size = x.shape[-1].value 19 | weight_name = 'weight' + '_' + str(postfix) if postfix else 'weight' 20 | weight = tf.get_variable( 21 | name=weight_name, 22 | shape=(input_size, n_units), 23 | initializer=tf.contrib.layers.xavier_initializer()) 24 | 25 | # `tf.tensordot` supports broadcasting 26 | return tf.tensordot(x, weight, axes=((-1, ), (0, ))) 27 | 28 | out = 0 29 | for i, layer_size in enumerate(layer_sizes): 30 | with tf.variable_scope('layer_{i}'.format(i=i)): 31 | if i == 0: 32 | for j, input_tensor in enumerate(inputs): 33 | out += linear(input_tensor, layer_size, j) 34 | else: 35 | out = linear(out, layer_size) 36 | 37 | out += bias(layer_size) 38 | 39 | if i < len(layer_sizes) - 1 and activation_fn: 40 | out = activation_fn(out) 41 | 42 | if output_nonlinearity: 43 | out = output_nonlinearity(out) 44 | 45 | return out 46 | 47 | 48 | class MLPFunction(Parameterized, Serializable): 49 | def __init__(self, inputs, name, hidden_layer_sizes): 50 | Parameterized.__init__(self) 51 | Serializable.quick_init(self, locals()) 52 | 53 | self._name = name 54 | self._inputs = inputs 55 | self._layer_sizes = list(hidden_layer_sizes) + [1] 56 | 57 | self._output = self._output_for(self._inputs) 58 | 59 | def _output_for(self, inputs, reuse=False): 60 | with tf.variable_scope(self._name, reuse=reuse): 61 | out = feedforward_net( 62 | inputs=inputs, 63 | output_nonlinearity=None, 64 | layer_sizes=self._layer_sizes) 65 | 66 | return out[..., 0] 67 | 68 | def _eval(self, inputs): 69 | feeds = {pl: val for pl, val in zip(self._inputs, inputs)} 70 | 71 | return tf_utils.get_default_session().run(self._output, feeds) 72 | 73 | def get_params_internal(self, scope='', **tags): 74 | if len(tags) > 0: 75 | raise NotImplementedError 76 | 77 | scope += '/' + self._name if scope else self._name 78 | 79 | return tf.get_collection(tf.GraphKeys.TRAINABLE_VARIABLES, scope=scope) 80 | -------------------------------------------------------------------------------- /softqlearning/misc/plotter.py: -------------------------------------------------------------------------------- 1 | import numpy as np 2 | import matplotlib.pyplot as plt 3 | 4 | 5 | class QFPolicyPlotter: 6 | def __init__(self, qf, policy, obs_lst, default_action, n_samples): 7 | self._qf = qf 8 | self._policy = policy 9 | self._obs_lst = obs_lst 10 | self._default_action = default_action 11 | self._n_samples = n_samples 12 | 13 | self._var_inds = np.where(np.isnan(default_action))[0] 14 | assert len(self._var_inds) == 2 15 | 16 | n_plots = len(obs_lst) 17 | 18 | x_size = 5 * n_plots 19 | y_size = 5 20 | 21 | fig = plt.figure(figsize=(x_size, y_size)) 22 | self._ax_lst = [] 23 | for i in range(n_plots): 24 | ax = fig.add_subplot(100 + n_plots * 10 + i + 1) 25 | ax.set_xlim((-1, 1)) 26 | ax.set_ylim((-1, 1)) 27 | ax.grid(True) 28 | self._ax_lst.append(ax) 29 | 30 | self._line_objects = list() 31 | 32 | def draw(self): 33 | # noinspection PyArgumentList 34 | [h.remove() for h in self._line_objects] 35 | self._line_objects = list() 36 | 37 | self._plot_level_curves() 38 | self._plot_action_samples() 39 | 40 | plt.draw() 41 | plt.pause(0.001) 42 | 43 | def _plot_level_curves(self): 44 | # Create mesh grid. 45 | xs = np.linspace(-1, 1, 50) 46 | ys = np.linspace(-1, 1, 50) 47 | xgrid, ygrid = np.meshgrid(xs, ys) 48 | N = len(xs)*len(ys) 49 | 50 | # Copy default values along the first axis and replace nans with 51 | # the mesh grid points. 52 | actions = np.tile(self._default_action, (N, 1)) 53 | actions[:, self._var_inds[0]] = xgrid.ravel() 54 | actions[:, self._var_inds[1]] = ygrid.ravel() 55 | 56 | for ax, obs in zip(self._ax_lst, self._obs_lst): 57 | qs = self._qf.eval(obs[None], actions) 58 | 59 | qs = qs.reshape(xgrid.shape) 60 | 61 | cs = ax.contour(xgrid, ygrid, qs, 20) 62 | self._line_objects += cs.collections 63 | self._line_objects += ax.clabel( 64 | cs, inline=1, fontsize=10, fmt='%.2f') 65 | 66 | def _plot_action_samples(self): 67 | for ax, obs in zip(self._ax_lst, self._obs_lst): 68 | actions = self._policy.get_actions( 69 | np.ones((self._n_samples, 1)) * obs[None, :]) 70 | x, y = actions[:, 0], actions[:, 1] 71 | self._line_objects += ax.plot(x, y, 'b*') 72 | -------------------------------------------------------------------------------- /softqlearning/misc/sampler.py: -------------------------------------------------------------------------------- 1 | import numpy as np 2 | import os 3 | 4 | from rllab.misc import logger 5 | from experiment.hyper_parameters import SHARED_PARAMS 6 | 7 | save_path = SHARED_PARAMS['model_save_path'] 8 | if not os.path.exists(save_path): 9 | os.mkdir(save_path) 10 | 11 | 12 | def rollout(env, policy, path_length): 13 | env_spec = env.spec 14 | Da = env_spec.action_space.flat_dim 15 | Do = env_spec.observation_space.flat_dim 16 | 17 | observation = env._get_observation() 18 | policy.reset() 19 | 20 | observations = np.zeros((path_length + 1, Do)) 21 | actions = np.zeros((path_length, Da)) 22 | terminals = np.zeros((path_length, )) 23 | rewards = np.zeros((path_length, )) 24 | agent_infos = [] 25 | env_infos = [] 26 | 27 | t = 0 28 | for t in range(path_length): 29 | 30 | action, agent_info = policy.get_action(observation) 31 | next_obs, reward, terminal, env_info = env.step(action) 32 | 33 | agent_infos.append(agent_info) 34 | env_infos.append(env_info) 35 | 36 | actions[t] = action 37 | terminals[t] = terminal 38 | rewards[t] = reward 39 | observations[t] = observation 40 | 41 | observation = next_obs 42 | 43 | if terminal: 44 | break 45 | 46 | observations[t + 1] = observation 47 | 48 | path = { 49 | 'observations': observations[:t + 1], 50 | 'actions': actions[:t + 1], 51 | 'rewards': rewards[:t + 1], 52 | 'terminals': terminals[:t + 1], 53 | 'next_observations': observations[1:t + 2], 54 | 'agent_infos': agent_infos, 55 | 'env_infos': env_infos 56 | } 57 | 58 | return path 59 | 60 | 61 | def rollouts(env, policy, path_length, n_paths): 62 | paths = list() 63 | for i in range(n_paths): 64 | paths.append(rollout(env, policy, path_length)) 65 | 66 | return paths 67 | 68 | 69 | class Sampler(object): 70 | def __init__(self, max_path_length, min_pool_size, batch_size): 71 | self._max_path_length = max_path_length 72 | self._min_pool_size = min_pool_size 73 | self._batch_size = batch_size 74 | 75 | self.env = None 76 | self.policy = None 77 | self.pool = None 78 | 79 | def initialize(self, env, policy, pool): 80 | self.env = env 81 | self.policy = policy 82 | self.pool = pool 83 | 84 | def sample(self): 85 | raise NotImplementedError 86 | 87 | def batch_ready(self): 88 | enough_samples = self.pool.size >= self._min_pool_size 89 | return enough_samples 90 | 91 | def random_batch(self): 92 | return self.pool.random_batch(self._batch_size) 93 | 94 | def terminate(self): 95 | self.env.terminate() 96 | 97 | def log_diagnostics(self): 98 | logger.record_tabular('pool-size', self.pool.size) 99 | 100 | 101 | class SimpleSampler(Sampler): 102 | def __init__(self, **kwargs): 103 | super(SimpleSampler, self).__init__(**kwargs) 104 | 105 | self._path_length = 0 106 | self._path_return = 0 107 | self._last_path_return = 0 108 | self._max_path_return = -np.inf 109 | self._n_episodes = 0 110 | self._current_observation = None 111 | self._total_samples = 0 112 | 113 | def sample(self): 114 | if self._current_observation is None: 115 | self._current_observation = self.env.reset() 116 | 117 | action, _ = self.policy.get_action(self._current_observation) 118 | next_observation, reward, terminal, info = self.env.step(action) 119 | self._path_length += 1 120 | self._path_return += reward 121 | self._total_samples += 1 122 | 123 | self.pool.add_sample( 124 | observation=self._current_observation, 125 | action=action, 126 | reward=reward, 127 | terminal=terminal, 128 | next_observation=next_observation) 129 | 130 | if terminal or self._path_length >= self._max_path_length: 131 | self.policy.reset() 132 | self._current_observation = self.env.reset() 133 | self._path_length = 0 134 | self._max_path_return = max(self._max_path_return, 135 | self._path_return) 136 | self._last_path_return = self._path_return 137 | 138 | self._path_return = 0 139 | self._n_episodes += 1 140 | 141 | with open(save_path + '/rewards.txt', 'a+') as f: 142 | f.write(str(self._n_episodes) + ' ' + str(self._last_path_return) + '\n') 143 | 144 | else: 145 | self._current_observation = next_observation 146 | 147 | def log_diagnostics(self): 148 | print('last path return =', self._last_path_return) 149 | 150 | 151 | class DummySampler(Sampler): 152 | def __init__(self, batch_size, max_path_length): 153 | super(DummySampler, self).__init__( 154 | max_path_length=max_path_length, 155 | min_pool_size=0, 156 | batch_size=batch_size) 157 | 158 | def sample(self): 159 | pass 160 | -------------------------------------------------------------------------------- /softqlearning/misc/tf_utils.py: -------------------------------------------------------------------------------- 1 | import tensorflow as tf 2 | from rllab import config 3 | 4 | 5 | def get_default_session(): 6 | return tf.get_default_session() or create_session() 7 | 8 | 9 | def create_session(**kwargs): 10 | """ Create new tensorflow session with given configuration. """ 11 | if "config" not in kwargs: 12 | kwargs["config"] = get_configuration() 13 | return tf.InteractiveSession(**kwargs) 14 | 15 | 16 | def get_configuration(): 17 | """ Returns personal tensorflow configuration. """ 18 | if config.USE_GPU: 19 | raise NotImplementedError 20 | 21 | config_args = {} 22 | return tf.ConfigProto(**config_args) 23 | -------------------------------------------------------------------------------- /softqlearning/policies/nn_policy.py: -------------------------------------------------------------------------------- 1 | import tensorflow as tf 2 | 3 | from rllab.core.serializable import Serializable 4 | from rllab.misc.overrides import overrides 5 | from sandbox.rocky.tf.policies.base import Policy 6 | 7 | 8 | class NNPolicy(Policy, Serializable): 9 | def __init__(self, env_spec, obs_pl, action, scope_name=None): 10 | Serializable.quick_init(self, locals()) 11 | 12 | self._obs_pl = obs_pl 13 | self._action = action 14 | self._scope_name = (tf.get_variable_scope().name 15 | if not scope_name else scope_name) 16 | super(NNPolicy, self).__init__(env_spec) 17 | 18 | @overrides 19 | def get_action(self, observation): 20 | return self.get_actions(observation[None])[0], None 21 | 22 | @overrides 23 | def get_actions(self, observations): 24 | feeds = {self._obs_pl: observations} 25 | actions = tf.get_default_session().run(self._action, feeds) 26 | return actions 27 | 28 | @overrides 29 | def log_diagnostics(self, paths): 30 | pass 31 | 32 | @overrides 33 | def get_params_internal(self, **tags): 34 | # TODO: rewrite this using tensorflow collections 35 | if tags: 36 | raise NotImplementedError 37 | scope = self._scope_name 38 | # Add "/" to 'scope' unless it's empty (otherwise get_collection will 39 | # return all parameters that start with 'scope'. 40 | scope = scope if scope == '' else scope + '/' 41 | return tf.get_collection(tf.GraphKeys.TRAINABLE_VARIABLES, scope) 42 | -------------------------------------------------------------------------------- /softqlearning/policies/stochastic_policy.py: -------------------------------------------------------------------------------- 1 | import tensorflow as tf 2 | 3 | from rllab.core.serializable import Serializable 4 | 5 | from softqlearning.misc.nn import feedforward_net 6 | 7 | from softqlearning.policies.nn_policy import NNPolicy 8 | 9 | 10 | class StochasticNNPolicy(NNPolicy, Serializable): 11 | """Stochastic neural network policy.""" 12 | 13 | def __init__(self, 14 | env_spec, 15 | hidden_layer_sizes, 16 | squash=True, 17 | name='policy'): 18 | Serializable.quick_init(self, locals()) 19 | 20 | self._action_dim = env_spec.action_space.flat_dim 21 | self._observation_dim = env_spec.observation_space.flat_dim 22 | self._layer_sizes = list(hidden_layer_sizes) + [self._action_dim] 23 | self._squash = squash 24 | self._name = name 25 | 26 | self._observation_ph = tf.placeholder( 27 | tf.float32, 28 | shape=[None, self._observation_dim], 29 | name='observation') 30 | 31 | self._actions = self.actions_for(self._observation_ph) 32 | 33 | super(StochasticNNPolicy, self).__init__( 34 | env_spec, self._observation_ph, self._actions, self._name) 35 | 36 | def actions_for(self, observations, n_action_samples=1, reuse=False): 37 | 38 | n_state_samples = tf.shape(observations)[0] 39 | 40 | if n_action_samples > 1: 41 | observations = observations[:, None, :] 42 | latent_shape = (n_state_samples, n_action_samples, 43 | self._action_dim) 44 | else: 45 | latent_shape = (n_state_samples, self._action_dim) 46 | 47 | latents = tf.random_normal(latent_shape) 48 | 49 | with tf.variable_scope(self._name, reuse=reuse): 50 | raw_actions = feedforward_net( 51 | (observations, latents), 52 | layer_sizes=self._layer_sizes, 53 | activation_fn=tf.nn.relu, 54 | output_nonlinearity=None) 55 | 56 | return tf.tanh(raw_actions) if self._squash else raw_actions 57 | -------------------------------------------------------------------------------- /softqlearning/replay_buffers/replay_buffer.py: -------------------------------------------------------------------------------- 1 | import abc 2 | 3 | 4 | class ReplayBuffer(object): 5 | """ 6 | A class used to save and replay data. 7 | """ 8 | 9 | @abc.abstractmethod 10 | def add_sample(self, observation, action, reward, next_observation, 11 | terminal, **kwargs): 12 | """ 13 | Add a transition tuple. 14 | """ 15 | pass 16 | 17 | @abc.abstractmethod 18 | def terminate_episode(self): 19 | """ 20 | Let the replay buffer know that the episode has terminated in case some 21 | special book-keeping has to happen. 22 | :return: 23 | """ 24 | pass 25 | 26 | @property 27 | @abc.abstractmethod 28 | def size(self, **kwargs): 29 | """ 30 | :return: # of unique items that can be sampled. 31 | """ 32 | pass 33 | 34 | def add_path(self, path): 35 | """ 36 | Add a path to the replay buffer. 37 | 38 | This default implementation naively goes through every step, but you 39 | may want to optimize this. 40 | 41 | NOTE: You should NOT call "terminate_episode" after calling add_path. 42 | It's assumed that this function handles the episode termination. 43 | 44 | :param path: Dict like one outputted by railrl.samplers.util.rollout 45 | """ 46 | for i, ( 47 | obs, 48 | action, 49 | reward, 50 | next_obs, 51 | terminal, 52 | agent_info, 53 | env_info 54 | ) in enumerate(zip( 55 | path["observations"], 56 | path["actions"], 57 | path["rewards"], 58 | path["next_observations"], 59 | path["terminals"], 60 | path.get("agent_infos", {}), 61 | path.get("env_infos", {}), 62 | )): 63 | self.add_sample( 64 | observation=obs, 65 | action=action, 66 | reward=reward, 67 | next_observation=next_obs, 68 | terminal=terminal, 69 | agent_info=agent_info, 70 | env_info=env_info, 71 | ) 72 | self.terminate_episode() 73 | 74 | @abc.abstractmethod 75 | def random_batch(self, batch_size): 76 | """ 77 | Return a batch of size `batch_size`. 78 | :param batch_size: 79 | :return: 80 | """ 81 | pass 82 | -------------------------------------------------------------------------------- /softqlearning/replay_buffers/simple_replay_buffer.py: -------------------------------------------------------------------------------- 1 | import numpy as np 2 | 3 | from rllab.core.serializable import Serializable 4 | 5 | from softqlearning.replay_buffers.replay_buffer import ReplayBuffer 6 | 7 | 8 | class SimpleReplayBuffer(ReplayBuffer, Serializable): 9 | def __init__(self, env_spec, max_replay_buffer_size): 10 | super(SimpleReplayBuffer, self).__init__() 11 | Serializable.quick_init(self, locals()) 12 | 13 | max_replay_buffer_size = int(max_replay_buffer_size) 14 | 15 | self._env_spec = env_spec 16 | self._observation_dim = env_spec.observation_space.flat_dim 17 | self._action_dim = env_spec.action_space.flat_dim 18 | self._max_buffer_size = max_replay_buffer_size 19 | self._observations = np.zeros((max_replay_buffer_size, 20 | self._observation_dim)) 21 | # It's a bit memory inefficient to save the observations twice, 22 | # but it makes the code *much* easier since you no longer have to 23 | # worry about termination conditions. 24 | self._next_obs = np.zeros((max_replay_buffer_size, 25 | self._observation_dim)) 26 | self._actions = np.zeros((max_replay_buffer_size, self._action_dim)) 27 | self._rewards = np.zeros(max_replay_buffer_size) 28 | # self._terminals[i] = a terminal was received at time i 29 | self._terminals = np.zeros(max_replay_buffer_size, dtype='uint8') 30 | self._top = 0 31 | self._size = 0 32 | 33 | def add_sample(self, observation, action, reward, terminal, 34 | next_observation, **kwargs): 35 | self._observations[self._top] = observation 36 | self._actions[self._top] = action 37 | self._rewards[self._top] = reward 38 | self._terminals[self._top] = terminal 39 | self._next_obs[self._top] = next_observation 40 | 41 | self._advance() 42 | 43 | def terminate_episode(self): 44 | pass 45 | 46 | def _advance(self): 47 | self._top = (self._top + 1) % self._max_buffer_size 48 | if self._size < self._max_buffer_size: 49 | self._size += 1 50 | 51 | def random_batch(self, batch_size): 52 | indices = np.random.randint(0, self._size, batch_size) 53 | return { 54 | 'observations': self._observations[indices], 55 | 'actions': self._actions[indices], 56 | 'rewards': self._rewards[indices], 57 | 'terminals': self._terminals[indices], 58 | 'next_observations': self._next_obs[indices] 59 | } 60 | 61 | @property 62 | def size(self): 63 | return self._size 64 | 65 | def __getstate__(self): 66 | buffer_state = super(SimpleReplayBuffer, self).__getstate__() 67 | buffer_state.update({ 68 | 'observations': self._observations.tobytes(), 69 | 'actions': self._actions.tobytes(), 70 | 'rewards': self._rewards.tobytes(), 71 | 'terminals': self._terminals.tobytes(), 72 | 'next_observations': self._next_obs.tobytes(), 73 | 'top': self._top, 74 | 'size': self._size, 75 | }) 76 | return buffer_state 77 | 78 | def __setstate__(self, buffer_state): 79 | super(SimpleReplayBuffer, self).__setstate__(buffer_state) 80 | 81 | flat_obs = np.fromstring(buffer_state['observations']) 82 | flat_next_obs = np.fromstring(buffer_state['next_observations']) 83 | flat_actions = np.fromstring(buffer_state['actions']) 84 | flat_reward = np.fromstring(buffer_state['rewards']) 85 | flat_terminals = np.fromstring( 86 | buffer_state['terminals'], dtype=np.uint8) 87 | 88 | self._observations = flat_obs.reshape(self._max_buffer_size, -1) 89 | self._next_obs = flat_next_obs.reshape(self._max_buffer_size, -1) 90 | self._actions = flat_actions.reshape(self._max_buffer_size, -1) 91 | self._rewards = flat_reward.reshape(self._max_buffer_size) 92 | self._terminals = flat_terminals.reshape(self._max_buffer_size) 93 | self._top = buffer_state['top'] 94 | self._size = buffer_state['size'] 95 | -------------------------------------------------------------------------------- /softqlearning/value_functions/value_function.py: -------------------------------------------------------------------------------- 1 | import tensorflow as tf 2 | import numpy as np 3 | 4 | from rllab.core.serializable import Serializable 5 | 6 | from softqlearning.misc.nn import MLPFunction 7 | from softqlearning.misc import tf_utils 8 | 9 | 10 | class NNVFunction(MLPFunction): 11 | def __init__(self, 12 | env_spec, 13 | hidden_layer_sizes=(100, 100), 14 | name='value_function'): 15 | Serializable.quick_init(self, locals()) 16 | 17 | self._Do = env_spec.observation_space.flat_dim 18 | self._observations_ph = tf.placeholder( 19 | tf.float32, shape=[None, self._Do], name='observations') 20 | 21 | super(NNVFunction, self).__init__( 22 | inputs=(self._observations_ph, ), 23 | name=name, 24 | hidden_layer_sizes=hidden_layer_sizes) 25 | 26 | def eval(self, observations): 27 | return super(NNVFunction, self)._eval((observations, )) 28 | 29 | def output_for(self, observations, reuse=False): 30 | return super(NNVFunction, self)._output_for( 31 | (observations, ), reuse=reuse) 32 | 33 | 34 | class NNQFunction(MLPFunction): 35 | def __init__(self, 36 | env_spec, 37 | hidden_layer_sizes=(100, 100), 38 | name='q_function'): 39 | Serializable.quick_init(self, locals()) 40 | 41 | self._Da = env_spec.action_space.flat_dim 42 | self._Do = env_spec.observation_space.flat_dim 43 | 44 | self._observations_ph = tf.placeholder( 45 | tf.float32, shape=[None, self._Do], name='observations') 46 | self._actions_ph = tf.placeholder( 47 | tf.float32, shape=[None, self._Da], name='actions') 48 | 49 | super(NNQFunction, self).__init__( 50 | inputs=(self._observations_ph, self._actions_ph), 51 | name=name, 52 | hidden_layer_sizes=hidden_layer_sizes) 53 | 54 | def output_for(self, observations, actions, reuse=False): 55 | return super(NNQFunction, self)._output_for( 56 | (observations, actions), reuse=reuse) 57 | 58 | def eval(self, observations, actions): 59 | return super(NNQFunction, self)._eval((observations, actions)) 60 | 61 | 62 | class SumQFunction(Serializable): 63 | def __init__(self, env_spec, q_functions): 64 | Serializable.quick_init(self, locals()) 65 | 66 | self.q_functions = q_functions 67 | 68 | self._Da = env_spec.action_space.flat_dim 69 | self._Do = env_spec.observation_space.flat_dim 70 | 71 | self._observations_ph = tf.placeholder( 72 | tf.float32, shape=[None, self._Do], name='observations') 73 | self._actions_ph = tf.placeholder( 74 | tf.float32, shape=[None, self._Da], name='actions') 75 | 76 | self._output = self.output_for( 77 | self._observations_ph, self._actions_ph, reuse=True) 78 | 79 | def output_for(self, observations, actions, reuse=False): 80 | outputs = [ 81 | qf.output_for(observations, actions, reuse=reuse) 82 | for qf in self.q_functions 83 | ] 84 | output = tf.add_n(outputs) 85 | return output 86 | 87 | def _eval(self, observations, actions): 88 | feeds = { 89 | self._observations_ph: observations, 90 | self._actions_ph: actions 91 | } 92 | 93 | return tf_utils.get_default_session().run(self._output, feeds) 94 | 95 | def get_param_values(self): 96 | all_values_list = [qf.get_param_values() for qf in self.q_functions] 97 | 98 | return np.concatenate(all_values_list) 99 | 100 | def set_param_values(self, all_values): 101 | param_sizes = [qf.get_param_values().size for qf in self.q_functions] 102 | split_points = np.cumsum(param_sizes)[:-1] 103 | 104 | all_values_list = np.split(all_values, split_points) 105 | 106 | for values, qf in zip(all_values_list, self.q_functions): 107 | qf.set_param_values(values) 108 | -------------------------------------------------------------------------------- /version.py: -------------------------------------------------------------------------------- 1 | VERSION = '3.4.0' 2 | ARCH = 'x64' 3 | -------------------------------------------------------------------------------- /vrep.py: -------------------------------------------------------------------------------- 1 | # This file is part of the REMOTE API 2 | # 3 | # Copyright 2006-2017 Coppelia Robotics GmbH. All rights reserved. 4 | # marc@coppeliarobotics.com 5 | # www.coppeliarobotics.com 6 | # 7 | # The REMOTE API is licensed under the terms of GNU GPL: 8 | # 9 | # ------------------------------------------------------------------- 10 | # The REMOTE API is free software: you can redistribute it and/or modify 11 | # it under the terms of the GNU General Public License as published by 12 | # the Free Software Foundation, either version 3 of the License, or 13 | # (at your option) any later version. 14 | # 15 | # THE REMOTE API IS DISTRIBUTED "AS IS", WITHOUT ANY EXPRESS OR IMPLIED 16 | # WARRANTY. THE USER WILL USE IT AT HIS/HER OWN RISK. THE ORIGINAL 17 | # AUTHORS AND COPPELIA ROBOTICS GMBH WILL NOT BE LIABLE FOR DATA LOSS, 18 | # DAMAGES, LOSS OF PROFITS OR ANY OTHER KIND OF LOSS WHILE USING OR 19 | # MISUSING THIS SOFTWARE. 20 | # 21 | # See the GNU General Public License for more details. 22 | # 23 | # You should have received a copy of the GNU General Public License 24 | # along with the REMOTE API. If not, see . 25 | # ------------------------------------------------------------------- 26 | # 27 | # This file was automatically created for V-REP release V3.4.0 rev. 1 on April 5th 2017 28 | 29 | import platform 30 | import struct 31 | import sys 32 | import os 33 | import ctypes as ct 34 | from vrepConst import * 35 | 36 | from version import VERSION, ARCH 37 | 38 | #load library 39 | libsimx = None 40 | try: 41 | file_extension = '.so' 42 | if platform.system() =='cli': 43 | file_extension = '.dll' 44 | elif platform.system() =='Windows': 45 | file_extension = '.dll' 46 | elif platform.system() == 'Darwin': 47 | file_extension = '.dylib' 48 | else: 49 | file_extension = '.so' 50 | libfullpath = os.path.join(os.path.dirname(__file__), 'remoteApi-{}-{}{}'.format(VERSION, ARCH, file_extension)) 51 | libsimx = ct.CDLL(libfullpath) 52 | except: 53 | print ('----------------------------------------------------') 54 | print ('The remoteApi library could not be loaded. Make sure') 55 | print ('it is located in the same folder as "vrep.py", or') 56 | print ('appropriately adjust the file "vrep.py"') 57 | print ('----------------------------------------------------') 58 | print ('') 59 | 60 | #ctypes wrapper prototypes 61 | c_GetJointPosition = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxGetJointPosition", libsimx)) 62 | c_SetJointPosition = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_float, ct.c_int32)(("simxSetJointPosition", libsimx)) 63 | c_GetJointMatrix = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxGetJointMatrix", libsimx)) 64 | c_SetSphericalJointMatrix = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxSetSphericalJointMatrix", libsimx)) 65 | c_SetJointTargetVelocity = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_float, ct.c_int32)(("simxSetJointTargetVelocity", libsimx)) 66 | c_SetJointTargetPosition = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_float, ct.c_int32)(("simxSetJointTargetPosition", libsimx)) 67 | c_GetJointForce = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxGetJointForce", libsimx)) 68 | c_SetJointForce = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_float, ct.c_int32)(("simxSetJointForce", libsimx)) 69 | c_ReadForceSensor = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_ubyte), ct.POINTER(ct.c_float), ct.POINTER(ct.c_float), ct.c_int32)(("simxReadForceSensor", libsimx)) 70 | c_BreakForceSensor = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32)(("simxBreakForceSensor", libsimx)) 71 | c_ReadVisionSensor = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_ubyte), ct.POINTER(ct.POINTER(ct.c_float)), ct.POINTER(ct.POINTER(ct.c_int32)), ct.c_int32)(("simxReadVisionSensor", libsimx)) 72 | c_GetObjectHandle = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetObjectHandle", libsimx)) 73 | c_GetVisionSensorImage = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_byte)), ct.c_ubyte, ct.c_int32)(("simxGetVisionSensorImage", libsimx)) 74 | c_SetVisionSensorImage = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_byte), ct.c_int32, ct.c_ubyte, ct.c_int32)(("simxSetVisionSensorImage", libsimx)) 75 | c_GetVisionSensorDepthBuffer= ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_float)), ct.c_int32)(("simxGetVisionSensorDepthBuffer", libsimx)) 76 | c_GetObjectChild = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetObjectChild", libsimx)) 77 | c_GetObjectParent = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetObjectParent", libsimx)) 78 | c_ReadProximitySensor = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_ubyte), ct.POINTER(ct.c_float), ct.POINTER(ct.c_int32), ct.POINTER(ct.c_float), ct.c_int32)(("simxReadProximitySensor", libsimx)) 79 | c_LoadModel = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_ubyte, ct.POINTER(ct.c_int32), ct.c_int32)(("simxLoadModel", libsimx)) 80 | c_LoadUI = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_ubyte, ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_int32)), ct.c_int32)(("simxLoadUI", libsimx)) 81 | c_LoadScene = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_ubyte, ct.c_int32)(("simxLoadScene", libsimx)) 82 | c_StartSimulation = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32)(("simxStartSimulation", libsimx)) 83 | c_PauseSimulation = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32)(("simxPauseSimulation", libsimx)) 84 | c_StopSimulation = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32)(("simxStopSimulation", libsimx)) 85 | c_GetUIHandle = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetUIHandle", libsimx)) 86 | c_GetUISlider = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetUISlider", libsimx)) 87 | c_SetUISlider = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.c_int32, ct.c_int32)(("simxSetUISlider", libsimx)) 88 | c_GetUIEventButton = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetUIEventButton", libsimx)) 89 | c_GetUIButtonProperty = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetUIButtonProperty", libsimx)) 90 | c_SetUIButtonProperty = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.c_int32, ct.c_int32)(("simxSetUIButtonProperty", libsimx)) 91 | c_AddStatusbarMessage = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_int32)(("simxAddStatusbarMessage", libsimx)) 92 | c_AuxiliaryConsoleOpen = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.POINTER(ct.c_int32), ct.POINTER(ct.c_float), ct.POINTER(ct.c_float), ct.POINTER(ct.c_int32), ct.c_int32)(("simxAuxiliaryConsoleOpen", libsimx)) 93 | c_AuxiliaryConsoleClose = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32)(("simxAuxiliaryConsoleClose", libsimx)) 94 | c_AuxiliaryConsolePrint = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_char), ct.c_int32)(("simxAuxiliaryConsolePrint", libsimx)) 95 | c_AuxiliaryConsoleShow = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_ubyte, ct.c_int32)(("simxAuxiliaryConsoleShow", libsimx)) 96 | c_GetObjectOrientation = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxGetObjectOrientation", libsimx)) 97 | c_GetObjectPosition = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxGetObjectPosition", libsimx)) 98 | c_SetObjectOrientation = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxSetObjectOrientation", libsimx)) 99 | c_SetObjectPosition = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxSetObjectPosition", libsimx)) 100 | c_SetObjectParent = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.c_ubyte, ct.c_int32)(("simxSetObjectParent", libsimx)) 101 | c_SetUIButtonLabel = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_char), ct.c_int32)(("simxSetUIButtonLabel", libsimx)) 102 | c_GetLastErrors = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_char)), ct.c_int32)(("simxGetLastErrors", libsimx)) 103 | c_GetArrayParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxGetArrayParameter", libsimx)) 104 | c_SetArrayParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxSetArrayParameter", libsimx)) 105 | c_GetBooleanParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_ubyte), ct.c_int32)(("simxGetBooleanParameter", libsimx)) 106 | c_SetBooleanParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_ubyte, ct.c_int32)(("simxSetBooleanParameter", libsimx)) 107 | c_GetIntegerParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetIntegerParameter", libsimx)) 108 | c_SetIntegerParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.c_int32)(("simxSetIntegerParameter", libsimx)) 109 | c_GetFloatingParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxGetFloatingParameter", libsimx)) 110 | c_SetFloatingParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_float, ct.c_int32)(("simxSetFloatingParameter", libsimx)) 111 | c_GetStringParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.POINTER(ct.c_char)), ct.c_int32)(("simxGetStringParameter", libsimx)) 112 | c_GetCollisionHandle = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetCollisionHandle", libsimx)) 113 | c_GetDistanceHandle = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetDistanceHandle", libsimx)) 114 | c_GetCollectionHandle = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetCollectionHandle", libsimx)) 115 | c_ReadCollision = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_ubyte), ct.c_int32)(("simxReadCollision", libsimx)) 116 | c_ReadDistance = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxReadDistance", libsimx)) 117 | c_RemoveObject = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32)(("simxRemoveObject", libsimx)) 118 | c_RemoveModel = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32)(("simxRemoveModel", libsimx)) 119 | c_RemoveUI = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32)(("simxRemoveUI", libsimx)) 120 | c_CloseScene = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32)(("simxCloseScene", libsimx)) 121 | c_GetObjects = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_int32)), ct.c_int32)(("simxGetObjects", libsimx)) 122 | c_DisplayDialog = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_char), ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_float), ct.POINTER(ct.c_float), ct.POINTER(ct.c_int32), ct.POINTER(ct.c_int32), ct.c_int32)(("simxDisplayDialog", libsimx)) 123 | c_EndDialog = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32)(("simxEndDialog", libsimx)) 124 | c_GetDialogInput = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.POINTER(ct.c_char)), ct.c_int32)(("simxGetDialogInput", libsimx)) 125 | c_GetDialogResult = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetDialogResult", libsimx)) 126 | c_CopyPasteObjects = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32, ct.POINTER(ct.POINTER(ct.c_int32)), ct.POINTER(ct.c_int32), ct.c_int32)(("simxCopyPasteObjects", libsimx)) 127 | c_GetObjectSelection = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.POINTER(ct.c_int32)), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetObjectSelection", libsimx)) 128 | c_SetObjectSelection = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32, ct.c_int32)(("simxSetObjectSelection", libsimx)) 129 | c_ClearFloatSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_int32)(("simxClearFloatSignal", libsimx)) 130 | c_ClearIntegerSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_int32)(("simxClearIntegerSignal", libsimx)) 131 | c_ClearStringSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_int32)(("simxClearStringSignal", libsimx)) 132 | c_GetFloatSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_float), ct.c_int32)(("simxGetFloatSignal", libsimx)) 133 | c_GetIntegerSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetIntegerSignal", libsimx)) 134 | c_GetStringSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.POINTER(ct.c_ubyte)), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetStringSignal", libsimx)) 135 | c_SetFloatSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_float, ct.c_int32)(("simxSetFloatSignal", libsimx)) 136 | c_SetIntegerSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_int32, ct.c_int32)(("simxSetIntegerSignal", libsimx)) 137 | c_SetStringSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_ubyte), ct.c_int32, ct.c_int32)(("simxSetStringSignal", libsimx)) 138 | c_AppendStringSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_ubyte), ct.c_int32, ct.c_int32)(("simxAppendStringSignal", libsimx)) 139 | c_WriteStringStream = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_ubyte), ct.c_int32, ct.c_int32)(("simxWriteStringStream", libsimx)) 140 | c_GetObjectFloatParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.c_int32)(("simxGetObjectFloatParameter", libsimx)) 141 | c_SetObjectFloatParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.c_float, ct.c_int32)(("simxSetObjectFloatParameter", libsimx)) 142 | c_GetObjectIntParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetObjectIntParameter", libsimx)) 143 | c_SetObjectIntParameter = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.c_int32, ct.c_int32)(("simxSetObjectIntParameter", libsimx)) 144 | c_GetModelProperty = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetModelProperty", libsimx)) 145 | c_SetModelProperty = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.c_int32)(("simxSetModelProperty", libsimx)) 146 | c_Start = ct.CFUNCTYPE(ct.c_int32,ct.POINTER(ct.c_char), ct.c_int32, ct.c_ubyte, ct.c_ubyte, ct.c_int32, ct.c_int32)(("simxStart", libsimx)) 147 | c_Finish = ct.CFUNCTYPE(None, ct.c_int32)(("simxFinish", libsimx)) 148 | c_GetPingTime = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_int32))(("simxGetPingTime", libsimx)) 149 | c_GetLastCmdTime = ct.CFUNCTYPE(ct.c_int32,ct.c_int32)(("simxGetLastCmdTime", libsimx)) 150 | c_SynchronousTrigger = ct.CFUNCTYPE(ct.c_int32,ct.c_int32)(("simxSynchronousTrigger", libsimx)) 151 | c_Synchronous = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_ubyte)(("simxSynchronous", libsimx)) 152 | c_PauseCommunication = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_ubyte)(("simxPauseCommunication", libsimx)) 153 | c_GetInMessageInfo = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32))(("simxGetInMessageInfo", libsimx)) 154 | c_GetOutMessageInfo = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32))(("simxGetOutMessageInfo", libsimx)) 155 | c_GetConnectionId = ct.CFUNCTYPE(ct.c_int32,ct.c_int32)(("simxGetConnectionId", libsimx)) 156 | c_CreateBuffer = ct.CFUNCTYPE(ct.POINTER(ct.c_ubyte), ct.c_int32)(("simxCreateBuffer", libsimx)) 157 | c_ReleaseBuffer = ct.CFUNCTYPE(None, ct.c_void_p)(("simxReleaseBuffer", libsimx)) 158 | c_TransferFile = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_char), ct.c_int32, ct.c_int32)(("simxTransferFile", libsimx)) 159 | c_EraseFile = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.c_int32)(("simxEraseFile", libsimx)) 160 | c_GetAndClearStringSignal = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.POINTER(ct.c_ubyte)), ct.POINTER(ct.c_int32), ct.c_int32)(("simxGetAndClearStringSignal", libsimx)) 161 | c_ReadStringStream = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.POINTER(ct.c_ubyte)), ct.POINTER(ct.c_int32), ct.c_int32)(("simxReadStringStream", libsimx)) 162 | c_CreateDummy = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_float, ct.POINTER(ct.c_ubyte), ct.POINTER(ct.c_int32), ct.c_int32)(("simxCreateDummy", libsimx)) 163 | c_Query = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.c_ubyte), ct.c_int32, ct.POINTER(ct.c_char), ct.POINTER(ct.POINTER(ct.c_ubyte)), ct.POINTER(ct.c_int32), ct.c_int32)(("simxQuery", libsimx)) 164 | c_GetObjectGroupData = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.c_int32, ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_int32)), ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_int32)), ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_float)), ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_char)), ct.c_int32)(("simxGetObjectGroupData", libsimx)) 165 | c_GetObjectVelocity = ct.CFUNCTYPE(ct.c_int32,ct.c_int32, ct.c_int32, ct.POINTER(ct.c_float), ct.POINTER(ct.c_float), ct.c_int32)(("simxGetObjectVelocity", libsimx)) 166 | c_CallScriptFunction = ct.CFUNCTYPE(ct.c_int32,ct.c_int32,ct.POINTER(ct.c_char),ct.c_int32,ct.POINTER(ct.c_char),ct.c_int32,ct.POINTER(ct.c_int32),ct.c_int32,ct.POINTER(ct.c_float),ct.c_int32,ct.POINTER(ct.c_char),ct.c_int32,ct.POINTER(ct.c_ubyte),ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_int32)),ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_float)),ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_char)),ct.POINTER(ct.c_int32), ct.POINTER(ct.POINTER(ct.c_ubyte)),ct.c_int32)(("simxCallScriptFunction", libsimx)) 167 | 168 | #API functions 169 | def simxGetJointPosition(clientID, jointHandle, operationMode): 170 | ''' 171 | Please have a look at the function description/documentation in the V-REP user manual 172 | ''' 173 | position = ct.c_float() 174 | return c_GetJointPosition(clientID, jointHandle, ct.byref(position), operationMode), position.value 175 | 176 | def simxSetJointPosition(clientID, jointHandle, position, operationMode): 177 | ''' 178 | Please have a look at the function description/documentation in the V-REP user manual 179 | ''' 180 | 181 | return c_SetJointPosition(clientID, jointHandle, position, operationMode) 182 | 183 | def simxGetJointMatrix(clientID, jointHandle, operationMode): 184 | ''' 185 | Please have a look at the function description/documentation in the V-REP user manual 186 | ''' 187 | matrix = (ct.c_float*12)() 188 | ret = c_GetJointMatrix(clientID, jointHandle, matrix, operationMode) 189 | arr = [] 190 | for i in range(12): 191 | arr.append(matrix[i]) 192 | return ret, arr 193 | 194 | def simxSetSphericalJointMatrix(clientID, jointHandle, matrix, operationMode): 195 | ''' 196 | Please have a look at the function description/documentation in the V-REP user manual 197 | ''' 198 | matrix = (ct.c_float*12)(*matrix) 199 | return c_SetSphericalJointMatrix(clientID, jointHandle, matrix, operationMode) 200 | 201 | def simxSetJointTargetVelocity(clientID, jointHandle, targetVelocity, operationMode): 202 | ''' 203 | Please have a look at the function description/documentation in the V-REP user manual 204 | ''' 205 | 206 | return c_SetJointTargetVelocity(clientID, jointHandle, targetVelocity, operationMode) 207 | 208 | def simxSetJointTargetPosition(clientID, jointHandle, targetPosition, operationMode): 209 | ''' 210 | Please have a look at the function description/documentation in the V-REP user manual 211 | ''' 212 | 213 | return c_SetJointTargetPosition(clientID, jointHandle, targetPosition, operationMode) 214 | 215 | def simxJointGetForce(clientID, jointHandle, operationMode): 216 | ''' 217 | Please have a look at the function description/documentation in the V-REP user manual 218 | ''' 219 | force = ct.c_float() 220 | return c_GetJointForce(clientID, jointHandle, ct.byref(force), operationMode), force.value 221 | 222 | def simxGetJointForce(clientID, jointHandle, operationMode): 223 | ''' 224 | Please have a look at the function description/documentation in the V-REP user manual 225 | ''' 226 | force = ct.c_float() 227 | return c_GetJointForce(clientID, jointHandle, ct.byref(force), operationMode), force.value 228 | 229 | def simxSetJointForce(clientID, jointHandle, force, operationMode): 230 | ''' 231 | Please have a look at the function description/documentation in the V-REP user manual 232 | ''' 233 | return c_SetJointForce(clientID, jointHandle, force, operationMode) 234 | 235 | def simxReadForceSensor(clientID, forceSensorHandle, operationMode): 236 | ''' 237 | Please have a look at the function description/documentation in the V-REP user manual 238 | ''' 239 | state = ct.c_ubyte() 240 | forceVector = (ct.c_float*3)() 241 | torqueVector = (ct.c_float*3)() 242 | ret = c_ReadForceSensor(clientID, forceSensorHandle, ct.byref(state), forceVector, torqueVector, operationMode) 243 | arr1 = [] 244 | for i in range(3): 245 | arr1.append(forceVector[i]) 246 | arr2 = [] 247 | for i in range(3): 248 | arr2.append(torqueVector[i]) 249 | #if sys.version_info[0] == 3: 250 | # state=state.value 251 | #else: 252 | # state=ord(state.value) 253 | return ret, state.value, arr1, arr2 254 | 255 | def simxBreakForceSensor(clientID, forceSensorHandle, operationMode): 256 | ''' 257 | Please have a look at the function description/documentation in the V-REP user manual 258 | ''' 259 | return c_BreakForceSensor(clientID, forceSensorHandle, operationMode) 260 | 261 | def simxReadVisionSensor(clientID, sensorHandle, operationMode): 262 | ''' 263 | Please have a look at the function description/documentation in the V-REP user manual 264 | ''' 265 | 266 | detectionState = ct.c_ubyte() 267 | auxValues = ct.POINTER(ct.c_float)() 268 | auxValuesCount = ct.POINTER(ct.c_int)() 269 | ret = c_ReadVisionSensor(clientID, sensorHandle, ct.byref(detectionState), ct.byref(auxValues), ct.byref(auxValuesCount), operationMode) 270 | 271 | auxValues2 = [] 272 | if ret == 0: 273 | s = 0 274 | for i in range(auxValuesCount[0]): 275 | auxValues2.append(auxValues[s:s+auxValuesCount[i+1]]) 276 | s += auxValuesCount[i+1] 277 | 278 | #free C buffers 279 | c_ReleaseBuffer(auxValues) 280 | c_ReleaseBuffer(auxValuesCount) 281 | 282 | return ret, bool(detectionState.value!=0), auxValues2 283 | 284 | def simxGetObjectHandle(clientID, objectName, operationMode): 285 | ''' 286 | Please have a look at the function description/documentation in the V-REP user manual 287 | ''' 288 | handle = ct.c_int() 289 | if (sys.version_info[0] == 3) and (type(objectName) is str): 290 | objectName=objectName.encode('utf-8') 291 | return c_GetObjectHandle(clientID, objectName, ct.byref(handle), operationMode), handle.value 292 | 293 | def simxGetVisionSensorImage(clientID, sensorHandle, options, operationMode): 294 | ''' 295 | Please have a look at the function description/documentation in the V-REP user manual 296 | ''' 297 | 298 | resolution = (ct.c_int*2)() 299 | c_image = ct.POINTER(ct.c_byte)() 300 | bytesPerPixel = 3 301 | if (options and 1) != 0: 302 | bytesPerPixel = 1 303 | ret = c_GetVisionSensorImage(clientID, sensorHandle, resolution, ct.byref(c_image), options, operationMode) 304 | 305 | reso = [] 306 | image = [] 307 | if (ret == 0): 308 | image = [None]*resolution[0]*resolution[1]*bytesPerPixel 309 | for i in range(resolution[0] * resolution[1] * bytesPerPixel): 310 | image[i] = c_image[i] 311 | for i in range(2): 312 | reso.append(resolution[i]) 313 | return ret, reso, image 314 | 315 | def simxSetVisionSensorImage(clientID, sensorHandle, image, options, operationMode): 316 | ''' 317 | Please have a look at the function description/documentation in the V-REP user manual 318 | ''' 319 | size = len(image) 320 | image_bytes = (ct.c_byte*size)(*image) 321 | return c_SetVisionSensorImage(clientID, sensorHandle, image_bytes, size, options, operationMode) 322 | 323 | def simxGetVisionSensorDepthBuffer(clientID, sensorHandle, operationMode): 324 | ''' 325 | Please have a look at the function description/documentation in the V-REP user manual 326 | ''' 327 | c_buffer = ct.POINTER(ct.c_float)() 328 | resolution = (ct.c_int*2)() 329 | ret = c_GetVisionSensorDepthBuffer(clientID, sensorHandle, resolution, ct.byref(c_buffer), operationMode) 330 | reso = [] 331 | buffer = [] 332 | if (ret == 0): 333 | buffer = [None]*resolution[0]*resolution[1] 334 | for i in range(resolution[0] * resolution[1]): 335 | buffer[i] = c_buffer[i] 336 | for i in range(2): 337 | reso.append(resolution[i]) 338 | return ret, reso, buffer 339 | 340 | def simxGetObjectChild(clientID, parentObjectHandle, childIndex, operationMode): 341 | ''' 342 | Please have a look at the function description/documentation in the V-REP user manual 343 | ''' 344 | childObjectHandle = ct.c_int() 345 | return c_GetObjectChild(clientID, parentObjectHandle, childIndex, ct.byref(childObjectHandle), operationMode), childObjectHandle.value 346 | 347 | def simxGetObjectParent(clientID, childObjectHandle, operationMode): 348 | ''' 349 | Please have a look at the function description/documentation in the V-REP user manual 350 | ''' 351 | 352 | parentObjectHandle = ct.c_int() 353 | return c_GetObjectParent(clientID, childObjectHandle, ct.byref(parentObjectHandle), operationMode), parentObjectHandle.value 354 | 355 | def simxReadProximitySensor(clientID, sensorHandle, operationMode): 356 | ''' 357 | Please have a look at the function description/documentation in the V-REP user manual 358 | ''' 359 | 360 | detectionState = ct.c_ubyte() 361 | detectedObjectHandle = ct.c_int() 362 | detectedPoint = (ct.c_float*3)() 363 | detectedSurfaceNormalVector = (ct.c_float*3)() 364 | ret = c_ReadProximitySensor(clientID, sensorHandle, ct.byref(detectionState), detectedPoint, ct.byref(detectedObjectHandle), detectedSurfaceNormalVector, operationMode) 365 | arr1 = [] 366 | for i in range(3): 367 | arr1.append(detectedPoint[i]) 368 | arr2 = [] 369 | for i in range(3): 370 | arr2.append(detectedSurfaceNormalVector[i]) 371 | return ret, bool(detectionState.value!=0), arr1, detectedObjectHandle.value, arr2 372 | 373 | def simxLoadModel(clientID, modelPathAndName, options, operationMode): 374 | ''' 375 | Please have a look at the function description/documentation in the V-REP user manual 376 | ''' 377 | baseHandle = ct.c_int() 378 | if (sys.version_info[0] == 3) and (type(modelPathAndName) is str): 379 | modelPathAndName=modelPathAndName.encode('utf-8') 380 | return c_LoadModel(clientID, modelPathAndName, options, ct.byref(baseHandle), operationMode), baseHandle.value 381 | 382 | def simxLoadUI(clientID, uiPathAndName, options, operationMode): 383 | ''' 384 | Please have a look at the function description/documentation in the V-REP user manual 385 | ''' 386 | 387 | count = ct.c_int() 388 | uiHandles = ct.POINTER(ct.c_int)() 389 | if (sys.version_info[0] == 3) and (type(uiPathAndName) is str): 390 | uiPathAndName=uiPathAndName.encode('utf-8') 391 | ret = c_LoadUI(clientID, uiPathAndName, options, ct.byref(count), ct.byref(uiHandles), operationMode) 392 | 393 | handles = [] 394 | if ret == 0: 395 | for i in range(count.value): 396 | handles.append(uiHandles[i]) 397 | #free C buffers 398 | c_ReleaseBuffer(uiHandles) 399 | 400 | return ret, handles 401 | 402 | def simxLoadScene(clientID, scenePathAndName, options, operationMode): 403 | ''' 404 | Please have a look at the function description/documentation in the V-REP user manual 405 | ''' 406 | 407 | if (sys.version_info[0] == 3) and (type(scenePathAndName) is str): 408 | scenePathAndName=scenePathAndName.encode('utf-8') 409 | return c_LoadScene(clientID, scenePathAndName, options, operationMode) 410 | 411 | def simxStartSimulation(clientID, operationMode): 412 | ''' 413 | Please have a look at the function description/documentation in the V-REP user manual 414 | ''' 415 | 416 | return c_StartSimulation(clientID, operationMode) 417 | 418 | def simxPauseSimulation(clientID, operationMode): 419 | ''' 420 | Please have a look at the function description/documentation in the V-REP user manual 421 | ''' 422 | 423 | return c_PauseSimulation(clientID, operationMode) 424 | 425 | def simxStopSimulation(clientID, operationMode): 426 | ''' 427 | Please have a look at the function description/documentation in the V-REP user manual 428 | ''' 429 | 430 | return c_StopSimulation(clientID, operationMode) 431 | 432 | def simxGetUIHandle(clientID, uiName, operationMode): 433 | ''' 434 | Please have a look at the function description/documentation in the V-REP user manual 435 | ''' 436 | 437 | handle = ct.c_int() 438 | if (sys.version_info[0] == 3) and (type(uiName) is str): 439 | uiName=uiName.encode('utf-8') 440 | return c_GetUIHandle(clientID, uiName, ct.byref(handle), operationMode), handle.value 441 | 442 | def simxGetUISlider(clientID, uiHandle, uiButtonID, operationMode): 443 | ''' 444 | Please have a look at the function description/documentation in the V-REP user manual 445 | ''' 446 | 447 | position = ct.c_int() 448 | return c_GetUISlider(clientID, uiHandle, uiButtonID, ct.byref(position), operationMode), position.value 449 | 450 | def simxSetUISlider(clientID, uiHandle, uiButtonID, position, operationMode): 451 | ''' 452 | Please have a look at the function description/documentation in the V-REP user manual 453 | ''' 454 | 455 | return c_SetUISlider(clientID, uiHandle, uiButtonID, position, operationMode) 456 | 457 | def simxGetUIEventButton(clientID, uiHandle, operationMode): 458 | ''' 459 | Please have a look at the function description/documentation in the V-REP user manual 460 | ''' 461 | 462 | uiEventButtonID = ct.c_int() 463 | auxValues = (ct.c_int*2)() 464 | ret = c_GetUIEventButton(clientID, uiHandle, ct.byref(uiEventButtonID), auxValues, operationMode) 465 | arr = [] 466 | for i in range(2): 467 | arr.append(auxValues[i]) 468 | return ret, uiEventButtonID.value, arr 469 | 470 | def simxGetUIButtonProperty(clientID, uiHandle, uiButtonID, operationMode): 471 | ''' 472 | Please have a look at the function description/documentation in the V-REP user manual 473 | ''' 474 | 475 | prop = ct.c_int() 476 | return c_GetUIButtonProperty(clientID, uiHandle, uiButtonID, ct.byref(prop), operationMode), prop.value 477 | 478 | def simxSetUIButtonProperty(clientID, uiHandle, uiButtonID, prop, operationMode): 479 | ''' 480 | Please have a look at the function description/documentation in the V-REP user manual 481 | ''' 482 | 483 | return c_SetUIButtonProperty(clientID, uiHandle, uiButtonID, prop, operationMode) 484 | 485 | def simxAddStatusbarMessage(clientID, message, operationMode): 486 | ''' 487 | Please have a look at the function description/documentation in the V-REP user manual 488 | ''' 489 | 490 | if (sys.version_info[0] == 3) and (type(message) is str): 491 | message=message.encode('utf-8') 492 | return c_AddStatusbarMessage(clientID, message, operationMode) 493 | 494 | def simxAuxiliaryConsoleOpen(clientID, title, maxLines, mode, position, size, textColor, backgroundColor, operationMode): 495 | ''' 496 | Please have a look at the function description/documentation in the V-REP user manual 497 | ''' 498 | 499 | consoleHandle = ct.c_int() 500 | if (sys.version_info[0] == 3) and (type(title) is str): 501 | title=title.encode('utf-8') 502 | if position != None: 503 | c_position = (ct.c_int*2)(*position) 504 | else: 505 | c_position = None 506 | if size != None: 507 | c_size = (ct.c_int*2)(*size) 508 | else: 509 | c_size = None 510 | if textColor != None: 511 | c_textColor = (ct.c_float*3)(*textColor) 512 | else: 513 | c_textColor = None 514 | if backgroundColor != None: 515 | c_backgroundColor = (ct.c_float*3)(*backgroundColor) 516 | else: 517 | c_backgroundColor = None 518 | return c_AuxiliaryConsoleOpen(clientID, title, maxLines, mode, c_position, c_size, c_textColor, c_backgroundColor, ct.byref(consoleHandle), operationMode), consoleHandle.value 519 | 520 | def simxAuxiliaryConsoleClose(clientID, consoleHandle, operationMode): 521 | ''' 522 | Please have a look at the function description/documentation in the V-REP user manual 523 | ''' 524 | 525 | return c_AuxiliaryConsoleClose(clientID, consoleHandle, operationMode) 526 | 527 | def simxAuxiliaryConsolePrint(clientID, consoleHandle, txt, operationMode): 528 | ''' 529 | Please have a look at the function description/documentation in the V-REP user manual 530 | ''' 531 | 532 | if (sys.version_info[0] == 3) and (type(txt) is str): 533 | txt=txt.encode('utf-8') 534 | return c_AuxiliaryConsolePrint(clientID, consoleHandle, txt, operationMode) 535 | 536 | def simxAuxiliaryConsoleShow(clientID, consoleHandle, showState, operationMode): 537 | ''' 538 | Please have a look at the function description/documentation in the V-REP user manual 539 | ''' 540 | 541 | return c_AuxiliaryConsoleShow(clientID, consoleHandle, showState, operationMode) 542 | 543 | def simxGetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, operationMode): 544 | ''' 545 | Please have a look at the function description/documentation in the V-REP user manual 546 | ''' 547 | eulerAngles = (ct.c_float*3)() 548 | ret = c_GetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, eulerAngles, operationMode) 549 | arr = [] 550 | for i in range(3): 551 | arr.append(eulerAngles[i]) 552 | return ret, arr 553 | 554 | def simxGetObjectPosition(clientID, objectHandle, relativeToObjectHandle, operationMode): 555 | ''' 556 | Please have a look at the function description/documentation in the V-REP user manual 557 | ''' 558 | position = (ct.c_float*3)() 559 | ret = c_GetObjectPosition(clientID, objectHandle, relativeToObjectHandle, position, operationMode) 560 | arr = [] 561 | for i in range(3): 562 | arr.append(position[i]) 563 | return ret, arr 564 | 565 | def simxSetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, eulerAngles, operationMode): 566 | ''' 567 | Please have a look at the function description/documentation in the V-REP user manual 568 | ''' 569 | 570 | angles = (ct.c_float*3)(*eulerAngles) 571 | return c_SetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, angles, operationMode) 572 | 573 | def simxSetObjectPosition(clientID, objectHandle, relativeToObjectHandle, position, operationMode): 574 | ''' 575 | Please have a look at the function description/documentation in the V-REP user manual 576 | ''' 577 | 578 | c_position = (ct.c_float*3)(*position) 579 | return c_SetObjectPosition(clientID, objectHandle, relativeToObjectHandle, c_position, operationMode) 580 | 581 | def simxSetObjectParent(clientID, objectHandle, parentObject, keepInPlace, operationMode): 582 | ''' 583 | Please have a look at the function description/documentation in the V-REP user manual 584 | ''' 585 | 586 | return c_SetObjectParent(clientID, objectHandle, parentObject, keepInPlace, operationMode) 587 | 588 | def simxSetUIButtonLabel(clientID, uiHandle, uiButtonID, upStateLabel, downStateLabel, operationMode): 589 | ''' 590 | Please have a look at the function description/documentation in the V-REP user manual 591 | ''' 592 | 593 | if sys.version_info[0] == 3: 594 | if type(upStateLabel) is str: 595 | upStateLabel=upStateLabel.encode('utf-8') 596 | if type(downStateLabel) is str: 597 | downStateLabel=downStateLabel.encode('utf-8') 598 | return c_SetUIButtonLabel(clientID, uiHandle, uiButtonID, upStateLabel, downStateLabel, operationMode) 599 | 600 | def simxGetLastErrors(clientID, operationMode): 601 | ''' 602 | Please have a look at the function description/documentation in the V-REP user manual 603 | ''' 604 | errors =[] 605 | errorCnt = ct.c_int() 606 | errorStrings = ct.POINTER(ct.c_char)() 607 | ret = c_GetLastErrors(clientID, ct.byref(errorCnt), ct.byref(errorStrings), operationMode) 608 | if ret == 0: 609 | s = 0 610 | for i in range(errorCnt.value): 611 | a = bytearray() 612 | while errorStrings[s] != b'\0': 613 | if sys.version_info[0] == 3: 614 | a.append(int.from_bytes(errorStrings[s],'big')) 615 | else: 616 | a.append(errorStrings[s]) 617 | s += 1 618 | s += 1 #skip null 619 | if sys.version_info[0] == 3: 620 | errors.append(str(a,'utf-8')) 621 | else: 622 | errors.append(str(a)) 623 | 624 | return ret, errors 625 | 626 | def simxGetArrayParameter(clientID, paramIdentifier, operationMode): 627 | ''' 628 | Please have a look at the function description/documentation in the V-REP user manual 629 | ''' 630 | paramValues = (ct.c_float*3)() 631 | ret = c_GetArrayParameter(clientID, paramIdentifier, paramValues, operationMode) 632 | arr = [] 633 | for i in range(3): 634 | arr.append(paramValues[i]) 635 | return ret, arr 636 | 637 | def simxSetArrayParameter(clientID, paramIdentifier, paramValues, operationMode): 638 | ''' 639 | Please have a look at the function description/documentation in the V-REP user manual 640 | ''' 641 | 642 | c_paramValues = (ct.c_float*3)(*paramValues) 643 | return c_SetArrayParameter(clientID, paramIdentifier, c_paramValues, operationMode) 644 | 645 | def simxGetBooleanParameter(clientID, paramIdentifier, operationMode): 646 | ''' 647 | Please have a look at the function description/documentation in the V-REP user manual 648 | ''' 649 | 650 | paramValue = ct.c_ubyte() 651 | return c_GetBooleanParameter(clientID, paramIdentifier, ct.byref(paramValue), operationMode), bool(paramValue.value!=0) 652 | 653 | def simxSetBooleanParameter(clientID, paramIdentifier, paramValue, operationMode): 654 | ''' 655 | Please have a look at the function description/documentation in the V-REP user manual 656 | ''' 657 | 658 | return c_SetBooleanParameter(clientID, paramIdentifier, paramValue, operationMode) 659 | 660 | def simxGetIntegerParameter(clientID, paramIdentifier, operationMode): 661 | ''' 662 | Please have a look at the function description/documentation in the V-REP user manual 663 | ''' 664 | 665 | paramValue = ct.c_int() 666 | return c_GetIntegerParameter(clientID, paramIdentifier, ct.byref(paramValue), operationMode), paramValue.value 667 | 668 | def simxSetIntegerParameter(clientID, paramIdentifier, paramValue, operationMode): 669 | ''' 670 | Please have a look at the function description/documentation in the V-REP user manual 671 | ''' 672 | 673 | return c_SetIntegerParameter(clientID, paramIdentifier, paramValue, operationMode) 674 | 675 | def simxGetFloatingParameter(clientID, paramIdentifier, operationMode): 676 | ''' 677 | Please have a look at the function description/documentation in the V-REP user manual 678 | ''' 679 | 680 | paramValue = ct.c_float() 681 | return c_GetFloatingParameter(clientID, paramIdentifier, ct.byref(paramValue), operationMode), paramValue.value 682 | 683 | def simxSetFloatingParameter(clientID, paramIdentifier, paramValue, operationMode): 684 | ''' 685 | Please have a look at the function description/documentation in the V-REP user manual 686 | ''' 687 | 688 | return c_SetFloatingParameter(clientID, paramIdentifier, paramValue, operationMode) 689 | 690 | def simxGetStringParameter(clientID, paramIdentifier, operationMode): 691 | ''' 692 | Please have a look at the function description/documentation in the V-REP user manual 693 | ''' 694 | paramValue = ct.POINTER(ct.c_char)() 695 | ret = c_GetStringParameter(clientID, paramIdentifier, ct.byref(paramValue), operationMode) 696 | 697 | a = bytearray() 698 | if ret == 0: 699 | i = 0 700 | while paramValue[i] != b'\0': 701 | if sys.version_info[0] == 3: 702 | a.append(int.from_bytes(paramValue[i],'big')) 703 | else: 704 | a.append(paramValue[i]) 705 | i=i+1 706 | if sys.version_info[0] == 3: 707 | a=str(a,'utf-8') 708 | else: 709 | a=str(a) 710 | return ret, a 711 | 712 | def simxGetCollisionHandle(clientID, collisionObjectName, operationMode): 713 | ''' 714 | Please have a look at the function description/documentation in the V-REP user manual 715 | ''' 716 | 717 | handle = ct.c_int() 718 | if (sys.version_info[0] == 3) and (type(collisionObjectName) is str): 719 | collisionObjectName=collisionObjectName.encode('utf-8') 720 | return c_GetCollisionHandle(clientID, collisionObjectName, ct.byref(handle), operationMode), handle.value 721 | 722 | def simxGetCollectionHandle(clientID, collectionName, operationMode): 723 | ''' 724 | Please have a look at the function description/documentation in the V-REP user manual 725 | ''' 726 | 727 | handle = ct.c_int() 728 | if (sys.version_info[0] == 3) and (type(collectionName) is str): 729 | collectionName=collectionName.encode('utf-8') 730 | return c_GetCollectionHandle(clientID, collectionName, ct.byref(handle), operationMode), handle.value 731 | 732 | def simxGetDistanceHandle(clientID, distanceObjectName, operationMode): 733 | ''' 734 | Please have a look at the function description/documentation in the V-REP user manual 735 | ''' 736 | 737 | handle = ct.c_int() 738 | if (sys.version_info[0] == 3) and (type(distanceObjectName) is str): 739 | distanceObjectName=distanceObjectName.encode('utf-8') 740 | return c_GetDistanceHandle(clientID, distanceObjectName, ct.byref(handle), operationMode), handle.value 741 | 742 | def simxReadCollision(clientID, collisionObjectHandle, operationMode): 743 | ''' 744 | Please have a look at the function description/documentation in the V-REP user manual 745 | ''' 746 | collisionState = ct.c_ubyte() 747 | return c_ReadCollision(clientID, collisionObjectHandle, ct.byref(collisionState), operationMode), bool(collisionState.value!=0) 748 | 749 | def simxReadDistance(clientID, distanceObjectHandle, operationMode): 750 | ''' 751 | Please have a look at the function description/documentation in the V-REP user manual 752 | ''' 753 | 754 | minimumDistance = ct.c_float() 755 | return c_ReadDistance(clientID, distanceObjectHandle, ct.byref(minimumDistance), operationMode), minimumDistance.value 756 | 757 | def simxRemoveObject(clientID, objectHandle, operationMode): 758 | ''' 759 | Please have a look at the function description/documentation in the V-REP user manual 760 | ''' 761 | 762 | return c_RemoveObject(clientID, objectHandle, operationMode) 763 | 764 | def simxRemoveModel(clientID, objectHandle, operationMode): 765 | ''' 766 | Please have a look at the function description/documentation in the V-REP user manual 767 | ''' 768 | 769 | return c_RemoveModel(clientID, objectHandle, operationMode) 770 | 771 | def simxRemoveUI(clientID, uiHandle, operationMode): 772 | ''' 773 | Please have a look at the function description/documentation in the V-REP user manual 774 | ''' 775 | 776 | return c_RemoveUI(clientID, uiHandle, operationMode) 777 | 778 | def simxCloseScene(clientID, operationMode): 779 | ''' 780 | Please have a look at the function description/documentation in the V-REP user manual 781 | ''' 782 | 783 | return c_CloseScene(clientID, operationMode) 784 | 785 | def simxGetObjects(clientID, objectType, operationMode): 786 | ''' 787 | Please have a look at the function description/documentation in the V-REP user manual 788 | ''' 789 | 790 | objectCount = ct.c_int() 791 | objectHandles = ct.POINTER(ct.c_int)() 792 | 793 | ret = c_GetObjects(clientID, objectType, ct.byref(objectCount), ct.byref(objectHandles), operationMode) 794 | handles = [] 795 | if ret == 0: 796 | for i in range(objectCount.value): 797 | handles.append(objectHandles[i]) 798 | 799 | return ret, handles 800 | 801 | 802 | def simxDisplayDialog(clientID, titleText, mainText, dialogType, initialText, titleColors, dialogColors, operationMode): 803 | ''' 804 | Please have a look at the function description/documentation in the V-REP user manual 805 | ''' 806 | if titleColors != None: 807 | c_titleColors = (ct.c_float*6)(*titleColors) 808 | else: 809 | c_titleColors = None 810 | if dialogColors != None: 811 | c_dialogColors = (ct.c_float*6)(*dialogColors) 812 | else: 813 | c_dialogColors = None 814 | 815 | c_dialogHandle = ct.c_int() 816 | c_uiHandle = ct.c_int() 817 | if sys.version_info[0] == 3: 818 | if type(titleText) is str: 819 | titleText=titleText.encode('utf-8') 820 | if type(mainText) is str: 821 | mainText=mainText.encode('utf-8') 822 | if type(initialText) is str: 823 | initialText=initialText.encode('utf-8') 824 | return c_DisplayDialog(clientID, titleText, mainText, dialogType, initialText, c_titleColors, c_dialogColors, ct.byref(c_dialogHandle), ct.byref(c_uiHandle), operationMode), c_dialogHandle.value, c_uiHandle.value 825 | 826 | def simxEndDialog(clientID, dialogHandle, operationMode): 827 | ''' 828 | Please have a look at the function description/documentation in the V-REP user manual 829 | ''' 830 | 831 | return c_EndDialog(clientID, dialogHandle, operationMode) 832 | 833 | def simxGetDialogInput(clientID, dialogHandle, operationMode): 834 | ''' 835 | Please have a look at the function description/documentation in the V-REP user manual 836 | ''' 837 | inputText = ct.POINTER(ct.c_char)() 838 | ret = c_GetDialogInput(clientID, dialogHandle, ct.byref(inputText), operationMode) 839 | 840 | a = bytearray() 841 | if ret == 0: 842 | i = 0 843 | while inputText[i] != b'\0': 844 | if sys.version_info[0] == 3: 845 | a.append(int.from_bytes(inputText[i],'big')) 846 | else: 847 | a.append(inputText[i]) 848 | i = i+1 849 | 850 | if sys.version_info[0] == 3: 851 | a=str(a,'utf-8') 852 | else: 853 | a=str(a) 854 | return ret, a 855 | 856 | 857 | def simxGetDialogResult(clientID, dialogHandle, operationMode): 858 | ''' 859 | Please have a look at the function description/documentation in the V-REP user manual 860 | ''' 861 | result = ct.c_int() 862 | return c_GetDialogResult(clientID, dialogHandle, ct.byref(result), operationMode), result.value 863 | 864 | def simxCopyPasteObjects(clientID, objectHandles, operationMode): 865 | ''' 866 | Please have a look at the function description/documentation in the V-REP user manual 867 | ''' 868 | c_objectHandles = (ct.c_int*len(objectHandles))(*objectHandles) 869 | c_objectHandles = ct.cast(c_objectHandles,ct.POINTER(ct.c_int)) # IronPython needs this 870 | newObjectCount = ct.c_int() 871 | newObjectHandles = ct.POINTER(ct.c_int)() 872 | ret = c_CopyPasteObjects(clientID, c_objectHandles, len(objectHandles), ct.byref(newObjectHandles), ct.byref(newObjectCount), operationMode) 873 | 874 | newobj = [] 875 | if ret == 0: 876 | for i in range(newObjectCount.value): 877 | newobj.append(newObjectHandles[i]) 878 | 879 | return ret, newobj 880 | 881 | 882 | def simxGetObjectSelection(clientID, operationMode): 883 | ''' 884 | Please have a look at the function description/documentation in the V-REP user manual 885 | ''' 886 | objectCount = ct.c_int() 887 | objectHandles = ct.POINTER(ct.c_int)() 888 | ret = c_GetObjectSelection(clientID, ct.byref(objectHandles), ct.byref(objectCount), operationMode) 889 | 890 | newobj = [] 891 | if ret == 0: 892 | for i in range(objectCount.value): 893 | newobj.append(objectHandles[i]) 894 | 895 | return ret, newobj 896 | 897 | 898 | 899 | def simxSetObjectSelection(clientID, objectHandles, operationMode): 900 | ''' 901 | Please have a look at the function description/documentation in the V-REP user manual 902 | ''' 903 | 904 | c_objectHandles = (ct.c_int*len(objectHandles))(*objectHandles) 905 | return c_SetObjectSelection(clientID, c_objectHandles, len(objectHandles), operationMode) 906 | 907 | def simxClearFloatSignal(clientID, signalName, operationMode): 908 | ''' 909 | Please have a look at the function description/documentation in the V-REP user manual 910 | ''' 911 | 912 | if (sys.version_info[0] == 3) and (type(signalName) is str): 913 | signalName=signalName.encode('utf-8') 914 | return c_ClearFloatSignal(clientID, signalName, operationMode) 915 | 916 | def simxClearIntegerSignal(clientID, signalName, operationMode): 917 | ''' 918 | Please have a look at the function description/documentation in the V-REP user manual 919 | ''' 920 | 921 | if (sys.version_info[0] == 3) and (type(signalName) is str): 922 | signalName=signalName.encode('utf-8') 923 | return c_ClearIntegerSignal(clientID, signalName, operationMode) 924 | 925 | def simxClearStringSignal(clientID, signalName, operationMode): 926 | ''' 927 | Please have a look at the function description/documentation in the V-REP user manual 928 | ''' 929 | 930 | if (sys.version_info[0] == 3) and (type(signalName) is str): 931 | signalName=signalName.encode('utf-8') 932 | return c_ClearStringSignal(clientID, signalName, operationMode) 933 | 934 | def simxGetFloatSignal(clientID, signalName, operationMode): 935 | ''' 936 | Please have a look at the function description/documentation in the V-REP user manual 937 | ''' 938 | 939 | signalValue = ct.c_float() 940 | if (sys.version_info[0] == 3) and (type(signalName) is str): 941 | signalName=signalName.encode('utf-8') 942 | return c_GetFloatSignal(clientID, signalName, ct.byref(signalValue), operationMode), signalValue.value 943 | 944 | def simxGetIntegerSignal(clientID, signalName, operationMode): 945 | ''' 946 | Please have a look at the function description/documentation in the V-REP user manual 947 | ''' 948 | 949 | signalValue = ct.c_int() 950 | if (sys.version_info[0] == 3) and (type(signalName) is str): 951 | signalName=signalName.encode('utf-8') 952 | return c_GetIntegerSignal(clientID, signalName, ct.byref(signalValue), operationMode), signalValue.value 953 | 954 | def simxGetStringSignal(clientID, signalName, operationMode): 955 | ''' 956 | Please have a look at the function description/documentation in the V-REP user manual 957 | ''' 958 | 959 | signalLength = ct.c_int(); 960 | signalValue = ct.POINTER(ct.c_ubyte)() 961 | if (sys.version_info[0] == 3) and (type(signalName) is str): 962 | signalName=signalName.encode('utf-8') 963 | ret = c_GetStringSignal(clientID, signalName, ct.byref(signalValue), ct.byref(signalLength), operationMode) 964 | 965 | a = bytearray() 966 | if ret == 0: 967 | for i in range(signalLength.value): 968 | a.append(signalValue[i]) 969 | if sys.version_info[0] != 3: 970 | a=str(a) 971 | 972 | return ret, a 973 | 974 | def simxGetAndClearStringSignal(clientID, signalName, operationMode): 975 | ''' 976 | Please have a look at the function description/documentation in the V-REP user manual 977 | ''' 978 | 979 | signalLength = ct.c_int(); 980 | signalValue = ct.POINTER(ct.c_ubyte)() 981 | if (sys.version_info[0] == 3) and (type(signalName) is str): 982 | signalName=signalName.encode('utf-8') 983 | ret = c_GetAndClearStringSignal(clientID, signalName, ct.byref(signalValue), ct.byref(signalLength), operationMode) 984 | 985 | a = bytearray() 986 | if ret == 0: 987 | for i in range(signalLength.value): 988 | a.append(signalValue[i]) 989 | if sys.version_info[0] != 3: 990 | a=str(a) 991 | 992 | return ret, a 993 | 994 | def simxReadStringStream(clientID, signalName, operationMode): 995 | ''' 996 | Please have a look at the function description/documentation in the V-REP user manual 997 | ''' 998 | 999 | signalLength = ct.c_int(); 1000 | signalValue = ct.POINTER(ct.c_ubyte)() 1001 | if (sys.version_info[0] == 3) and (type(signalName) is str): 1002 | signalName=signalName.encode('utf-8') 1003 | ret = c_ReadStringStream(clientID, signalName, ct.byref(signalValue), ct.byref(signalLength), operationMode) 1004 | 1005 | a = bytearray() 1006 | if ret == 0: 1007 | for i in range(signalLength.value): 1008 | a.append(signalValue[i]) 1009 | if sys.version_info[0] != 3: 1010 | a=str(a) 1011 | 1012 | return ret, a 1013 | 1014 | def simxSetFloatSignal(clientID, signalName, signalValue, operationMode): 1015 | ''' 1016 | Please have a look at the function description/documentation in the V-REP user manual 1017 | ''' 1018 | 1019 | if (sys.version_info[0] == 3) and (type(signalName) is str): 1020 | signalName=signalName.encode('utf-8') 1021 | return c_SetFloatSignal(clientID, signalName, signalValue, operationMode) 1022 | 1023 | def simxSetIntegerSignal(clientID, signalName, signalValue, operationMode): 1024 | ''' 1025 | Please have a look at the function description/documentation in the V-REP user manual 1026 | ''' 1027 | 1028 | if (sys.version_info[0] == 3) and (type(signalName) is str): 1029 | signalName=signalName.encode('utf-8') 1030 | return c_SetIntegerSignal(clientID, signalName, signalValue, operationMode) 1031 | 1032 | def simxSetStringSignal(clientID, signalName, signalValue, operationMode): 1033 | ''' 1034 | Please have a look at the function description/documentation in the V-REP user manual 1035 | ''' 1036 | 1037 | sigV=signalValue 1038 | if sys.version_info[0] == 3: 1039 | if type(signalName) is str: 1040 | signalName=signalName.encode('utf-8') 1041 | if type(signalValue) is bytearray: 1042 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1043 | if type(signalValue) is str: 1044 | signalValue=signalValue.encode('utf-8') 1045 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1046 | else: 1047 | if type(signalValue) is bytearray: 1048 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1049 | if type(signalValue) is str: 1050 | signalValue=bytearray(signalValue) 1051 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1052 | sigV=ct.cast(sigV,ct.POINTER(ct.c_ubyte)) # IronPython needs this 1053 | return c_SetStringSignal(clientID, signalName, sigV, len(signalValue), operationMode) 1054 | 1055 | def simxAppendStringSignal(clientID, signalName, signalValue, operationMode): 1056 | ''' 1057 | Please have a look at the function description/documentation in the V-REP user manual 1058 | ''' 1059 | 1060 | sigV=signalValue 1061 | if sys.version_info[0] == 3: 1062 | if type(signalName) is str: 1063 | signalName=signalName.encode('utf-8') 1064 | if type(signalValue) is bytearray: 1065 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1066 | if type(signalValue) is str: 1067 | signalValue=signalValue.encode('utf-8') 1068 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1069 | else: 1070 | if type(signalValue) is bytearray: 1071 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1072 | if type(signalValue) is str: 1073 | signalValue=bytearray(signalValue) 1074 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1075 | sigV=ct.cast(sigV,ct.POINTER(ct.c_ubyte)) # IronPython needs this 1076 | return c_AppendStringSignal(clientID, signalName, sigV, len(signalValue), operationMode) 1077 | 1078 | def simxWriteStringStream(clientID, signalName, signalValue, operationMode): 1079 | ''' 1080 | Please have a look at the function description/documentation in the V-REP user manual 1081 | ''' 1082 | 1083 | sigV=signalValue 1084 | if sys.version_info[0] == 3: 1085 | if type(signalName) is str: 1086 | signalName=signalName.encode('utf-8') 1087 | if type(signalValue) is bytearray: 1088 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1089 | if type(signalValue) is str: 1090 | signalValue=signalValue.encode('utf-8') 1091 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1092 | else: 1093 | if type(signalValue) is bytearray: 1094 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1095 | if type(signalValue) is str: 1096 | signalValue=bytearray(signalValue) 1097 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1098 | sigV=ct.cast(sigV,ct.POINTER(ct.c_ubyte)) # IronPython needs this 1099 | return c_WriteStringStream(clientID, signalName, sigV, len(signalValue), operationMode) 1100 | 1101 | def simxGetObjectFloatParameter(clientID, objectHandle, parameterID, operationMode): 1102 | ''' 1103 | Please have a look at the function description/documentation in the V-REP user manual 1104 | ''' 1105 | 1106 | parameterValue = ct.c_float() 1107 | return c_GetObjectFloatParameter(clientID, objectHandle, parameterID, ct.byref(parameterValue), operationMode), parameterValue.value 1108 | 1109 | def simxSetObjectFloatParameter(clientID, objectHandle, parameterID, parameterValue, operationMode): 1110 | ''' 1111 | Please have a look at the function description/documentation in the V-REP user manual 1112 | ''' 1113 | 1114 | return c_SetObjectFloatParameter(clientID, objectHandle, parameterID, parameterValue, operationMode) 1115 | 1116 | def simxGetObjectIntParameter(clientID, objectHandle, parameterID, operationMode): 1117 | ''' 1118 | Please have a look at the function description/documentation in the V-REP user manual 1119 | ''' 1120 | 1121 | parameterValue = ct.c_int() 1122 | return c_GetObjectIntParameter(clientID, objectHandle, parameterID, ct.byref(parameterValue), operationMode), parameterValue.value 1123 | 1124 | def simxSetObjectIntParameter(clientID, objectHandle, parameterID, parameterValue, operationMode): 1125 | ''' 1126 | Please have a look at the function description/documentation in the V-REP user manual 1127 | ''' 1128 | 1129 | return c_SetObjectIntParameter(clientID, objectHandle, parameterID, parameterValue, operationMode) 1130 | 1131 | def simxGetModelProperty(clientID, objectHandle, operationMode): 1132 | ''' 1133 | Please have a look at the function description/documentation in the V-REP user manual 1134 | ''' 1135 | prop = ct.c_int() 1136 | return c_GetModelProperty(clientID, objectHandle, ct.byref(prop), operationMode), prop.value 1137 | 1138 | def simxSetModelProperty(clientID, objectHandle, prop, operationMode): 1139 | ''' 1140 | Please have a look at the function description/documentation in the V-REP user manual 1141 | ''' 1142 | 1143 | return c_SetModelProperty(clientID, objectHandle, prop, operationMode) 1144 | 1145 | def simxStart(connectionAddress, connectionPort, waitUntilConnected, doNotReconnectOnceDisconnected, timeOutInMs, commThreadCycleInMs): 1146 | ''' 1147 | Please have a look at the function description/documentation in the V-REP user manual 1148 | ''' 1149 | 1150 | if (sys.version_info[0] == 3) and (type(connectionAddress) is str): 1151 | connectionAddress=connectionAddress.encode('utf-8') 1152 | return c_Start(connectionAddress, connectionPort, waitUntilConnected, doNotReconnectOnceDisconnected, timeOutInMs, commThreadCycleInMs) 1153 | 1154 | def simxFinish(clientID): 1155 | ''' 1156 | Please have a look at the function description/documentation in the V-REP user manual 1157 | ''' 1158 | 1159 | return c_Finish(clientID) 1160 | 1161 | def simxGetPingTime(clientID): 1162 | ''' 1163 | Please have a look at the function description/documentation in the V-REP user manual 1164 | ''' 1165 | pingTime = ct.c_int() 1166 | return c_GetPingTime(clientID, ct.byref(pingTime)), pingTime.value 1167 | 1168 | def simxGetLastCmdTime(clientID): 1169 | ''' 1170 | Please have a look at the function description/documentation in the V-REP user manual 1171 | ''' 1172 | 1173 | return c_GetLastCmdTime(clientID) 1174 | 1175 | def simxSynchronousTrigger(clientID): 1176 | ''' 1177 | Please have a look at the function description/documentation in the V-REP user manual 1178 | ''' 1179 | 1180 | return c_SynchronousTrigger(clientID) 1181 | 1182 | def simxSynchronous(clientID, enable): 1183 | ''' 1184 | Please have a look at the function description/documentation in the V-REP user manual 1185 | ''' 1186 | 1187 | return c_Synchronous(clientID, enable) 1188 | 1189 | def simxPauseCommunication(clientID, enable): 1190 | ''' 1191 | Please have a look at the function description/documentation in the V-REP user manual 1192 | ''' 1193 | 1194 | return c_PauseCommunication(clientID, enable) 1195 | 1196 | def simxGetInMessageInfo(clientID, infoType): 1197 | ''' 1198 | Please have a look at the function description/documentation in the V-REP user manual 1199 | ''' 1200 | info = ct.c_int() 1201 | return c_GetInMessageInfo(clientID, infoType, ct.byref(info)), info.value 1202 | 1203 | def simxGetOutMessageInfo(clientID, infoType): 1204 | ''' 1205 | Please have a look at the function description/documentation in the V-REP user manual 1206 | ''' 1207 | info = ct.c_int() 1208 | return c_GetOutMessageInfo(clientID, infoType, ct.byref(info)), info.value 1209 | 1210 | def simxGetConnectionId(clientID): 1211 | ''' 1212 | Please have a look at the function description/documentation in the V-REP user manual 1213 | ''' 1214 | 1215 | return c_GetConnectionId(clientID) 1216 | 1217 | def simxCreateBuffer(bufferSize): 1218 | ''' 1219 | Please have a look at the function description/documentation in the V-REP user manual 1220 | ''' 1221 | 1222 | return c_CreateBuffer(bufferSize) 1223 | 1224 | def simxReleaseBuffer(buffer): 1225 | ''' 1226 | Please have a look at the function description/documentation in the V-REP user manual 1227 | ''' 1228 | 1229 | return c_ReleaseBuffer(buffer) 1230 | 1231 | def simxTransferFile(clientID, filePathAndName, fileName_serverSide, timeOut, operationMode): 1232 | ''' 1233 | Please have a look at the function description/documentation in the V-REP user manual 1234 | ''' 1235 | 1236 | if (sys.version_info[0] == 3) and (type(filePathAndName) is str): 1237 | filePathAndName=filePathAndName.encode('utf-8') 1238 | return c_TransferFile(clientID, filePathAndName, fileName_serverSide, timeOut, operationMode) 1239 | 1240 | def simxEraseFile(clientID, fileName_serverSide, operationMode): 1241 | ''' 1242 | Please have a look at the function description/documentation in the V-REP user manual 1243 | ''' 1244 | 1245 | if (sys.version_info[0] == 3) and (type(fileName_serverSide) is str): 1246 | fileName_serverSide=fileName_serverSide.encode('utf-8') 1247 | return c_EraseFile(clientID, fileName_serverSide, operationMode) 1248 | 1249 | def simxCreateDummy(clientID, size, color, operationMode): 1250 | ''' 1251 | Please have a look at the function description/documentation in the V-REP user manual 1252 | ''' 1253 | 1254 | handle = ct.c_int() 1255 | if color != None: 1256 | c_color = (ct.c_ubyte*12)(*color) 1257 | else: 1258 | c_color = None 1259 | return c_CreateDummy(clientID, size, c_color, ct.byref(handle), operationMode), handle.value 1260 | 1261 | def simxQuery(clientID, signalName, signalValue, retSignalName, timeOutInMs): 1262 | ''' 1263 | Please have a look at the function description/documentation in the V-REP user manual 1264 | ''' 1265 | 1266 | retSignalLength = ct.c_int(); 1267 | retSignalValue = ct.POINTER(ct.c_ubyte)() 1268 | 1269 | sigV=signalValue 1270 | if sys.version_info[0] == 3: 1271 | if type(signalName) is str: 1272 | signalName=signalName.encode('utf-8') 1273 | if type(retSignalName) is str: 1274 | retSignalName=retSignalName.encode('utf-8') 1275 | if type(signalValue) is bytearray: 1276 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1277 | if type(signalValue) is str: 1278 | signalValue=signalValue.encode('utf-8') 1279 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1280 | else: 1281 | if type(signalValue) is bytearray: 1282 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1283 | if type(signalValue) is str: 1284 | signalValue=bytearray(signalValue) 1285 | sigV = (ct.c_ubyte*len(signalValue))(*signalValue) 1286 | sigV=ct.cast(sigV,ct.POINTER(ct.c_ubyte)) # IronPython needs this 1287 | 1288 | ret = c_Query(clientID, signalName, sigV, len(signalValue), retSignalName, ct.byref(retSignalValue), ct.byref(retSignalLength), timeOutInMs) 1289 | 1290 | a = bytearray() 1291 | if ret == 0: 1292 | for i in range(retSignalLength.value): 1293 | a.append(retSignalValue[i]) 1294 | if sys.version_info[0] != 3: 1295 | a=str(a) 1296 | 1297 | return ret, a 1298 | 1299 | def simxGetObjectGroupData(clientID, objectType, dataType, operationMode): 1300 | ''' 1301 | Please have a look at the function description/documentation in the V-REP user manual 1302 | ''' 1303 | 1304 | handles =[] 1305 | intData =[] 1306 | floatData =[] 1307 | stringData =[] 1308 | handlesC = ct.c_int() 1309 | handlesP = ct.POINTER(ct.c_int)() 1310 | intDataC = ct.c_int() 1311 | intDataP = ct.POINTER(ct.c_int)() 1312 | floatDataC = ct.c_int() 1313 | floatDataP = ct.POINTER(ct.c_float)() 1314 | stringDataC = ct.c_int() 1315 | stringDataP = ct.POINTER(ct.c_char)() 1316 | ret = c_GetObjectGroupData(clientID, objectType, dataType, ct.byref(handlesC), ct.byref(handlesP), ct.byref(intDataC), ct.byref(intDataP), ct.byref(floatDataC), ct.byref(floatDataP), ct.byref(stringDataC), ct.byref(stringDataP), operationMode) 1317 | 1318 | if ret == 0: 1319 | for i in range(handlesC.value): 1320 | handles.append(handlesP[i]) 1321 | for i in range(intDataC.value): 1322 | intData.append(intDataP[i]) 1323 | for i in range(floatDataC.value): 1324 | floatData.append(floatDataP[i]) 1325 | s = 0 1326 | for i in range(stringDataC.value): 1327 | a = bytearray() 1328 | while stringDataP[s] != b'\0': 1329 | if sys.version_info[0] == 3: 1330 | a.append(int.from_bytes(stringDataP[s],'big')) 1331 | else: 1332 | a.append(stringDataP[s]) 1333 | s += 1 1334 | s += 1 #skip null 1335 | if sys.version_info[0] == 3: 1336 | a=str(a,'utf-8') 1337 | else: 1338 | a=str(a) 1339 | stringData.append(a) 1340 | 1341 | return ret, handles, intData, floatData, stringData 1342 | 1343 | def simxCallScriptFunction(clientID, scriptDescription, options, functionName, inputInts, inputFloats, inputStrings, inputBuffer, operationMode): 1344 | ''' 1345 | Please have a look at the function description/documentation in the V-REP user manual 1346 | ''' 1347 | 1348 | inputBufferV=inputBuffer 1349 | if sys.version_info[0] == 3: 1350 | if type(scriptDescription) is str: 1351 | scriptDescription=scriptDescription.encode('utf-8') 1352 | if type(functionName) is str: 1353 | functionName=functionName.encode('utf-8') 1354 | if type(inputBuffer) is bytearray: 1355 | inputBufferV = (ct.c_ubyte*len(inputBuffer))(*inputBuffer) 1356 | if type(inputBuffer) is str: 1357 | inputBuffer=inputBuffer.encode('utf-8') 1358 | inputBufferV = (ct.c_ubyte*len(inputBuffer))(*inputBuffer) 1359 | else: 1360 | if type(inputBuffer) is bytearray: 1361 | inputBufferV = (ct.c_ubyte*len(inputBuffer))(*inputBuffer) 1362 | if type(inputBuffer) is str: 1363 | inputBuffer=bytearray(inputBuffer) 1364 | inputBufferV = (ct.c_ubyte*len(inputBuffer))(*inputBuffer) 1365 | inputBufferV=ct.cast(inputBufferV,ct.POINTER(ct.c_ubyte)) # IronPython needs this 1366 | 1367 | c_inInts = (ct.c_int*len(inputInts))(*inputInts) 1368 | c_inInts = ct.cast(c_inInts,ct.POINTER(ct.c_int)) # IronPython needs this 1369 | c_inFloats = (ct.c_float*len(inputFloats))(*inputFloats) 1370 | c_inFloats = ct.cast(c_inFloats,ct.POINTER(ct.c_float)) # IronPython needs this 1371 | 1372 | concatStr=''.encode('utf-8') 1373 | for i in range(len(inputStrings)): 1374 | a=inputStrings[i] 1375 | a=a+'\0' 1376 | if type(a) is str: 1377 | a=a.encode('utf-8') 1378 | concatStr=concatStr+a 1379 | c_inStrings = (ct.c_char*len(concatStr))(*concatStr) 1380 | 1381 | intDataOut =[] 1382 | floatDataOut =[] 1383 | stringDataOut =[] 1384 | bufferOut =bytearray() 1385 | 1386 | intDataC = ct.c_int() 1387 | intDataP = ct.POINTER(ct.c_int)() 1388 | floatDataC = ct.c_int() 1389 | floatDataP = ct.POINTER(ct.c_float)() 1390 | stringDataC = ct.c_int() 1391 | stringDataP = ct.POINTER(ct.c_char)() 1392 | bufferS = ct.c_int() 1393 | bufferP = ct.POINTER(ct.c_ubyte)() 1394 | 1395 | ret = c_CallScriptFunction(clientID,scriptDescription,options,functionName,len(inputInts),c_inInts,len(inputFloats),c_inFloats,len(inputStrings),c_inStrings,len(inputBuffer),inputBufferV,ct.byref(intDataC),ct.byref(intDataP),ct.byref(floatDataC),ct.byref(floatDataP),ct.byref(stringDataC),ct.byref(stringDataP),ct.byref(bufferS),ct.byref(bufferP),operationMode) 1396 | 1397 | if ret == 0: 1398 | for i in range(intDataC.value): 1399 | intDataOut.append(intDataP[i]) 1400 | for i in range(floatDataC.value): 1401 | floatDataOut.append(floatDataP[i]) 1402 | s = 0 1403 | for i in range(stringDataC.value): 1404 | a = bytearray() 1405 | while stringDataP[s] != b'\0': 1406 | if sys.version_info[0] == 3: 1407 | a.append(int.from_bytes(stringDataP[s],'big')) 1408 | else: 1409 | a.append(stringDataP[s]) 1410 | s += 1 1411 | s += 1 #skip null 1412 | if sys.version_info[0] == 3: 1413 | a=str(a,'utf-8') 1414 | else: 1415 | a=str(a) 1416 | stringDataOut.append(a) 1417 | for i in range(bufferS.value): 1418 | bufferOut.append(bufferP[i]) 1419 | if sys.version_info[0] != 3: 1420 | bufferOut=str(bufferOut) 1421 | 1422 | return ret, intDataOut, floatDataOut, stringDataOut, bufferOut 1423 | 1424 | def simxGetObjectVelocity(clientID, objectHandle, operationMode): 1425 | ''' 1426 | Please have a look at the function description/documentation in the V-REP user manual 1427 | ''' 1428 | linearVel = (ct.c_float*3)() 1429 | angularVel = (ct.c_float*3)() 1430 | ret = c_GetObjectVelocity(clientID, objectHandle, linearVel, angularVel, operationMode) 1431 | arr1 = [] 1432 | for i in range(3): 1433 | arr1.append(linearVel[i]) 1434 | arr2 = [] 1435 | for i in range(3): 1436 | arr2.append(angularVel[i]) 1437 | return ret, arr1, arr2 1438 | 1439 | def simxPackInts(intList): 1440 | ''' 1441 | Please have a look at the function description/documentation in the V-REP user manual 1442 | ''' 1443 | 1444 | if sys.version_info[0] == 3: 1445 | s=bytes() 1446 | for i in range(len(intList)): 1447 | s=s+struct.pack('. 25 | # ------------------------------------------------------------------- 26 | # 27 | # This file was automatically created for V-REP release V3.4.0 rev. 1 on April 5th 2017 28 | 29 | #constants 30 | #Scene object types. Values are serialized 31 | sim_object_shape_type =0 32 | sim_object_joint_type =1 33 | sim_object_graph_type =2 34 | sim_object_camera_type =3 35 | sim_object_dummy_type =4 36 | sim_object_proximitysensor_type =5 37 | sim_object_reserved1 =6 38 | sim_object_reserved2 =7 39 | sim_object_path_type =8 40 | sim_object_visionsensor_type =9 41 | sim_object_volume_type =10 42 | sim_object_mill_type =11 43 | sim_object_forcesensor_type =12 44 | sim_object_light_type =13 45 | sim_object_mirror_type =14 46 | 47 | #General object types. Values are serialized 48 | sim_appobj_object_type =109 49 | sim_appobj_collision_type =110 50 | sim_appobj_distance_type =111 51 | sim_appobj_simulation_type =112 52 | sim_appobj_ik_type =113 53 | sim_appobj_constraintsolver_type=114 54 | sim_appobj_collection_type =115 55 | sim_appobj_ui_type =116 56 | sim_appobj_script_type =117 57 | sim_appobj_pathplanning_type =118 58 | sim_appobj_RESERVED_type =119 59 | sim_appobj_texture_type =120 60 | 61 | # Ik calculation methods. Values are serialized 62 | sim_ik_pseudo_inverse_method =0 63 | sim_ik_damped_least_squares_method =1 64 | sim_ik_jacobian_transpose_method =2 65 | 66 | # Ik constraints. Values are serialized 67 | sim_ik_x_constraint =1 68 | sim_ik_y_constraint =2 69 | sim_ik_z_constraint =4 70 | sim_ik_alpha_beta_constraint=8 71 | sim_ik_gamma_constraint =16 72 | sim_ik_avoidance_constraint =64 73 | 74 | # Ik calculation results 75 | sim_ikresult_not_performed =0 76 | sim_ikresult_success =1 77 | sim_ikresult_fail =2 78 | 79 | # Scene object sub-types. Values are serialized 80 | # Light sub-types 81 | sim_light_omnidirectional_subtype =1 82 | sim_light_spot_subtype =2 83 | sim_light_directional_subtype =3 84 | # Joint sub-types 85 | sim_joint_revolute_subtype =10 86 | sim_joint_prismatic_subtype =11 87 | sim_joint_spherical_subtype =12 88 | # Shape sub-types 89 | sim_shape_simpleshape_subtype =20 90 | sim_shape_multishape_subtype =21 91 | # Proximity sensor sub-types 92 | sim_proximitysensor_pyramid_subtype =30 93 | sim_proximitysensor_cylinder_subtype=31 94 | sim_proximitysensor_disc_subtype =32 95 | sim_proximitysensor_cone_subtype =33 96 | sim_proximitysensor_ray_subtype =34 97 | # Mill sub-types 98 | sim_mill_pyramid_subtype =40 99 | sim_mill_cylinder_subtype =41 100 | sim_mill_disc_subtype =42 101 | sim_mill_cone_subtype =42 102 | # No sub-type 103 | sim_object_no_subtype =200 104 | 105 | 106 | #Scene object main properties (serialized) 107 | sim_objectspecialproperty_collidable =0x0001 108 | sim_objectspecialproperty_measurable =0x0002 109 | #reserved =0x0004 110 | #reserved =0x0008 111 | sim_objectspecialproperty_detectable_ultrasonic =0x0010 112 | sim_objectspecialproperty_detectable_infrared =0x0020 113 | sim_objectspecialproperty_detectable_laser =0x0040 114 | sim_objectspecialproperty_detectable_inductive =0x0080 115 | sim_objectspecialproperty_detectable_capacitive =0x0100 116 | sim_objectspecialproperty_renderable =0x0200 117 | sim_objectspecialproperty_detectable_all =sim_objectspecialproperty_detectable_ultrasonic|sim_objectspecialproperty_detectable_infrared|sim_objectspecialproperty_detectable_laser|sim_objectspecialproperty_detectable_inductive|sim_objectspecialproperty_detectable_capacitive 118 | sim_objectspecialproperty_cuttable =0x0400 119 | sim_objectspecialproperty_pathplanning_ignored =0x0800 120 | 121 | # Model properties (serialized) 122 | sim_modelproperty_not_collidable =0x0001 123 | sim_modelproperty_not_measurable =0x0002 124 | sim_modelproperty_not_renderable =0x0004 125 | sim_modelproperty_not_detectable =0x0008 126 | sim_modelproperty_not_cuttable =0x0010 127 | sim_modelproperty_not_dynamic =0x0020 128 | sim_modelproperty_not_respondable =0x0040 # cannot be selected if sim_modelproperty_not_dynamic is not selected 129 | sim_modelproperty_not_reset =0x0080 # Model is not reset at simulation end. This flag is cleared at simulation end 130 | sim_modelproperty_not_visible =0x0100 # Whole model is invisible independent of local visibility settings 131 | sim_modelproperty_not_model =0xf000 # object is not a model 132 | 133 | 134 | # Check the documentation instead of comments below!! 135 | # Following messages are dispatched to the Lua-message container 136 | sim_message_ui_button_state_change =0 # a UI button slider etc. changed (due to a user's action). aux[0]=UI handle aux[1]=button handle aux[2]=button attributes aux[3]=slider position (if slider) 137 | sim_message_reserved9 =1 # Do not use 138 | sim_message_object_selection_changed=2 139 | sim_message_reserved10 =3 # do not use 140 | sim_message_model_loaded =4 141 | sim_message_reserved11 =5 # do not use 142 | sim_message_keypress =6 # a key was pressed while the focus was on a page (aux[0]=key aux[1]=ctrl and shift key state) 143 | sim_message_bannerclicked =7 # a banner was clicked (aux[0]=banner ID) 144 | 145 | 146 | # Following messages are dispatched only to the C-API (not available from Lua) 147 | sim_message_for_c_api_only_start =0x100 # Do not use 148 | sim_message_reserved1 =0x101 # Do not use 149 | sim_message_reserved2 =0x102 # Do not use 150 | sim_message_reserved3 =0x103 # Do not use 151 | sim_message_eventcallback_scenesave =0x104 # about to save a scene 152 | sim_message_eventcallback_modelsave =0x105 # about to save a model (current selection will be saved) 153 | sim_message_eventcallback_moduleopen =0x106 # called when simOpenModule in Lua is called 154 | sim_message_eventcallback_modulehandle =0x107 # called when simHandleModule in Lua is called with argument false 155 | sim_message_eventcallback_moduleclose =0x108 # called when simCloseModule in Lua is called 156 | sim_message_reserved4 =0x109 # Do not use 157 | sim_message_reserved5 =0x10a # Do not use 158 | sim_message_reserved6 =0x10b # Do not use 159 | sim_message_reserved7 =0x10c # Do not use 160 | sim_message_eventcallback_instancepass =0x10d # Called once every main application loop pass. auxiliaryData[0] contains event flags of events that happened since last time 161 | sim_message_eventcallback_broadcast =0x10e 162 | sim_message_eventcallback_imagefilter_enumreset =0x10f 163 | sim_message_eventcallback_imagefilter_enumerate =0x110 164 | sim_message_eventcallback_imagefilter_adjustparams =0x111 165 | sim_message_eventcallback_imagefilter_reserved =0x112 166 | sim_message_eventcallback_imagefilter_process =0x113 167 | sim_message_eventcallback_reserved1 =0x114 # do not use 168 | sim_message_eventcallback_reserved2 =0x115 # do not use 169 | sim_message_eventcallback_reserved3 =0x116 # do not use 170 | sim_message_eventcallback_reserved4 =0x117 # do not use 171 | sim_message_eventcallback_abouttoundo =0x118 # the undo button was hit and a previous state is about to be restored 172 | sim_message_eventcallback_undoperformed =0x119 # the undo button was hit and a previous state restored 173 | sim_message_eventcallback_abouttoredo =0x11a # the redo button was hit and a future state is about to be restored 174 | sim_message_eventcallback_redoperformed =0x11b # the redo button was hit and a future state restored 175 | sim_message_eventcallback_scripticondblclick =0x11c # scipt icon was double clicked. (aux[0]=object handle associated with script set replyData[0] to 1 if script should not be opened) 176 | sim_message_eventcallback_simulationabouttostart =0x11d 177 | sim_message_eventcallback_simulationended =0x11e 178 | sim_message_eventcallback_reserved5 =0x11f # do not use 179 | sim_message_eventcallback_keypress =0x120 # a key was pressed while the focus was on a page (aux[0]=key aux[1]=ctrl and shift key state) 180 | sim_message_eventcallback_modulehandleinsensingpart =0x121 # called when simHandleModule in Lua is called with argument true 181 | sim_message_eventcallback_renderingpass =0x122 # called just before the scene is rendered 182 | sim_message_eventcallback_bannerclicked =0x123 # called when a banner was clicked (aux[0]=banner ID) 183 | sim_message_eventcallback_menuitemselected =0x124 # auxiliaryData[0] indicates the handle of the item auxiliaryData[1] indicates the state of the item 184 | sim_message_eventcallback_refreshdialogs =0x125 # aux[0]=refresh degree (0=light 1=medium 2=full) 185 | sim_message_eventcallback_sceneloaded =0x126 186 | sim_message_eventcallback_modelloaded =0x127 187 | sim_message_eventcallback_instanceswitch =0x128 188 | sim_message_eventcallback_guipass =0x129 189 | sim_message_eventcallback_mainscriptabouttobecalled =0x12a 190 | sim_message_eventcallback_rmlposition =0x12b #the command simRMLPosition was called. The appropriate plugin should handle the call 191 | sim_message_eventcallback_rmlvelocity =0x12c # the command simRMLVelocity was called. The appropriate plugin should handle the call 192 | sim_message_simulation_start_resume_request =0x1000 193 | sim_message_simulation_pause_request =0x1001 194 | sim_message_simulation_stop_request =0x1002 195 | 196 | # Scene object properties. Combine with the | operator 197 | sim_objectproperty_reserved1 =0x0000 198 | sim_objectproperty_reserved2 =0x0001 199 | sim_objectproperty_reserved3 =0x0002 200 | sim_objectproperty_reserved4 =0x0003 201 | sim_objectproperty_reserved5 =0x0004 # formely sim_objectproperty_visible 202 | sim_objectproperty_reserved6 =0x0008 # formely sim_objectproperty_wireframe 203 | sim_objectproperty_collapsed =0x0010 204 | sim_objectproperty_selectable =0x0020 205 | sim_objectproperty_reserved7 =0x0040 206 | sim_objectproperty_selectmodelbaseinstead =0x0080 207 | sim_objectproperty_dontshowasinsidemodel =0x0100 208 | # reserved =0x0200 209 | sim_objectproperty_canupdatedna =0x0400 210 | sim_objectproperty_selectinvisible =0x0800 211 | sim_objectproperty_depthinvisible =0x1000 212 | 213 | 214 | # type of arguments (input and output) for custom lua commands 215 | sim_lua_arg_nil =0 216 | sim_lua_arg_bool =1 217 | sim_lua_arg_int =2 218 | sim_lua_arg_float =3 219 | sim_lua_arg_string =4 220 | sim_lua_arg_invalid =5 221 | sim_lua_arg_table =8 222 | 223 | # custom user interface properties. Values are serialized. 224 | sim_ui_property_visible =0x0001 225 | sim_ui_property_visibleduringsimulationonly =0x0002 226 | sim_ui_property_moveable =0x0004 227 | sim_ui_property_relativetoleftborder =0x0008 228 | sim_ui_property_relativetotopborder =0x0010 229 | sim_ui_property_fixedwidthfont =0x0020 230 | sim_ui_property_systemblock =0x0040 231 | sim_ui_property_settocenter =0x0080 232 | sim_ui_property_rolledup =0x0100 233 | sim_ui_property_selectassociatedobject =0x0200 234 | sim_ui_property_visiblewhenobjectselected =0x0400 235 | 236 | 237 | # button properties. Values are serialized. 238 | sim_buttonproperty_button =0x0000 239 | sim_buttonproperty_label =0x0001 240 | sim_buttonproperty_slider =0x0002 241 | sim_buttonproperty_editbox =0x0003 242 | sim_buttonproperty_staydown =0x0008 243 | sim_buttonproperty_enabled =0x0010 244 | sim_buttonproperty_borderless =0x0020 245 | sim_buttonproperty_horizontallycentered =0x0040 246 | sim_buttonproperty_ignoremouse =0x0080 247 | sim_buttonproperty_isdown =0x0100 248 | sim_buttonproperty_transparent =0x0200 249 | sim_buttonproperty_nobackgroundcolor =0x0400 250 | sim_buttonproperty_rollupaction =0x0800 251 | sim_buttonproperty_closeaction =0x1000 252 | sim_buttonproperty_verticallycentered =0x2000 253 | sim_buttonproperty_downupevent =0x4000 254 | 255 | 256 | # Simulation status 257 | sim_simulation_stopped =0x00 # Simulation is stopped 258 | sim_simulation_paused =0x08 # Simulation is paused 259 | sim_simulation_advancing =0x10 # Simulation is advancing 260 | sim_simulation_advancing_firstafterstop =sim_simulation_advancing|0x00 # First simulation pass (1x) 261 | sim_simulation_advancing_running =sim_simulation_advancing|0x01 # Normal simulation pass (>=1x) 262 | # reserved =sim_simulation_advancing|0x02 263 | sim_simulation_advancing_lastbeforepause =sim_simulation_advancing|0x03 # Last simulation pass before pause (1x) 264 | sim_simulation_advancing_firstafterpause =sim_simulation_advancing|0x04 # First simulation pass after pause (1x) 265 | sim_simulation_advancing_abouttostop =sim_simulation_advancing|0x05 # "Trying to stop" simulation pass (>=1x) 266 | sim_simulation_advancing_lastbeforestop =sim_simulation_advancing|0x06 # Last simulation pass (1x) 267 | 268 | 269 | # Script execution result (first return value) 270 | sim_script_no_error =0 271 | sim_script_main_script_nonexistent =1 272 | sim_script_main_script_not_called =2 273 | sim_script_reentrance_error =4 274 | sim_script_lua_error =8 275 | sim_script_call_error =16 276 | 277 | 278 | # Script types (serialized!) 279 | sim_scripttype_mainscript =0 280 | sim_scripttype_childscript =1 281 | sim_scripttype_jointctrlcallback =4 282 | sim_scripttype_contactcallback =5 283 | sim_scripttype_customizationscript =6 284 | sim_scripttype_generalcallback =7 285 | 286 | # API call error messages 287 | sim_api_errormessage_ignore =0 # does not memorize nor output errors 288 | sim_api_errormessage_report =1 # memorizes errors (default for C-API calls) 289 | sim_api_errormessage_output =2 # memorizes and outputs errors (default for Lua-API calls) 290 | 291 | 292 | # special argument of some functions 293 | sim_handle_all =-2 294 | sim_handle_all_except_explicit =-3 295 | sim_handle_self =-4 296 | sim_handle_main_script =-5 297 | sim_handle_tree =-6 298 | sim_handle_chain =-7 299 | sim_handle_single =-8 300 | sim_handle_default =-9 301 | sim_handle_all_except_self =-10 302 | sim_handle_parent =-11 303 | 304 | 305 | # special handle flags 306 | sim_handleflag_assembly =0x400000 307 | sim_handleflag_model =0x800000 308 | 309 | 310 | # distance calculation methods (serialized) 311 | sim_distcalcmethod_dl =0 312 | sim_distcalcmethod_dac =1 313 | sim_distcalcmethod_max_dl_dac =2 314 | sim_distcalcmethod_dl_and_dac =3 315 | sim_distcalcmethod_sqrt_dl2_and_dac2=4 316 | sim_distcalcmethod_dl_if_nonzero =5 317 | sim_distcalcmethod_dac_if_nonzero =6 318 | 319 | 320 | # Generic dialog styles 321 | sim_dlgstyle_message =0 322 | sim_dlgstyle_input =1 323 | sim_dlgstyle_ok =2 324 | sim_dlgstyle_ok_cancel =3 325 | sim_dlgstyle_yes_no =4 326 | sim_dlgstyle_dont_center =32# can be combined with one of above values. Only with this flag can the position of the related UI be set just after dialog creation 327 | 328 | # Generic dialog return values 329 | sim_dlgret_still_open =0 330 | sim_dlgret_ok =1 331 | sim_dlgret_cancel =2 332 | sim_dlgret_yes =3 333 | sim_dlgret_no =4 334 | 335 | 336 | # Path properties 337 | sim_pathproperty_show_line =0x0001 338 | sim_pathproperty_show_orientation =0x0002 339 | sim_pathproperty_closed_path =0x0004 340 | sim_pathproperty_automatic_orientation =0x0008 341 | sim_pathproperty_invert_velocity =0x0010 342 | sim_pathproperty_infinite_acceleration =0x0020 343 | sim_pathproperty_flat_path =0x0040 344 | sim_pathproperty_show_position =0x0080 345 | sim_pathproperty_auto_velocity_profile_translation =0x0100 346 | sim_pathproperty_auto_velocity_profile_rotation =0x0200 347 | sim_pathproperty_endpoints_at_zero =0x0400 348 | sim_pathproperty_keep_x_up =0x0800 349 | 350 | 351 | # drawing objects 352 | # following are mutually exclusive 353 | sim_drawing_points =0 # 3 values per point (point size in pixels) 354 | sim_drawing_lines =1 # 6 values per line (line size in pixels) 355 | sim_drawing_triangles =2 # 9 values per triangle 356 | sim_drawing_trianglepoints =3 # 6 values per point (3 for triangle position 3 for triangle normal vector) (triangle size in meters) 357 | sim_drawing_quadpoints =4 # 6 values per point (3 for quad position 3 for quad normal vector) (quad size in meters) 358 | sim_drawing_discpoints =5 # 6 values per point (3 for disc position 3 for disc normal vector) (disc size in meters) 359 | sim_drawing_cubepoints =6 # 6 values per point (3 for cube position 3 for cube normal vector) (cube size in meters) 360 | sim_drawing_spherepoints =7 # 3 values per point (sphere size in meters) 361 | 362 | # following can be or-combined 363 | sim_drawing_itemcolors =0x00020 # +3 values per item (each item has its own ambient color (rgb values)). 364 | # Mutually exclusive with sim_drawing_vertexcolors 365 | sim_drawing_vertexcolors =0x00040 # +3 values per vertex (each vertex has its own ambient color (rgb values). Only for sim_drawing_lines (+6) and for sim_drawing_triangles(+9)). Mutually exclusive with sim_drawing_itemcolors 366 | sim_drawing_itemsizes =0x00080 # +1 value per item (each item has its own size). Not for sim_drawing_triangles 367 | sim_drawing_backfaceculling =0x00100 # back faces are not displayed for all items 368 | sim_drawing_wireframe =0x00200 # all items displayed in wireframe 369 | sim_drawing_painttag =0x00400 # all items are tagged as paint (for additinal processing at a later stage) 370 | sim_drawing_followparentvisibility =0x00800 # if the object is associated with a scene object then it follows that visibility otherwise it is always visible 371 | sim_drawing_cyclic =0x01000 # if the max item count was reached then the first items are overwritten. 372 | sim_drawing_50percenttransparency =0x02000 # the drawing object will be 50% transparent 373 | sim_drawing_25percenttransparency =0x04000 # the drawing object will be 25% transparent 374 | sim_drawing_12percenttransparency =0x08000 # the drawing object will be 12.5% transparent 375 | sim_drawing_emissioncolor =0x10000 # When used in combination with sim_drawing_itemcolors or sim_drawing_vertexcolors then the specified colors will be for the emissive component 376 | sim_drawing_facingcamera =0x20000 # Only for trianglepoints quadpoints discpoints and cubepoints. If specified the normal verctor is calculated to face the camera (each item data requires 3 values less) 377 | sim_drawing_overlay =0x40000 # When specified objects are always drawn on top of "regular objects" 378 | sim_drawing_itemtransparency =0x80000 # +1 value per item (each item has its own transparency value (0-1)). Not compatible with sim_drawing_vertexcolors 379 | 380 | # banner values 381 | # following can be or-combined 382 | sim_banner_left =0x00001 # Banners display on the left of the specified point 383 | sim_banner_right =0x00002 # Banners display on the right of the specified point 384 | sim_banner_nobackground =0x00004 # Banners have no background rectangle 385 | sim_banner_overlay =0x00008 # When specified banners are always drawn on top of "regular objects" 386 | sim_banner_followparentvisibility =0x00010 # if the object is associated with a scene object then it follows that visibility otherwise it is always visible 387 | sim_banner_clickselectsparent =0x00020 # if the object is associated with a scene object then clicking the banner will select the scene object 388 | sim_banner_clicktriggersevent =0x00040 # if the banner is clicked an event is triggered (sim_message_eventcallback_bannerclicked and sim_message_bannerclicked are generated) 389 | sim_banner_facingcamera =0x00080 # If specified the banner will always face the camera by rotating around the banner's vertical axis (y-axis) 390 | sim_banner_fullyfacingcamera =0x00100 # If specified the banner will always fully face the camera (the banner's orientation is same as the camera looking at it) 391 | sim_banner_backfaceculling =0x00200 # If specified the banner will only be visible from one side 392 | sim_banner_keepsamesize =0x00400 # If specified the banner will always appear in the same size. In that case size represents the character height in pixels 393 | sim_banner_bitmapfont =0x00800 # If specified a fixed-size bitmap font is used. The text will also always fully face the camera and be right 394 | # to the specified position. Bitmap fonts are not clickable 395 | 396 | 397 | # particle objects following are mutually exclusive 398 | sim_particle_points1 =0 # 6 values per point (pt1 and pt2. Pt1 is start position pt2-pt1 is the initial velocity vector). i 399 | #Point is 1 pixel big. Only appearance is a point internally handled as a perfect sphere 400 | sim_particle_points2 =1 # 6 values per point. Point is 2 pixel big. Only appearance is a point internally handled as a perfect sphere 401 | sim_particle_points4 =2 # 6 values per point. Point is 4 pixel big. Only appearance is a point internally handled as a perfect sphere 402 | sim_particle_roughspheres =3 # 6 values per sphere. Only appearance is rough. Internally a perfect sphere 403 | sim_particle_spheres =4 # 6 values per sphere. Internally a perfect sphere 404 | 405 | 406 | 407 | 408 | # following can be or-combined 409 | sim_particle_respondable1to4 =0x0020 # the particles are respondable against shapes (against all objects that have at least one bit 1-4 activated in the global respondable mask) 410 | sim_particle_respondable5to8 =0x0040 # the particles are respondable against shapes (against all objects that have at least one bit 5-8 activated in the global respondable mask) 411 | sim_particle_particlerespondable =0x0080 # the particles are respondable against each other 412 | sim_particle_ignoresgravity =0x0100 # the particles ignore the effect of gravity. Not compatible with sim_particle_water 413 | sim_particle_invisible =0x0200 # the particles are invisible 414 | sim_particle_itemsizes =0x0400 # +1 value per particle (each particle can have a different size) 415 | sim_particle_itemdensities =0x0800 # +1 value per particle (each particle can have a different density) 416 | sim_particle_itemcolors =0x1000 # +3 values per particle (each particle can have a different color) 417 | sim_particle_cyclic =0x2000 # if the max item count was reached then the first items are overwritten. 418 | sim_particle_emissioncolor =0x4000 # When used in combination with sim_particle_itemcolors then the specified colors will be for the emissive component 419 | sim_particle_water =0x8000 # the particles are water particles (no weight in the water (i.e. when z<0)). Not compatible with sim_particle_ignoresgravity 420 | sim_particle_painttag =0x10000 # The particles can be seen by vision sensors (sim_particle_invisible must not be set) 421 | 422 | 423 | 424 | 425 | # custom user interface menu attributes 426 | sim_ui_menu_title =1 427 | sim_ui_menu_minimize =2 428 | sim_ui_menu_close =4 429 | sim_ui_menu_systemblock =8 430 | 431 | 432 | 433 | # Boolean parameters 434 | sim_boolparam_hierarchy_visible =0 435 | sim_boolparam_console_visible =1 436 | sim_boolparam_collision_handling_enabled =2 437 | sim_boolparam_distance_handling_enabled =3 438 | sim_boolparam_ik_handling_enabled =4 439 | sim_boolparam_gcs_handling_enabled =5 440 | sim_boolparam_dynamics_handling_enabled =6 441 | sim_boolparam_joint_motion_handling_enabled =7 442 | sim_boolparam_path_motion_handling_enabled =8 443 | sim_boolparam_proximity_sensor_handling_enabled =9 444 | sim_boolparam_vision_sensor_handling_enabled =10 445 | sim_boolparam_mill_handling_enabled =11 446 | sim_boolparam_browser_visible =12 447 | sim_boolparam_scene_and_model_load_messages =13 448 | sim_reserved0 =14 449 | sim_boolparam_shape_textures_are_visible =15 450 | sim_boolparam_display_enabled =16 451 | sim_boolparam_infotext_visible =17 452 | sim_boolparam_statustext_open =18 453 | sim_boolparam_fog_enabled =19 454 | sim_boolparam_rml2_available =20 455 | sim_boolparam_rml4_available =21 456 | sim_boolparam_mirrors_enabled =22 457 | sim_boolparam_aux_clip_planes_enabled =23 458 | sim_boolparam_full_model_copy_from_api =24 459 | sim_boolparam_realtime_simulation =25 460 | sim_boolparam_force_show_wireless_emission =27 461 | sim_boolparam_force_show_wireless_reception =28 462 | sim_boolparam_video_recording_triggered =29 463 | sim_boolparam_threaded_rendering_enabled =32 464 | sim_boolparam_fullscreen =33 465 | sim_boolparam_headless =34 466 | sim_boolparam_hierarchy_toolbarbutton_enabled =35 467 | sim_boolparam_browser_toolbarbutton_enabled =36 468 | sim_boolparam_objectshift_toolbarbutton_enabled =37 469 | sim_boolparam_objectrotate_toolbarbutton_enabled=38 470 | sim_boolparam_force_calcstruct_all_visible =39 471 | sim_boolparam_force_calcstruct_all =40 472 | sim_boolparam_exit_request =41 473 | sim_boolparam_play_toolbarbutton_enabled =42 474 | sim_boolparam_pause_toolbarbutton_enabled =43 475 | sim_boolparam_stop_toolbarbutton_enabled =44 476 | sim_boolparam_waiting_for_trigger =45 477 | 478 | 479 | # Integer parameters 480 | sim_intparam_error_report_mode =0 # Check sim_api_errormessage_... constants above for valid values 481 | sim_intparam_program_version =1 # e.g Version 2.1.4 --> 20104. Can only be read 482 | sim_intparam_instance_count =2 # do not use anymore (always returns 1 since V-REP 2.5.11) 483 | sim_intparam_custom_cmd_start_id =3 # can only be read 484 | sim_intparam_compilation_version =4 # 0=evaluation version 1=full version 2=player version. Can only be read 485 | sim_intparam_current_page =5 486 | sim_intparam_flymode_camera_handle =6 # can only be read 487 | sim_intparam_dynamic_step_divider =7 # can only be read 488 | sim_intparam_dynamic_engine =8 # 0=Bullet 1=ODE. 2=Vortex. 489 | sim_intparam_server_port_start =9 # can only be read 490 | sim_intparam_server_port_range =10 # can only be read 491 | sim_intparam_visible_layers =11 492 | sim_intparam_infotext_style =12 493 | sim_intparam_settings =13 494 | sim_intparam_edit_mode_type =14 # can only be read 495 | sim_intparam_server_port_next =15 # is initialized at sim_intparam_server_port_start 496 | sim_intparam_qt_version =16 # version of the used Qt framework 497 | sim_intparam_event_flags_read =17 # can only be read 498 | sim_intparam_event_flags_read_clear =18 # can only be read 499 | sim_intparam_platform =19 # can only be read 500 | sim_intparam_scene_unique_id =20 # can only be read 501 | sim_intparam_work_thread_count =21 502 | sim_intparam_mouse_x =22 503 | sim_intparam_mouse_y =23 504 | sim_intparam_core_count =24 505 | sim_intparam_work_thread_calc_time_ms =25 506 | sim_intparam_idle_fps =26 507 | sim_intparam_prox_sensor_select_down =27 508 | sim_intparam_prox_sensor_select_up =28 509 | sim_intparam_stop_request_counter =29 510 | sim_intparam_program_revision =30 511 | sim_intparam_mouse_buttons =31 512 | sim_intparam_dynamic_warning_disabled_mask =32 513 | sim_intparam_simulation_warning_disabled_mask =33 514 | sim_intparam_scene_index =34 515 | sim_intparam_motionplanning_seed =35 516 | sim_intparam_speedmodifier =36 517 | 518 | # Float parameters 519 | sim_floatparam_rand=0 # random value (0.0-1.0) 520 | sim_floatparam_simulation_time_step =1 521 | sim_floatparam_stereo_distance =2 522 | 523 | # String parameters 524 | sim_stringparam_application_path=0 # path of V-REP's executable 525 | sim_stringparam_video_filename=1 526 | sim_stringparam_app_arg1 =2 527 | sim_stringparam_app_arg2 =3 528 | sim_stringparam_app_arg3 =4 529 | sim_stringparam_app_arg4 =5 530 | sim_stringparam_app_arg5 =6 531 | sim_stringparam_app_arg6 =7 532 | sim_stringparam_app_arg7 =8 533 | sim_stringparam_app_arg8 =9 534 | sim_stringparam_app_arg9 =10 535 | sim_stringparam_scene_path_and_name =13 536 | 537 | # Array parameters 538 | sim_arrayparam_gravity =0 539 | sim_arrayparam_fog =1 540 | sim_arrayparam_fog_color =2 541 | sim_arrayparam_background_color1=3 542 | sim_arrayparam_background_color2=4 543 | sim_arrayparam_ambient_light =5 544 | sim_arrayparam_random_euler =6 545 | 546 | sim_objintparam_visibility_layer= 10 547 | sim_objfloatparam_abs_x_velocity= 11 548 | sim_objfloatparam_abs_y_velocity= 12 549 | sim_objfloatparam_abs_z_velocity= 13 550 | sim_objfloatparam_abs_rot_velocity= 14 551 | sim_objfloatparam_objbbox_min_x= 15 552 | sim_objfloatparam_objbbox_min_y= 16 553 | sim_objfloatparam_objbbox_min_z= 17 554 | sim_objfloatparam_objbbox_max_x= 18 555 | sim_objfloatparam_objbbox_max_y= 19 556 | sim_objfloatparam_objbbox_max_z= 20 557 | sim_objfloatparam_modelbbox_min_x= 21 558 | sim_objfloatparam_modelbbox_min_y= 22 559 | sim_objfloatparam_modelbbox_min_z= 23 560 | sim_objfloatparam_modelbbox_max_x= 24 561 | sim_objfloatparam_modelbbox_max_y= 25 562 | sim_objfloatparam_modelbbox_max_z= 26 563 | sim_objintparam_collection_self_collision_indicator= 27 564 | sim_objfloatparam_transparency_offset= 28 565 | sim_objintparam_child_role= 29 566 | sim_objintparam_parent_role= 30 567 | sim_objintparam_manipulation_permissions= 31 568 | sim_objintparam_illumination_handle= 32 569 | 570 | sim_visionfloatparam_near_clipping= 1000 571 | sim_visionfloatparam_far_clipping= 1001 572 | sim_visionintparam_resolution_x= 1002 573 | sim_visionintparam_resolution_y= 1003 574 | sim_visionfloatparam_perspective_angle= 1004 575 | sim_visionfloatparam_ortho_size= 1005 576 | sim_visionintparam_disabled_light_components= 1006 577 | sim_visionintparam_rendering_attributes= 1007 578 | sim_visionintparam_entity_to_render= 1008 579 | sim_visionintparam_windowed_size_x= 1009 580 | sim_visionintparam_windowed_size_y= 1010 581 | sim_visionintparam_windowed_pos_x= 1011 582 | sim_visionintparam_windowed_pos_y= 1012 583 | sim_visionintparam_pov_focal_blur= 1013 584 | sim_visionfloatparam_pov_blur_distance= 1014 585 | sim_visionfloatparam_pov_aperture= 1015 586 | sim_visionintparam_pov_blur_sampled= 1016 587 | sim_visionintparam_render_mode= 1017 588 | 589 | sim_jointintparam_motor_enabled= 2000 590 | sim_jointintparam_ctrl_enabled= 2001 591 | sim_jointfloatparam_pid_p= 2002 592 | sim_jointfloatparam_pid_i= 2003 593 | sim_jointfloatparam_pid_d= 2004 594 | sim_jointfloatparam_intrinsic_x= 2005 595 | sim_jointfloatparam_intrinsic_y= 2006 596 | sim_jointfloatparam_intrinsic_z= 2007 597 | sim_jointfloatparam_intrinsic_qx= 2008 598 | sim_jointfloatparam_intrinsic_qy= 2009 599 | sim_jointfloatparam_intrinsic_qz= 2010 600 | sim_jointfloatparam_intrinsic_qw= 2011 601 | sim_jointfloatparam_velocity= 2012 602 | sim_jointfloatparam_spherical_qx= 2013 603 | sim_jointfloatparam_spherical_qy= 2014 604 | sim_jointfloatparam_spherical_qz= 2015 605 | sim_jointfloatparam_spherical_qw= 2016 606 | sim_jointfloatparam_upper_limit= 2017 607 | sim_jointfloatparam_kc_k= 2018 608 | sim_jointfloatparam_kc_c= 2019 609 | sim_jointfloatparam_ik_weight= 2021 610 | sim_jointfloatparam_error_x= 2022 611 | sim_jointfloatparam_error_y= 2023 612 | sim_jointfloatparam_error_z= 2024 613 | sim_jointfloatparam_error_a= 2025 614 | sim_jointfloatparam_error_b= 2026 615 | sim_jointfloatparam_error_g= 2027 616 | sim_jointfloatparam_error_pos= 2028 617 | sim_jointfloatparam_error_angle= 2029 618 | sim_jointintparam_velocity_lock= 2030 619 | sim_jointintparam_vortex_dep_handle= 2031 620 | sim_jointfloatparam_vortex_dep_multiplication= 2032 621 | sim_jointfloatparam_vortex_dep_offset= 2033 622 | 623 | sim_shapefloatparam_init_velocity_x= 3000 624 | sim_shapefloatparam_init_velocity_y= 3001 625 | sim_shapefloatparam_init_velocity_z= 3002 626 | sim_shapeintparam_static= 3003 627 | sim_shapeintparam_respondable= 3004 628 | sim_shapefloatparam_mass= 3005 629 | sim_shapefloatparam_texture_x= 3006 630 | sim_shapefloatparam_texture_y= 3007 631 | sim_shapefloatparam_texture_z= 3008 632 | sim_shapefloatparam_texture_a= 3009 633 | sim_shapefloatparam_texture_b= 3010 634 | sim_shapefloatparam_texture_g= 3011 635 | sim_shapefloatparam_texture_scaling_x= 3012 636 | sim_shapefloatparam_texture_scaling_y= 3013 637 | sim_shapeintparam_culling= 3014 638 | sim_shapeintparam_wireframe= 3015 639 | sim_shapeintparam_compound= 3016 640 | sim_shapeintparam_convex= 3017 641 | sim_shapeintparam_convex_check= 3018 642 | sim_shapeintparam_respondable_mask= 3019 643 | sim_shapefloatparam_init_velocity_a= 3020 644 | sim_shapefloatparam_init_velocity_b= 3021 645 | sim_shapefloatparam_init_velocity_g= 3022 646 | sim_shapestringparam_color_name= 3023 647 | sim_shapeintparam_edge_visibility= 3024 648 | sim_shapefloatparam_shading_angle= 3025 649 | sim_shapefloatparam_edge_angle= 3026 650 | sim_shapeintparam_edge_borders_hidden= 3027 651 | 652 | sim_proxintparam_ray_invisibility= 4000 653 | 654 | sim_forcefloatparam_error_x= 5000 655 | sim_forcefloatparam_error_y= 5001 656 | sim_forcefloatparam_error_z= 5002 657 | sim_forcefloatparam_error_a= 5003 658 | sim_forcefloatparam_error_b= 5004 659 | sim_forcefloatparam_error_g= 5005 660 | sim_forcefloatparam_error_pos= 5006 661 | sim_forcefloatparam_error_angle= 5007 662 | 663 | sim_lightintparam_pov_casts_shadows= 8000 664 | 665 | sim_cameraintparam_disabled_light_components= 9000 666 | sim_camerafloatparam_perspective_angle= 9001 667 | sim_camerafloatparam_ortho_size= 9002 668 | sim_cameraintparam_rendering_attributes= 9003 669 | sim_cameraintparam_pov_focal_blur= 9004 670 | sim_camerafloatparam_pov_blur_distance= 9005 671 | sim_camerafloatparam_pov_aperture= 9006 672 | sim_cameraintparam_pov_blur_samples= 9007 673 | 674 | sim_dummyintparam_link_type= 10000 675 | 676 | sim_mirrorfloatparam_width= 12000 677 | sim_mirrorfloatparam_height= 12001 678 | sim_mirrorfloatparam_reflectance= 12002 679 | sim_mirrorintparam_enable= 12003 680 | 681 | sim_pplanfloatparam_x_min= 20000 682 | sim_pplanfloatparam_x_range= 20001 683 | sim_pplanfloatparam_y_min= 20002 684 | sim_pplanfloatparam_y_range= 20003 685 | sim_pplanfloatparam_z_min= 20004 686 | sim_pplanfloatparam_z_range= 20005 687 | sim_pplanfloatparam_delta_min= 20006 688 | sim_pplanfloatparam_delta_range= 20007 689 | 690 | sim_mplanintparam_nodes_computed= 25000 691 | sim_mplanintparam_prepare_nodes= 25001 692 | sim_mplanintparam_clear_nodes= 25002 693 | 694 | # User interface elements 695 | sim_gui_menubar =0x0001 696 | sim_gui_popups =0x0002 697 | sim_gui_toolbar1 =0x0004 698 | sim_gui_toolbar2 =0x0008 699 | sim_gui_hierarchy =0x0010 700 | sim_gui_infobar =0x0020 701 | sim_gui_statusbar =0x0040 702 | sim_gui_scripteditor =0x0080 703 | sim_gui_scriptsimulationparameters =0x0100 704 | sim_gui_dialogs =0x0200 705 | sim_gui_browser =0x0400 706 | sim_gui_all =0xffff 707 | 708 | 709 | # Joint modes 710 | sim_jointmode_passive =0 711 | sim_jointmode_motion =1 712 | sim_jointmode_ik =2 713 | sim_jointmode_ikdependent =3 714 | sim_jointmode_dependent =4 715 | sim_jointmode_force =5 716 | 717 | 718 | # Navigation and selection modes with the mouse. Lower byte values are mutually exclusive upper byte bits can be combined 719 | sim_navigation_passive =0x0000 720 | sim_navigation_camerashift =0x0001 721 | sim_navigation_camerarotate =0x0002 722 | sim_navigation_camerazoom =0x0003 723 | sim_navigation_cameratilt =0x0004 724 | sim_navigation_cameraangle =0x0005 725 | sim_navigation_camerafly =0x0006 726 | sim_navigation_objectshift =0x0007 727 | sim_navigation_objectrotate =0x0008 728 | sim_navigation_reserved2 =0x0009 729 | sim_navigation_reserved3 =0x000A 730 | sim_navigation_jointpathtest =0x000B 731 | sim_navigation_ikmanip =0x000C 732 | sim_navigation_objectmultipleselection =0x000D 733 | # Bit-combine following values and add them to one of above's values for a valid navigation mode 734 | sim_navigation_reserved4 =0x0100 735 | sim_navigation_clickselection =0x0200 736 | sim_navigation_ctrlselection =0x0400 737 | sim_navigation_shiftselection =0x0800 738 | sim_navigation_camerazoomwheel =0x1000 739 | sim_navigation_camerarotaterightbutton =0x2000 740 | 741 | 742 | 743 | #Remote API constants 744 | SIMX_VERSION =0 745 | # Remote API message header structure 746 | SIMX_HEADER_SIZE =18 747 | simx_headeroffset_crc =0 # 1 simxUShort. Generated by the client or server. The CRC for the message 748 | simx_headeroffset_version =2 # 1 byte. Generated by the client or server. The version of the remote API software 749 | simx_headeroffset_message_id =3 # 1 simxInt. Generated by the client (and used in a reply by the server) 750 | simx_headeroffset_client_time =7 # 1 simxInt. Client time stamp generated by the client (and sent back by the server) 751 | simx_headeroffset_server_time =11 # 1 simxInt. Generated by the server when a reply is generated. The server timestamp 752 | simx_headeroffset_scene_id =15 # 1 simxUShort. Generated by the server. A unique ID identifying the scene currently displayed 753 | simx_headeroffset_server_state =17 # 1 byte. Generated by the server. Bit coded 0 set --> simulation not stopped 1 set --> simulation paused 2 set --> real-time switch on 3-5 edit mode type (0=no edit mode 1=triangle 2=vertex 3=edge 4=path 5=UI) 754 | 755 | # Remote API command header 756 | SIMX_SUBHEADER_SIZE =26 757 | simx_cmdheaderoffset_mem_size =0 # 1 simxInt. Generated by the client or server. The buffer size of the command. 758 | simx_cmdheaderoffset_full_mem_size =4 # 1 simxInt. Generated by the client or server. The full buffer size of the command (applies to split chunks). 759 | simx_cmdheaderoffset_pdata_offset0 =8 # 1 simxUShort. Generated by the client or server. The amount of data that is part of the command identification. 760 | simx_cmdheaderoffset_pdata_offset1 =10 # 1 simxInt. Generated by the client or server. The amount of shift of the pure data buffer (applies to split chunks). 761 | simx_cmdheaderoffset_cmd=14 # 1 simxInt. Generated by the client (and used in a reply by the server). The command combined with the operation mode of the command. 762 | simx_cmdheaderoffset_delay_or_split =18 # 1 simxUShort. Generated by the client or server. The amount of delay in ms of a continuous command or the max. pure data size to send at once (applies to split commands). 763 | simx_cmdheaderoffset_sim_time =20 # 1 simxInt. Generated by the server. The simulation time (in ms) when the command was executed (or 0 if simulation is not running) 764 | simx_cmdheaderoffset_status =24 # 1 byte. Generated by the server. (1 bit 0 is set --> error in function execution on server side). The client writes bit 1 if command cannot be overwritten 765 | simx_cmdheaderoffset_reserved =25 # 1 byte. Not yet used 766 | 767 | 768 | 769 | 770 | 771 | # Regular operation modes 772 | simx_opmode_oneshot =0x000000 # sends command as one chunk. Reply will also come as one chunk. Doesn't wait for the reply. 773 | simx_opmode_blocking =0x010000 # sends command as one chunk. Reply will also come as one chunk. Waits for the reply (_REPLY_WAIT_TIMEOUT_IN_MS is the timeout). 774 | simx_opmode_oneshot_wait =0x010000 # sends command as one chunk. Reply will also come as one chunk. Waits for the reply (_REPLY_WAIT_TIMEOUT_IN_MS is the timeout). 775 | simx_opmode_continuous =0x020000 776 | simx_opmode_streaming =0x020000 # sends command as one chunk. Command will be stored on the server and always executed 777 | #(every x ms (as far as possible) where x can be 0-65535. just add x to opmode_continuous). 778 | # A reply will be sent continuously each time as one chunk. Doesn't wait for the reply. 779 | 780 | # Operation modes for heavy data 781 | simx_opmode_oneshot_split =0x030000 # sends command as several chunks (max chunk size is x bytes where x can be _MIN_SPLIT_AMOUNT_IN_BYTES-65535. Just add x to opmode_oneshot_split). Reply will also come as several chunks. Doesn't wait for the reply. 782 | simx_opmode_continuous_split =0x040000 783 | simx_opmode_streaming_split =0x040000 # sends command as several chunks (max chunk size is x bytes where x can be _MIN_SPLIT_AMOUNT_IN_BYTES-65535. Just add x to opmode_continuous_split). Command will be stored on the server and always executed. A reply will be sent continuously each time as several chunks. Doesn't wait for the reply. 784 | 785 | # Special operation modes 786 | simx_opmode_discontinue =0x050000 # removes and cancels all commands stored on the client or server side (also continuous commands) 787 | simx_opmode_buffer =0x060000 # doesn't send anything but checks if a reply for the given command is available in the input buffer (i.e. previously received from the server) 788 | simx_opmode_remove =0x070000 # doesn't send anything and doesn't return any specific value. It just erases a similar command reply in the inbox (to free some memory) 789 | 790 | 791 | # Command return codes 792 | simx_return_ok =0x000000 793 | simx_return_novalue_flag =0x000001 # input buffer doesn't contain the specified command 794 | simx_return_timeout_flag =0x000002 # command reply not received in time for opmode_oneshot_wait operation mode 795 | simx_return_illegal_opmode_flag =0x000004 # command doesn't support the specified operation mode 796 | simx_return_remote_error_flag =0x000008 # command caused an error on the server side 797 | simx_return_split_progress_flag =0x000010 # previous similar command not yet fully processed (applies to opmode_oneshot_split operation modes) 798 | simx_return_local_error_flag =0x000020 # command caused an error on the client side 799 | simx_return_initialize_error_flag =0x000040 # simxStart was not yet called 800 | 801 | # Following for backward compatibility (same as above) 802 | simx_error_noerror =0x000000 803 | simx_error_novalue_flag =0x000001 # input buffer doesn't contain the specified command 804 | simx_error_timeout_flag =0x000002 # command reply not received in time for opmode_oneshot_wait operation mode 805 | simx_error_illegal_opmode_flag =0x000004 # command doesn't support the specified operation mode 806 | simx_error_remote_error_flag =0x000008 # command caused an error on the server side 807 | simx_error_split_progress_flag =0x000010 # previous similar command not yet fully processed (applies to opmode_oneshot_split operation modes) 808 | simx_error_local_error_flag =0x000020 # command caused an error on the client side 809 | simx_error_initialize_error_flag =0x000040 # simxStart was not yet called 810 | 811 | 812 | --------------------------------------------------------------------------------