12#ifndef HPP_CORBASERVER_ROBOT_SERVER_IDL
13#define HPP_CORBASERVER_ROBOT_SERVER_IDL
36 in
string urdfName, in
string srdfName)
50 in
string urdfName, in
string srdfName)
62 in
string urdfString, in
string srdfString)
74 in
string urdfString, in
string srdfString)
331 out
string report) raises (
Error);
430 in
string jointName, in
string jointType,
442 void createBox (in
string name, in
double x, in
double y, in
double z)
462 unsigned long addPoint(in
string inPolyName, in
double x, in
double y, in
double z)
471 unsigned long addTriangle(in
string inPolyName, in
unsigned long pt1,
472 in
unsigned long pt2, in
unsigned long pt3)
480 in
string objectName,
Definition robots-idl.hh:94
Corba exception travelling through the Corba channel.
Definition common.idl:27
Creation of a device, joints and bodies.
Definition robot.idl:21
void autocollisionCheck(out boolSeq collide)
void createCylinder(in string name, in double radius, in double length)
floatSeq getJointConfig(in string jointName)
floatSeq getCurrentVelocity()
void setJointConfig(in string jointName, in floatSeq config)
floatSeq getJointVelocity(in string jointName)
void setRootJointPosition(in Transform_ position)
void setCurrentConfig(in floatSeq dofArray)
Names_t getJointInnerObjects(in string jointName)
void loadHumanoidModelFromString(in string robotName, in string rootJointType, in string urdfString, in string srdfString)
void appendJoint(in string parentJoint, in string jointName, in string jointType, in Transform_ pos)
void loadHumanoidModel(in string robotName, in string rootJointType, in string urdfName, in string srdfName)
long getJointNumberDof(in string jointName)
floatSeq getJointBounds(in string jointName)
void setJointBounds(in string jointName, in floatSeq inJointBound)
set bounds for a joint
void autocollisionPairs(out Names_t innerObjects, out Names_t outerObjects, out boolSeq active)
long getJointConfigSize(in string jointName)
void isConfigValid(in floatSeq dofArray, out boolean validity, out string report)
floatSeq getCurrentConfig()
floatSeq getVelocityPartialCom(in string comName)
Get the velocity of the partial center of mass.
floatSeqSeq getCurrentTransformation(in string jointName)
void createBox(in string name, in double x, in double y, in double z)
double getMass()
Get mass of robot.
void createPolyhedron(in string inPolyName)
void getObjectPosition(in string objectName, out Transform_ cfg)
void loadRobotModel(in string robotName, in string rootJointType, in string urdfName, in string srdfName)
Names_t getAllJointNames()
Get all joint names including anchor joints.
Names_t getJointOuterObjects(in string jointName)
string getParentJointName(in string jointName)
Transform_ getLinkPosition(in string linkName)
void distancesToCollision(out floatSeq distances, out Names_t innerObjects, out Names_t outerObjects, out floatSeqSeq innerPoints, out floatSeqSeq outerPoints)
unsigned long getDimensionExtraConfigSpace()
string getJointType(in string jointName)
Transform_ getJointPosition(in string jointName)
TransformSeq getJointsPosition(in floatSeq q, in Names_t jointNames)
void setExtraConfigSpaceBounds(in floatSeq bounds)
floatSeq getCenterOfMassVelocity()
Get velocity of center of mass.
floatSeqSeq getJacobianCenterOfMass()
Get Jacobian of the center of mass.
Transform_ getJointPositionInParentFrame(in string jointName)
void addPartialCom(in string comName, in Names_t jointNames)
void addObjectToJoint(in string jointName, in string objectName, in Transform_ pos)
floatSeq shootRandomConfig()
string getRobotName()
Get the name of the current robot.
floatSeq getPartialCom(in string comName)
Get position of partial center of mass.
floatSeq getCenterOfMass()
Get position of center of mass.
void createSphere(in string name, in double radius)
floatSeqSeq getJacobianPartialCom(in string comName)
Get Jacobian of the partial center of mass.
floatSeq getJointVelocityInLocalFrame(in string jointName)
unsigned long addPoint(in string inPolyName, in double x, in double y, in double z)
floatSeq getRobotAABB()
Get the aligned axes bounding box around the robot.
void createRobot(in string robotName)
TransformSeq getLinksPosition(in floatSeq q, in Names_t linkName)
Names_t getJointTypes()
Get joint types in the same order as in the configuration.
Transform_ getRootJointPosition()
void setJointPositionInParentFrame(in string jointName, in Transform_ position)
Names_t getLinkNames(in string jointName)
floatSeq jointIntegrate(in floatSeq jointCfg, in string jointName, in floatSeq speed, in boolean saturate)
void setAutoCollision(in string innerObject, in string outerObject, in boolean active)
void setDimensionExtraConfigSpace(in unsigned long dimension)
pinocchio_idl::CenterOfMassComputation getCenterOfMassComputation(in string name)
void loadRobotModelFromString(in string robotName, in string rootJointType, in string urdfString, in string srdfString)
void setCurrentVelocity(in floatSeq qDot)
unsigned long addTriangle(in string inPolyName, in unsigned long pt1, in unsigned long pt2, in unsigned long pt3)
Definition _problem.idl:17
Implement CORBA interface `‘Obstacle’'.
Definition client.hh:46
sequence< boolean > boolSeq
Definition common.idl:30
sequence< double > floatSeq
Robot configuration is defined by a sequence of dof value.
Definition common.idl:34
double Transform_[7]
Element of SE(3) represented by a vector and a unit quaternion.
Definition common.idl:38
sequence< Transform_ > TransformSeq
Definition common.idl:39
sequence< floatSeq > floatSeqSeq
Definition common.idl:35
sequence< string > Names_t
Sequence of names.
Definition common.idl:23