URDF/SDF: add a flag to force concave mesh collisiofor static objects. <collision concave="yes" name="pod_collision"> VR: support teleporting using buttong, allow multiple controllers to be used, fast wireframe rendering, Turn off warnings about deprecated C routine in btScalar.h/b3Scalar.h Add a dummy return to stop a warning Expose defaultContactERP in shared memory api/pybullet. First start to expose IK in shared memory api/pybullet (not working yet)
33 lines
691 B
C++
33 lines
691 B
C++
#ifndef IK_TRAJECTORY_HELPER_H
|
|
#define IK_TRAJECTORY_HELPER_H
|
|
|
|
enum IK2_Method
|
|
{
|
|
IK2_JACOB_TRANS=0,
|
|
IK2_PURE_PSEUDO,
|
|
IK2_DLS,
|
|
IK2_SDLS ,
|
|
IK2_DLS_SVD
|
|
};
|
|
|
|
|
|
class IKTrajectoryHelper
|
|
{
|
|
struct IKTrajectoryHelperInternalData* m_data;
|
|
|
|
public:
|
|
IKTrajectoryHelper();
|
|
virtual ~IKTrajectoryHelper();
|
|
|
|
///todo: replace createKukaIIWA with a generic way of create an IK tree
|
|
void createKukaIIWA();
|
|
|
|
bool createFromMultiBody(class btMultiBody* mb);
|
|
|
|
bool computeIK(const double endEffectorTargetPosition[3],
|
|
const double* q_old, int numQ,
|
|
double* q_new, int ikMethod);
|
|
|
|
};
|
|
#endif //IK_TRAJECTORY_HELPER_H
|