From aeb46664b9bf46ca44edbb52c767a787b595bec6 Mon Sep 17 00:00:00 2001 From: Maxime Busy Date: Tue, 9 Jun 2020 18:02:19 +0200 Subject: [PATCH 01/12] Remove unused variables and extra spaces --- qibullet/ros_wrapper.py | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/qibullet/ros_wrapper.py b/qibullet/ros_wrapper.py index 7220952..d4a846e 100644 --- a/qibullet/ros_wrapper.py +++ b/qibullet/ros_wrapper.py @@ -45,10 +45,6 @@ except ImportError as e: MISSING_IMPORT = str(e) -TOP_OPTICAL_FRAME = "CameraTop_optical_frame" -BOTTOM_OPTICAL_FRAME = "CameraBottom_optical_frame" -DEPTH_OPTICAL_FRAME = "CameraDepth_optical_frame" - class RosWrapper: """ @@ -65,9 +61,6 @@ def __init__(self): self.spin_thread = None self._wrapper_termination = False self.image_bridge = CvBridge() - self.front_info_msg = dict() - self.bottom_info_msg = dict() - self.depth_info_msg = dict() self.roslauncher = None self.transform_broadcaster = tf2_ros.TransformBroadcaster() atexit.register(self.stopWrapper) @@ -251,7 +244,7 @@ def _broadcastCamera(self, camera, image_publisher, info_publisher): image_msg = self.image_bridge.cv2_to_imgmsg(frame) image_msg.header.frame_id = camera.getCameraLink().getName() - # Check if the retrieved image is RGB or a depth image + # Check if the retrieved image is RGB or a depth image if isinstance(camera, CameraDepth): image_msg.encoding = "16UC1" else: From b6b1254d373fa4194efb26481ff265ebe7621daf Mon Sep 17 00:00:00 2001 From: Maxime Busy Date: Thu, 11 Jun 2020 11:20:18 +0200 Subject: [PATCH 02/12] Handling multiple active cameras in the _broadcastCamera methods of the RosWrapper child classes --- qibullet/ros_wrapper.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/qibullet/ros_wrapper.py b/qibullet/ros_wrapper.py index d4a846e..ebcbc10 100644 --- a/qibullet/ros_wrapper.py +++ b/qibullet/ros_wrapper.py @@ -402,7 +402,7 @@ def _broadcastCamera(self): self.front_cam_pub, self.front_info_pub) - elif self.robot.camera_dict[NaoVirtual.ID_CAMERA_BOTTOM].isActive(): + if self.robot.camera_dict[NaoVirtual.ID_CAMERA_BOTTOM].isActive(): RosWrapper._broadcastCamera( self, self.robot.camera_dict[NaoVirtual.ID_CAMERA_BOTTOM], @@ -530,14 +530,14 @@ def _broadcastCamera(self): self.right_cam_pub, self.right_info_pub) - elif self.robot.camera_dict[RomeoVirtual.ID_CAMERA_LEFT].isActive(): + if self.robot.camera_dict[RomeoVirtual.ID_CAMERA_LEFT].isActive(): RosWrapper._broadcastCamera( self, self.robot.camera_dict[RomeoVirtual.ID_CAMERA_LEFT], self.left_cam_pub, self.left_info_pub) - elif self.robot.camera_dict[RomeoVirtual.ID_CAMERA_DEPTH].isActive(): + if self.robot.camera_dict[RomeoVirtual.ID_CAMERA_DEPTH].isActive(): RosWrapper._broadcastCamera( self, self.robot.camera_dict[RomeoVirtual.ID_CAMERA_DEPTH], @@ -728,14 +728,14 @@ def _broadcastCamera(self): self.front_cam_pub, self.front_info_pub) - elif self.robot.camera_dict[PepperVirtual.ID_CAMERA_BOTTOM].isActive(): + if self.robot.camera_dict[PepperVirtual.ID_CAMERA_BOTTOM].isActive(): RosWrapper._broadcastCamera( self, self.robot.camera_dict[PepperVirtual.ID_CAMERA_BOTTOM], self.bottom_cam_pub, self.bottom_info_pub) - elif self.robot.camera_dict[PepperVirtual.ID_CAMERA_DEPTH].isActive(): + if self.robot.camera_dict[PepperVirtual.ID_CAMERA_DEPTH].isActive(): RosWrapper._broadcastCamera( self, self.robot.camera_dict[PepperVirtual.ID_CAMERA_DEPTH], From 191ff8c1464db193ed1262c4ef10a0d5befac7a3 Mon Sep 17 00:00:00 2001 From: Maxime Busy Date: Mon, 22 Jun 2020 11:59:38 +0200 Subject: [PATCH 03/12] Spawn the duck in front of the robot, update max detection distance and add timesleep, solving #39 --- examples/pepper_lasers.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/examples/pepper_lasers.py b/examples/pepper_lasers.py index 66cd8f5..ab1b2b7 100644 --- a/examples/pepper_lasers.py +++ b/examples/pepper_lasers.py @@ -1,6 +1,7 @@ #!/usr/bin/env python # coding: utf-8 +import time import pybullet import pybullet_data from qibullet import PepperVirtual @@ -16,7 +17,7 @@ def main(): pybullet.loadURDF( "duck_vhacd.urdf", - basePosition=[1, -1, 0.5], + basePosition=[1, 0, 0.5], globalScaling=10.0, physicsClientId=client) @@ -29,12 +30,14 @@ def main(): laser_list.extend(pepper.getFrontLaserValue()) laser_list.extend(pepper.getLeftLaserValue()) - if all(laser == 5.6 for laser in laser_list): + if all(laser == 3.0 for laser in laser_list): print("Nothing detected") else: print("Detected") pass + time.sleep(0.1) + if __name__ == "__main__": main() From 7732c2094856a7534e3e7866b82805db41788c31 Mon Sep 17 00:00:00 2001 From: mbusy Date: Wed, 12 Aug 2020 13:56:35 +0200 Subject: [PATCH 04/12] Fix the spawning methods docstrings, as mentioned in #43 --- qibullet/simulation_manager.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/qibullet/simulation_manager.py b/qibullet/simulation_manager.py index 6ab6441..cc944af 100644 --- a/qibullet/simulation_manager.py +++ b/qibullet/simulation_manager.py @@ -133,7 +133,7 @@ def spawnPepper( robot is supposed to be spawned translation - List containing 3 elements, the spawning translation [x, y, z] in the WORLD frame - quaternions - List containing 4 elements, the spawning rotation as + quaternion - List containing 4 elements, the spawning rotation as a quaternion [x, y, z, w] in the WORLD frame spawn_ground_plane - If True, the pybullet_data ground plane will be spawned @@ -168,7 +168,7 @@ def spawnNao( robot is supposed to be spawned translation - List containing 3 elements, the spawning translation [x, y, z] in the WORLD frame - quaternions - List containing 4 elements, the spawning rotation as + quaternion - List containing 4 elements, the spawning rotation as a quaternion [x, y, z, w] in the WORLD frame spawn_ground_plane - If True, the pybullet_data ground plane will be spawned @@ -202,7 +202,7 @@ def spawnRomeo( robot is supposed to be spawned translation - List containing 3 elements, the spawning translation [x, y, z] in the WORLD frame - quaternions - List containing 4 elements, the spawning rotation as + quaternion - List containing 4 elements, the spawning rotation as a quaternion [x, y, z, w] in the WORLD frame spawn_ground_plane - If True, the pybullet_data ground plane will be spawned From e684b31ac4d700ce2d3628be9a6081dcc124ad6e Mon Sep 17 00:00:00 2001 From: Maxime Busy Date: Mon, 21 Sep 2020 17:04:59 +0200 Subject: [PATCH 05/12] Add the stopMove method --- qibullet/base_controller.py | 8 ++++++++ qibullet/pepper_virtual.py | 8 ++++++++ 2 files changed, 16 insertions(+) diff --git a/qibullet/base_controller.py b/qibullet/base_controller.py index dfad915..aa24407 100644 --- a/qibullet/base_controller.py +++ b/qibullet/base_controller.py @@ -311,6 +311,14 @@ def move(self, x, y, theta): [0, 0, theta], physicsClientId=self.physics_client) + def stopMove(self): + """ + If an aynchronous moveTo has been launched, calling this method will + stop the asynchronous process. Calling this method is equivalent to + calling moveTo(0.0, 0.0, 0.0, _async=True) + """ + self.moveTo(0.0, 0.0, 0.0, _async=True) + def _updateConstraint(self): """ INTERNAL METHOD, update the robot's constraint. diff --git a/qibullet/pepper_virtual.py b/qibullet/pepper_virtual.py index b48e185..bd7f5cd 100644 --- a/qibullet/pepper_virtual.py +++ b/qibullet/pepper_virtual.py @@ -217,6 +217,14 @@ def move(self, x, y, theta): """ self.base_controller.move(x, y, theta) + def stopMove(self): + """ + If an aynchronous moveTo has been launched, calling this method will + stop the asynchronous process. Calling this method is equivalent to + calling moveTo(0.0, 0.0, 0.0, _async=True) + """ + self.base_controller.stopMove() + def setAngles(self, joint_names, joint_values, percentage_speed): """ Overloads @setAngles from the @RobotVirtual class. Handles the finger From e5f8367fb5d26f5421a688a55049547105ebf6ef Mon Sep 17 00:00:00 2001 From: Maxime Busy Date: Mon, 21 Sep 2020 17:05:19 +0200 Subject: [PATCH 06/12] Update the base_test unit test accordingly --- tests/base_test.py | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/tests/base_test.py b/tests/base_test.py index 8240fd6..04bfdb1 100644 --- a/tests/base_test.py +++ b/tests/base_test.py @@ -180,12 +180,7 @@ def test_move_to_base_async(self): # Stop the async moveTo process before exitting the test, we don't want # the async process to parasite the other tests - PepperBaseTest.robot.moveTo( - 0, - 0, - 0, - frame=PepperVirtual.FRAME_ROBOT, - _async=True) + PepperBaseTest.robot.stopMove() # Sleep to ensure that the previous snippet has been taken into account # and that the moveTo async process is stopped. From baa8881eab9426b2a3c154490b3093f8fbcfb9ee Mon Sep 17 00:00:00 2001 From: Maxime Busy Date: Mon, 21 Sep 2020 17:29:56 +0200 Subject: [PATCH 07/12] Add the getLink, getJoint and getLinkPosition methods. Possible improvement, handling more than one link/joint --- qibullet/robot_virtual.py | 41 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 41 insertions(+) diff --git a/qibullet/robot_virtual.py b/qibullet/robot_virtual.py index a357d0e..8324ad2 100644 --- a/qibullet/robot_virtual.py +++ b/qibullet/robot_virtual.py @@ -108,6 +108,26 @@ def getPhysicsClientId(self): """ return self.physics_client + def getJoint(self, joint_name): + """ + Returns the Joint object named "joint_name". If the required joint does + not exist, the method will raise a KeyError. + + Parameters: + joint_name - The name of the desired joint, eg "RShoulderPitch" + """ + return self.joint_dict[joint_dict] + + def getLink(self, link_name): + """ + Returns the Link object named "link_name". If the required link does + not exist, the method will raise a KeyError. + + Parameters: + link_name - The name of the desired link, eg "Tibia" + """ + return self.link_dict[link_name] + def setAngles(self, joint_names, joint_values, percentage_speeds): """ Set angles on the robot's joints. Tests have to be performed by the @@ -187,6 +207,27 @@ def getAnglesVelocity(self, joint_names): indexes, physicsClientId=self.physics_client)] + def getLinkPosition(self, link_name): + """ + Returns the position of a robot link in the WORLD frame. The position + is expressed as a 3 dimensional translation [x, y, z] and a 4 + dimensional quaternion [x, y, z, w]. If the required link does not + exist, the method will raise a KeyError. + + Parameters: + link_name - The name of the desired link, eg "Tibia" + + Returns: + translation - 3 dimensional list containing the translation + quaternion - 4 dimensional list containing the rotation, as a + quaternion + """ + link_state = pybullet.getLinkState( + self.robot_model, + self.link_dict[link_name].getIndex()) + + return link_state[0], link_state[1] + def subscribeCamera(self, camera_id, resolution=Camera.K_QVGA): """ Subscribe to the camera holding the camera id (for instance, From 7a3d19c14f412838df9ce47a202871f4533d0961 Mon Sep 17 00:00:00 2001 From: Maxime Busy Date: Mon, 21 Sep 2020 17:51:35 +0200 Subject: [PATCH 08/12] Add the corresponding link and joint unit tests --- tests/joint_test.py | 19 +++++++++++++++++++ tests/link_test.py | 41 +++++++++++++++++++++++++++++++++++++++++ 2 files changed, 60 insertions(+) diff --git a/tests/joint_test.py b/tests/joint_test.py index 6aac013..36765e4 100644 --- a/tests/joint_test.py +++ b/tests/joint_test.py @@ -50,6 +50,16 @@ def test_joints_characteristics(self): self.assertNotEqual(dummy_joint_first, dummy_joint_second) + def test_get_joint(self): + """ + Test the @getJoint method + """ + for key, value in JointTest.robot.joint_dict.items(): + self.assertEqual(JointTest.robot.getJoint(key), value) + + with self.assertRaises(KeyError): + JointTest.robot.getJoint("Non_existent_joint") + def test_set_angles(self): """ Test the set @setAngles method @@ -173,6 +183,9 @@ def tearDownClass(cls): def test_joints_characteristics(self): JointTest.test_joints_characteristics(self) + def test_get_joint(self): + JointTest.test_get_joint(self) + def test_set_angles(self): JointTest.test_set_angles(self) @@ -218,6 +231,9 @@ def tearDownClass(cls): def test_joints_characteristics(self): JointTest.test_joints_characteristics(self) + def test_get_joint(self): + JointTest.test_get_joint(self) + def test_set_angles(self): JointTest.test_set_angles(self) @@ -263,6 +279,9 @@ def tearDownClass(cls): def test_joints_characteristics(self): JointTest.test_joints_characteristics(self) + def test_get_joint(self): + JointTest.test_get_joint(self) + def test_set_angles(self): JointTest.test_set_angles(self) diff --git a/tests/link_test.py b/tests/link_test.py index b8a9ab4..38d6f64 100644 --- a/tests/link_test.py +++ b/tests/link_test.py @@ -33,6 +33,29 @@ def test_links_characteristics(self): list(LinkTest.robot.link_dict.values())[0], list(LinkTest.robot.link_dict.values())[1]) + def test_get_link(self): + """ + Test the @getLink method + """ + for key, value in LinkTest.robot.link_dict.items(): + self.assertEqual(LinkTest.robot.getLink(key), value) + + with self.assertRaises(KeyError): + LinkTest.robot.getLink("non_existent_link") + + def test_get_link_position(self): + """ + Test the @getLinkPosition method + """ + # Only test that the values returned by getLinkPosition are indeed a + # 3D translation and a 4D orientation (quaternion) + translation, orientation = LinkTest.robot.getLinkPosition("r_hand") + self.assertEqual(len(translation), 3) + self.assertEqual(len(orientation), 4) + + with self.assertRaises(KeyError): + LinkTest.robot.getLinkPosition("non_existent_link") + class PepperLinkTest(LinkTest): """ @@ -63,6 +86,12 @@ def tearDownClass(cls): def test_links_characteristics(self): LinkTest.test_links_characteristics(self) + def test_get_link(self): + LinkTest.test_get_link(self) + + def test_get_link_position(self): + LinkTest.test_get_link_position(self) + class NaoLinkTest(LinkTest): """ @@ -93,6 +122,12 @@ def tearDownClass(cls): def test_links_characteristics(self): LinkTest.test_links_characteristics(self) + def test_get_link(self): + LinkTest.test_get_link(self) + + def test_get_link_position(self): + LinkTest.test_get_link_position(self) + class RomeoLinkTest(LinkTest): """ @@ -123,6 +158,12 @@ def tearDownClass(cls): def test_links_characteristics(self): LinkTest.test_links_characteristics(self) + def test_get_link(self): + LinkTest.test_get_link(self) + + def test_get_link_position(self): + LinkTest.test_get_link_position(self) + if __name__ == "__main__": unittest.main() From 87c14425456638a993bee9f0049d3d658695c7e0 Mon Sep 17 00:00:00 2001 From: Maxime Busy Date: Mon, 21 Sep 2020 18:31:00 +0200 Subject: [PATCH 09/12] Fix unit tests --- qibullet/robot_virtual.py | 2 +- tests/laser_test.py | 2 +- tests/link_test.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/qibullet/robot_virtual.py b/qibullet/robot_virtual.py index 8324ad2..a3cf04f 100644 --- a/qibullet/robot_virtual.py +++ b/qibullet/robot_virtual.py @@ -116,7 +116,7 @@ def getJoint(self, joint_name): Parameters: joint_name - The name of the desired joint, eg "RShoulderPitch" """ - return self.joint_dict[joint_dict] + return self.joint_dict[joint_name] def getLink(self, link_name): """ diff --git a/tests/laser_test.py b/tests/laser_test.py index f5dbb24..798ceb1 100644 --- a/tests/laser_test.py +++ b/tests/laser_test.py @@ -38,7 +38,7 @@ def test_laser_robot_model(self): robot are the same """ self.assertEqual( - PepperLaserTest.laser_manager.getRobotModel(), + PepperLaserTest.robot.laser_manager.getRobotModel(), PepperLaserTest.robot.getRobotModel()) def test_lasers_data(self): diff --git a/tests/link_test.py b/tests/link_test.py index 38d6f64..cc60a49 100644 --- a/tests/link_test.py +++ b/tests/link_test.py @@ -49,7 +49,7 @@ def test_get_link_position(self): """ # Only test that the values returned by getLinkPosition are indeed a # 3D translation and a 4D orientation (quaternion) - translation, orientation = LinkTest.robot.getLinkPosition("r_hand") + translation, orientation = LinkTest.robot.getLinkPosition("torso") self.assertEqual(len(translation), 3) self.assertEqual(len(orientation), 4) From 8fc72d625858793579ac726686b93880f8fbc2e6 Mon Sep 17 00:00:00 2001 From: Maxime Busy Date: Mon, 21 Sep 2020 18:36:14 +0200 Subject: [PATCH 10/12] Fix the stopMove method --- qibullet/base_controller.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/qibullet/base_controller.py b/qibullet/base_controller.py index aa24407..90fb2ea 100644 --- a/qibullet/base_controller.py +++ b/qibullet/base_controller.py @@ -315,9 +315,9 @@ def stopMove(self): """ If an aynchronous moveTo has been launched, calling this method will stop the asynchronous process. Calling this method is equivalent to - calling moveTo(0.0, 0.0, 0.0, _async=True) + calling moveTo(0.0, 0.0, 0.0, BaseController.FRAME_ROBOT, _async=True) """ - self.moveTo(0.0, 0.0, 0.0, _async=True) + self.moveTo(0.0, 0.0, 0.0, BaseController.FRAME_ROBOT, _async=True) def _updateConstraint(self): """ From 14600b3217ec64944149f560c3277626ca37a31a Mon Sep 17 00:00:00 2001 From: mbusy Date: Tue, 22 Sep 2020 11:50:53 +0200 Subject: [PATCH 11/12] Bump version to 1.4.2 --- docs/Doxyfile | 2 +- qibullet/__init__.py | 2 +- setup.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/Doxyfile b/docs/Doxyfile index f182ce8..a03415a 100644 --- a/docs/Doxyfile +++ b/docs/Doxyfile @@ -38,7 +38,7 @@ PROJECT_NAME = "qiBullet" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 1.4.1 +PROJECT_NUMBER = 1.4.2 # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer a diff --git a/qibullet/__init__.py b/qibullet/__init__.py index 1b46171..f4d8550 100644 --- a/qibullet/__init__.py +++ b/qibullet/__init__.py @@ -10,4 +10,4 @@ from qibullet.ros_wrapper import PepperRosWrapper name = 'qibullet' -__version__ = "1.4.1" +__version__ = "1.4.2" diff --git a/setup.py b/setup.py index 8f38393..dce722d 100644 --- a/setup.py +++ b/setup.py @@ -86,7 +86,7 @@ def run(self): setuptools.setup( name="qibullet", - version="1.4.1", + version="1.4.2", author="Maxime Busy, Maxime Caniot", author_email="", description="Bullet-based simulation for SoftBank Robotics' robots", From f894eb45d5d5cc517da061153e76321f5c8fbb9c Mon Sep 17 00:00:00 2001 From: mbusy Date: Tue, 22 Sep 2020 11:54:44 +0200 Subject: [PATCH 12/12] Update the documentation --- docs/api/annotated.html | 2 +- docs/api/classes.html | 2 +- ..._controller_1_1BaseController-members.html | 2 +- ...1_1base__controller_1_1BaseController.html | 2 +- ...oller_1_1PepperBaseController-members.html | 3 +- ...e__controller_1_1PepperBaseController.html | 23 +++- ...sqibullet_1_1camera_1_1Camera-members.html | 2 +- .../classqibullet_1_1camera_1_1Camera.html | 2 +- ...llet_1_1camera_1_1CameraDepth-members.html | 2 +- ...lassqibullet_1_1camera_1_1CameraDepth.html | 2 +- ...1_1camera_1_1CameraResolution-members.html | 2 +- ...ibullet_1_1camera_1_1CameraResolution.html | 2 +- ...bullet_1_1camera_1_1CameraRgb-members.html | 2 +- .../classqibullet_1_1camera_1_1CameraRgb.html | 2 +- ...t_1_1controller_1_1Controller-members.html | 2 +- ...sqibullet_1_1controller_1_1Controller.html | 2 +- ...assqibullet_1_1joint_1_1Joint-members.html | 2 +- docs/api/classqibullet_1_1joint_1_1Joint.html | 2 +- ...assqibullet_1_1laser_1_1Laser-members.html | 2 +- docs/api/classqibullet_1_1laser_1_1Laser.html | 2 +- ...classqibullet_1_1link_1_1Link-members.html | 2 +- docs/api/classqibullet_1_1link_1_1Link.html | 2 +- ...1_1nao__virtual_1_1NaoVirtual-members.html | 53 +++++---- ...ibullet_1_1nao__virtual_1_1NaoVirtual.html | 8 +- ...per__virtual_1_1PepperVirtual-members.html | 60 +++++----- ...t_1_1pepper__virtual_1_1PepperVirtual.html | 29 ++++- ...1robot__module_1_1RobotModule-members.html | 2 +- ...ullet_1_1robot__module_1_1RobotModule.html | 2 +- ...1robot__posture_1_1NaoPosture-members.html | 2 +- ...ullet_1_1robot__posture_1_1NaoPosture.html | 2 +- ...bot__posture_1_1PepperPosture-members.html | 2 +- ...et_1_1robot__posture_1_1PepperPosture.html | 2 +- ...obot__posture_1_1RobotPosture-members.html | 2 +- ...let_1_1robot__posture_1_1RobotPosture.html | 2 +- ...obot__posture_1_1RomeoPosture-members.html | 2 +- ...let_1_1robot__posture_1_1RomeoPosture.html | 2 +- ...obot__virtual_1_1RobotVirtual-members.html | 29 ++--- ...let_1_1robot__virtual_1_1RobotVirtual.html | 108 +++++++++++++++++- ...omeo__virtual_1_1RomeoVirtual-members.html | 47 ++++---- ...let_1_1romeo__virtual_1_1RomeoVirtual.html | 8 +- ...ros__wrapper_1_1NaoRosWrapper-members.html | 29 +++-- ...llet_1_1ros__wrapper_1_1NaoRosWrapper.html | 11 +- ...__wrapper_1_1PepperRosWrapper-members.html | 33 +++--- ...t_1_1ros__wrapper_1_1PepperRosWrapper.html | 11 +- ...s__wrapper_1_1RomeoRosWrapper-members.html | 35 +++--- ...et_1_1ros__wrapper_1_1RomeoRosWrapper.html | 11 +- ...1_1ros__wrapper_1_1RosWrapper-members.html | 21 ++-- ...ibullet_1_1ros__wrapper_1_1RosWrapper.html | 11 +- ...sqibullet_1_1sensor_1_1Sensor-members.html | 2 +- .../classqibullet_1_1sensor_1_1Sensor.html | 2 +- ..._manager_1_1SimulationManager-members.html | 2 +- ...ulation__manager_1_1SimulationManager.html | 8 +- .../dir_6f408bf5b5cefda8ce18c40801c7f671.html | 4 +- docs/api/functions.html | 15 ++- docs/api/functions_func.html | 15 ++- docs/api/graph_legend.html | 2 +- docs/api/hierarchy.html | 2 +- docs/api/index.html | 2 +- docs/api/inherits.html | 2 +- docs/api/search/all_3.js | 3 + docs/api/search/all_b.js | 1 + docs/api/search/functions_1.js | 3 + docs/api/search/functions_6.js | 1 + 63 files changed, 410 insertions(+), 244 deletions(-) diff --git a/docs/api/annotated.html b/docs/api/annotated.html index dc1956e..8dc59fd 100644 --- a/docs/api/annotated.html +++ b/docs/api/annotated.html @@ -24,7 +24,7 @@
qiBullet -  1.4.1 +  1.4.2
Bullet-based python simulation for SoftBank Robotics' robots.
diff --git a/docs/api/classes.html b/docs/api/classes.html index 751fdba..974fb7e 100644 --- a/docs/api/classes.html +++ b/docs/api/classes.html @@ -24,7 +24,7 @@
qiBullet -  1.4.1 +  1.4.2
Bullet-based python simulation for SoftBank Robotics' robots.
diff --git a/docs/api/classqibullet_1_1base__controller_1_1BaseController-members.html b/docs/api/classqibullet_1_1base__controller_1_1BaseController-members.html index ce6084f..7e9df6f 100644 --- a/docs/api/classqibullet_1_1base__controller_1_1BaseController-members.html +++ b/docs/api/classqibullet_1_1base__controller_1_1BaseController-members.html @@ -24,7 +24,7 @@
qiBullet -  1.4.1 +  1.4.2
Bullet-based python simulation for SoftBank Robotics' robots.
diff --git a/docs/api/classqibullet_1_1base__controller_1_1BaseController.html b/docs/api/classqibullet_1_1base__controller_1_1BaseController.html index f0f1fc8..2b7a6a5 100644 --- a/docs/api/classqibullet_1_1base__controller_1_1BaseController.html +++ b/docs/api/classqibullet_1_1base__controller_1_1BaseController.html @@ -24,7 +24,7 @@
qiBullet -  1.4.1 +  1.4.2
Bullet-based python simulation for SoftBank Robotics' robots.
diff --git a/docs/api/classqibullet_1_1base__controller_1_1PepperBaseController-members.html b/docs/api/classqibullet_1_1base__controller_1_1PepperBaseController-members.html index f5db84a..11e78e4 100644 --- a/docs/api/classqibullet_1_1base__controller_1_1PepperBaseController-members.html +++ b/docs/api/classqibullet_1_1base__controller_1_1PepperBaseController-members.html @@ -24,7 +24,7 @@
qiBullet -  1.4.1 +  1.4.2
Bullet-based python simulation for SoftBank Robotics' robots.
@@ -129,6 +129,7 @@ pose_init (defined in qibullet.base_controller.BaseController)qibullet.base_controller.BaseController robot_model (defined in qibullet.robot_module.RobotModule)qibullet.robot_module.RobotModule setLinearVelocity(self, linear_velocity)qibullet.base_controller.PepperBaseController + stopMove(self)qibullet.base_controller.PepperBaseController