def run(self): sim = BasicSimulator() sim.init(mode='gui') floor = sim.create_box(extents=[10, 10, 0.1], mass=0) scale = sim.load_urdf('package://iai_bullet_sim/urdf/scale.urdf', pos=[0, 0, 0.1], useFixedBase=1) for x in range(5): sim.create_box(extents=[0.2, 0.2, 0.2], pos=[0, 0, 2 + x * 0.5], mass=20) scale.apply_joint_pos_cmds({'plate_lift': 0.2}) scale.enable_joint_sensor('plate_lift') last_update = time() while True: if time() - last_update >= sim.time_step: sim.update() print('Joint state:\n {}'.format('\n '.join([ '{:>12}: {}'.format(j, str(s.f)) for j, s in scale.get_sensor_states().items() ]))) last_update = time()
def __init__(self): temp = open('temp.urdf', 'w') temp.write(rospy.get_param('robot_description')) temp.close() self.sim = BasicSimulator() self.sim.init() self.sim.set_tick_rate(rospy.get_param('~sim_frequency', 50)) self.watchdog_period = rospy.get_param('~watchdog_period', 0.1) self.projection_mode = rospy.get_param('~projection_mode', False) self.robot = self.sim.load_urdf('temp.urdf', useFixedBase=True) self.robot.set_joint_positions(rospy.get_param('~start_config', {})) self.sim.register_plugin(JSPublisher(self.robot)) self.sim.register_plugin(SensorPublisher(self.robot)) self.sim.register_plugin(JointVelocityController(self.robot, watchdog_timeout=self.watchdog_period)) self.srv_server_set_js = rospy.Service('~set_joint_states', SetJointStateSrv, self.srv_set_js) if self.projection_mode: try: use_sim_time = rospy.get_param('/use_sim_time') if not use_sim_time: raise KeyError self.clock_pub = rospy.Publisher('/clock', ClockMsg, queue_size=1, tcp_nodelay=True) self.time = rospy.Time.now() self.time_step = rospy.Duration(1.0 / self.tick_rate) self.proj_sub = rospy.Subscriber('~/projection_command', ProjectionClockMsg, callback=self.proj_callback, queue_size=1) except KeyError: raise Exception('Parameter /use_sim_time must be set to "True" use projection mode!') else: self.timer = rospy.Timer(rospy.Duration(1.0 / self.sim.tick_rate), self.tick)
def run(self): sim = BasicSimulator() sim.init(mode='gui') floor = sim.create_box(extents=[10, 10, 0.1], mass=0) windmill = sim.load_urdf('package://iai_bullet_sim/urdf/windmill.urdf', useFixedBase=1) plugin = SimplePlugin(windmill) sim.register_plugin(plugin) windmill.apply_joint_vel_cmds({'wings_rotor': -2}) last_update = time() while True: if time() - last_update >= sim.time_step: windmill.apply_joint_pos_cmds({'head_pan': sin(time())}) sim.update() last_update = time()
def run(self): sim = BasicSimulator() sim.init(mode='gui') floor = sim.create_box(extents=[10, 10, 0.1], mass=0) suzanne = sim.load_mesh('package://iai_bullet_sim/meshes/suzanne.dae', pos=[0, 0, 2]) last_update = time() while True: if time() - last_update >= sim.time_step: sim.update() last_update = time()
def run(self): sim = BasicSimulator() sim.init(mode='gui') floor = sim.create_box(extents=[10, 10, 0.1], mass=0) capsule = sim.create_capsule(radius=0.25, height=1, pos=[0, 0, 2], rot=[0, 1, 0, 0], mass=10) last_update = time() while True: if time() - last_update >= sim.time_step: sim.update() print(str(capsule.pose().position)) last_update = time()
def run(self): sim = BasicSimulator() sim.init(mode='gui') floor = sim.create_box(extents=[10, 10, 0.1], mass=0) windmill = sim.load_urdf('package://iai_bullet_sim/urdf/windmill.urdf', useFixedBase=1) windmill.apply_joint_vel_cmds({'wings_rotor': -2}) last_update = time() while True: if time() - last_update >= sim.time_step: windmill.apply_joint_pos_cmds({'head_pan': sin(time())}) sim.update() print('Joint state:\n {}'.format('\n '.join([ '{:>12}: {}'.format(j, s.position) for j, s in windmill.joint_state().items() ]))) last_update = time()
def run(self): sim = BasicSimulator() sim.init(mode='gui') floor = sim.create_box(extents=[10, 10, 0.1], mass=0) scale = sim.load_urdf('package://iai_bullet_sim/urdf/scale.urdf', pos=[0, 0, 0.1], useFixedBase=1) for x in range(5): sim.create_box(extents=[0.2, 0.2, 0.2], pos=[0, 0, 2 + x * 0.5], mass=20) scale.apply_joint_pos_cmds({'plate_lift': 0.2}) scale.enable_joint_sensor('plate_lift') last_update = time() while True: if time() - last_update >= sim.time_step: sim.update() contacts = scale.get_contacts(own_link='plate') print('Contacts with plate:\n {}'.format('\n '.join( [sim.get_body_id(c.bodyB.bId()) for c in contacts]))) last_update = time()
class Node(object): def __init__(self): temp = open('temp.urdf', 'w') temp.write(rospy.get_param('robot_description')) temp.close() self.sim = BasicSimulator() self.sim.init() self.sim.set_tick_rate(rospy.get_param('~sim_frequency', 50)) self.watchdog_period = rospy.get_param('~watchdog_period', 0.1) self.projection_mode = rospy.get_param('~projection_mode', False) self.robot = self.sim.load_urdf('temp.urdf', useFixedBase=True) self.robot.set_joint_positions(rospy.get_param('~start_config', {})) self.sim.register_plugin(JSPublisher(self.robot)) self.sim.register_plugin(SensorPublisher(self.robot)) self.sim.register_plugin(JointVelocityController(self.robot, watchdog_timeout=self.watchdog_period)) self.srv_server_set_js = rospy.Service('~set_joint_states', SetJointStateSrv, self.srv_set_js) if self.projection_mode: try: use_sim_time = rospy.get_param('/use_sim_time') if not use_sim_time: raise KeyError self.clock_pub = rospy.Publisher('/clock', ClockMsg, queue_size=1, tcp_nodelay=True) self.time = rospy.Time.now() self.time_step = rospy.Duration(1.0 / self.tick_rate) self.proj_sub = rospy.Subscriber('~/projection_command', ProjectionClockMsg, callback=self.proj_callback, queue_size=1) except KeyError: raise Exception('Parameter /use_sim_time must be set to "True" use projection mode!') else: self.timer = rospy.Timer(rospy.Duration(1.0 / self.sim.tick_rate), self.tick) def tick(self, timer_event): self.sim.update() def tick_and_tock(self): self.sim.pre_update() self.sim.physics_update() self.time += self.time_step cmsg = ClockMsg() cmsg.clock = self.time self.clock_pub.publish(cmsg) self.sim.post_update() def srv_set_js(self, request): js_msg = request.state js = {js_msg.name[x]: js_msg.position[x] for x in range(len(js_msg.name))} for j in js.keys(): if j not in self.robot.joints: return SetJointStateSrv.Response(False, 'Can not set position for joint {}, because it is not part of the controlled robot.'.format(j)) self.robot.set_joint_positions(js, True) self.sim.reset() return SetJointStateSrv.Response(True, '') def proj_callback(self, msg): self.time = copy(msg.time) while True: self.tick_and_tock() if rospy.Time.now() - msg.time >= msg.period: break
#!/usr/bin/env python import sys from time import time from math import sin from iai_bullet_sim.basic_simulator import BasicSimulator if __name__ == '__main__': if len(sys.argv) < 2: print('Name of urdf to load required. ROS package URIs are supported.') else: sim = BasicSimulator() sim.init(mode='gui') floor = sim.create_box(extents=[10,10,0.1], mass=0) thing = sim.load_urdf(sys.argv[1], useFixedBase=1) box = sim.create_box(extents=[1,1,1], mass=20, pos=[0,0,10]) last_update = time() while True: if time() - last_update >= sim.time_step: sim.update() last_update = time()