Hi Coppelia and forum,
Is it possible to get the dimension of the bounding box?
I have a legged robot that comprises many parts and I want to use the bounding box width and height in a reinforcement learning algorithm. E.g., I want the robot to walk through narrow corridors and therefore the bounding box width should be as small as possible.
Best Regards,
Mathias Thor
Bounding box dimentions
Re: Bounding box dimentions
Hello Mathias,
you can use
If you need the bounding box along specific axes for an object or model, or the tight bounding box of a model (the normal model bounding box is the bounding box that encompasses all object bounding boxes inside of the model), then you will have to parse through the vertices of your shapes, using
Cheers
you can use
sim.getObjectFloatParameter
together with the appropriate args, e.g.:Code: Select all
function getObjectBoundingBoxSize(handle)
local s={}
local r,m=sim.getObjectFloatParameter(handle,sim.objfloatparam_objbbox_max_x)
local r,n=sim.getObjectFloatParameter(handle,sim.objfloatparam_objbbox_min_x)
s[1]=m-n
local r,m=sim.getObjectFloatParameter(handle,sim.objfloatparam_objbbox_max_y)
local r,n=sim.getObjectFloatParameter(handle,sim.objfloatparam_objbbox_min_y)
s[2]=m-n
local r,m=sim.getObjectFloatParameter(handle,sim.objfloatparam_objbbox_max_z)
local r,n=sim.getObjectFloatParameter(handle,sim.objfloatparam_objbbox_min_z)
s[3]=m-n
return s
end
function getModelBoundingBoxSize(handle)
local s={}
local r,m=sim.getObjectFloatParameter(handle,sim.objfloatparam_modelbbox_max_x)
local r,n=sim.getObjectFloatParameter(handle,sim.objfloatparam_modelbbox_min_x)
s[1]=m-n
local r,m=sim.getObjectFloatParameter(handle,sim.objfloatparam_modelbbox_max_y)
local r,n=sim.getObjectFloatParameter(handle,sim.objfloatparam_modelbbox_min_y )
s[2]=m-n
local r,m=sim.getObjectFloatParameter(handle,sim.objfloatparam_modelbbox_max_z)
local r,n=sim.getObjectFloatParameter(handle,sim.objfloatparam_modelbbox_min_z)
s[3]=m-n
return s
end
sim.getShapeMesh
(and probably some transformation functions). But that will be much slower obviously.Cheers
Re: Bounding box dimentions
Thanks for the quick response, worked perfectly!