When reading response from the Bullet server after a "load URDF" command, the client code allocated and zeroed buffers for the data chunks with a "+1" to account for the terminating zero. This was when the buffer pointer was interpreted as a `char *`, so it meant "+ 1 byte".
When reading those buffers, however, the associated pointer was a `void *`, so reading `sizeof(void*)` (8 on my machine) bytes at a time. Therefore it was reading up to 7 bytes past the allocated (and zeroed) memory.
The change fixes that by changing the "+ 1" to "+ sizeof(void*)". At one place it also extends the zeroing to the final buffer position (missing "+ 1" in the original).
When the parser sees no <inertial> tag inside a <deformable>, it logs an error but does not return false. So in the next step, a null pointer is dereferenced.
This can be tested with loading the following URDF:
```
<?xml version="1.0"?>
<robot name="rhythm_carrot_sticks">
<deformable name="bag">
</deformable>
</robot>
```
Skips triangle processing if the triangle is out-of-AABB on the up axis.
This massively improves OpenMW performance on my test machine.
Co-authored-by: Andrew Shulaev <ash.drone@gmail.com>
p.connect(p.GUI, options="--background_color_red=1 --background_color_blue=1 --background_color_green=1")
If you use bullet_client.py, you can use:
p = bc.BulletClient(connection_mode=pybullet.GUI,options="--background_color_red=1 --background_color_blue=1 --background_color_green=1")
--mouse_move_multiplier=0.4
--mouse_wheel_multiplier=0.01
--mp4=moviename.mp4
On some systems, such as Android, threads are not provided via
`-lpthread`.
CMake comes with a built-in module for finding the correct threads
library.
Use it to fix the linking issue on Android and possibly other systems.