hpp-corbaserver  6.0.0
Corba server for Humanoid Path Planner applications
robot.idl
Go to the documentation of this file.
1 // Copyright (C) 2009, 2010, 2011, 2012, 1013, 2014 CNRS
2 // Authors: Florent Lamiraux, Thomas Moulard.
3 //
4 // This file is part of the hpp-corbaserver.
5 //
6 // This software is provided "as is" without warranty of any kind,
7 // either expressed or implied, including but not limited to the
8 // implied warranties of fitness for a particular purpose.
9 //
10 // See the COPYING file for more information.
11 
12 #ifndef HPP_CORBASERVER_ROBOT_SERVER_IDL
13 #define HPP_CORBASERVER_ROBOT_SERVER_IDL
14 #include <hpp/common.idl>
16 
17 module hpp
18 {
19  module corbaserver {
21  interface Robot {
24 
35  void loadRobotModel (in string robotName, in string rootJointType,
36  in string urdfName, in string srdfName)
37  raises (Error);
38 
49  void loadHumanoidModel (in string robotName, in string rootJointType,
50  in string urdfName, in string srdfName)
51  raises (Error);
52 
61  void loadRobotModelFromString (in string robotName, in string rootJointType,
62  in string urdfString, in string srdfString)
63  raises (Error);
64 
73  void loadHumanoidModelFromString (in string robotName, in string rootJointType,
74  in string urdfString, in string srdfString)
75  raises (Error);
76 
78 
81 
84  long getConfigSize () raises (Error);
85 
88  long getNumberDof () raises (Error);
89 
91 
94 
97  Names_t getJointNames () raises (Error);
98 
100  Names_t getJointTypes () raises (Error);
101 
103  Names_t getAllJointNames () raises (Error);
104 
108  string getParentJointName (in string jointName) raises (Error);
109 
115  floatSeq getJointConfig(in string jointName) raises (Error);
116 
126  void setJointConfig(in string jointName, in floatSeq config) raises (Error);
127 
131  string getJointType(in string jointName) raises (Error);
132 
142  floatSeq jointIntegrate(in floatSeq jointCfg, in string jointName, in floatSeq speed, in boolean saturate) raises (Error);
143 
147  floatSeqSeq getCurrentTransformation(in string jointName) raises (Error);
148 
152  Transform_ getJointPosition (in string jointName) raises (Error);
153 
156  TransformSeq getJointsPosition (in floatSeq q, in Names_t jointNames) raises (Error);
157 
162  floatSeq getJointVelocity (in string jointName) raises (Error);
163 
168  floatSeq getJointVelocityInLocalFrame (in string jointName) raises (Error);
169 
173  Transform_ getJointPositionInParentFrame (in string jointName) raises (Error);
174 
178  Transform_ getRootJointPosition () raises (Error);
179 
183  void setRootJointPosition (in Transform_ position) raises (Error);
184 
187  void setJointPositionInParentFrame (in string jointName, in Transform_ position)
188  raises (Error);
189 
193  long getJointNumberDof (in string jointName) raises (Error);
194 
198  long getJointConfigSize (in string jointName) raises (Error);
199 
201 
210  void setJointBounds(in string jointName,
211  in floatSeq inJointBound)
212  raises (Error);
213 
221  floatSeq getJointBounds(in string jointName) raises (Error);
222 
232  Transform_ getLinkPosition (in string linkName) raises (Error);
233 
236  TransformSeq getLinksPosition (in floatSeq q, in Names_t linkName) raises (Error);
237 
242  Names_t getLinkNames (in string jointName) raises (Error);
243 
245 
248 
253  void setDimensionExtraConfigSpace (in unsigned long dimension)
254  raises (Error);
255 
259  unsigned long getDimensionExtraConfigSpace ()
260  raises (Error);
261 
268  void setExtraConfigSpaceBounds (in floatSeq bounds) raises (Error);
269 
271 
274 
277  floatSeq getCurrentConfig() raises (Error);
278 
281  floatSeq shootRandomConfig() raises (Error);
282 
285  void setCurrentConfig(in floatSeq dofArray) raises (Error);
286 
289  floatSeq getCurrentVelocity() raises (Error);
290 
293  void setCurrentVelocity(in floatSeq qDot) raises (Error);
294 
296 
299 
303  Names_t getJointInnerObjects (in string jointName) raises (Error);
304 
305 
309  Names_t getJointOuterObjects (in string jointName) raises (Error);
310 
316  void getObjectPosition (in string objectName, out Transform_ cfg)
317  raises (Error);
318 
320 
323 
330  void isConfigValid (in floatSeq dofArray, out boolean validity,
331  out string report) raises (Error);
332 
333 
343  void distancesToCollision (out floatSeq distances,
344  out Names_t innerObjects,
345  out Names_t outerObjects,
346  out floatSeqSeq innerPoints,
347  out floatSeqSeq outerPoints) raises (Error);
348 
353  void autocollisionCheck (out boolSeq collide) raises (Error);
354 
360  void autocollisionPairs (out Names_t innerObjects, out Names_t outerObjects, out boolSeq active) raises (Error);
361 
362  void setAutoCollision (in string innerObject, in string outerObject, in boolean active) raises (Error);
363 
365  floatSeq getRobotAABB () raises (Error);
366 
368 
371 
373  double getMass () raises (Error);
374 
376  floatSeq getCenterOfMass () raises (Error);
377 
379  floatSeq getCenterOfMassVelocity () raises (Error);
380 
382  floatSeqSeq getJacobianCenterOfMass () raises (Error);
383 
389  void addPartialCom (in string comName, in Names_t jointNames)
390  raises (Error);
391 
393  floatSeq getPartialCom (in string comName) raises (Error);
394 
396  floatSeqSeq getJacobianPartialCom (in string comName) raises (Error);
397 
399  floatSeq getVelocityPartialCom (in string comName)
400  raises (Error);
401 
403  string getRobotName () raises (Error);
404 
405  pinocchio_idl::CenterOfMassComputation getCenterOfMassComputation (in string name) raises (Error);
406 
408 
411 
414  void createRobot(in string robotName) raises (Error);
415 
416  // Create a new joint
417  // \param parentJoint name of the parent joint,
418  // \param jointName name of the joint,
419  // \param jointType among ["FreeFlyer", "Planar",
420  // "RX", "RY", "RZ",
421  // "RUBX", "RUBY",
422  // "RUBZ",
423  // "PX", "PY", "PZ",
424  // "Translation"]
425  // \param pos initial position of the joint
426  // \param joinBounds bounds of the joint. See setJointBounds for details.
427  // \note In the joint types, R stands for Rotation, RUB stands for
428  // Rotation UnBounded, P stands for Prismatic. Translation is 3D.
429  void appendJoint(in string parentJoint,
430  in string jointName, in string jointType,
431  in Transform_ pos)
432  raises (Error);
433 
437  void createPolyhedron(in string inPolyName) raises (Error);
438 
442  void createBox (in string name, in double x, in double y, in double z)
443  raises (Error);
444 
448  void createSphere (in string name, in double radius) raises (Error);
449 
454  void createCylinder (in string name, in double radius, in double length) raises (Error);
455 
462  unsigned long addPoint(in string inPolyName, in double x, in double y, in double z)
463  raises (Error);
464 
471  unsigned long addTriangle(in string inPolyName, in unsigned long pt1,
472  in unsigned long pt2, in unsigned long pt3)
473  raises (Error);
474 
479  void addObjectToJoint(in string jointName,
480  in string objectName,
481  in Transform_ pos)
482  raises (Error);
483 
485  };
486  };
487 };
488 
489 #endif // HPP_CORBASERVER_ROBOT_SERVER_IDL
Definition: robots-idl.hh:94
Definition: common-idl.hh:78
Definition: common-idl.hh:965
Definition: common-idl.hh:347
Definition: common-idl.hh:803
Definition: common-idl.hh:689
::CORBA::Double Transform_[7]
Definition: common-idl.hh:915
Corba exception travelling through the Corba channel.
Definition: common.idl:27
Creation of a device, joints and bodies.
Definition: robot.idl:21
void loadHumanoidModelFromString(in string robotName, in string rootJointType, in string urdfString, in string srdfString)
void loadHumanoidModel(in string robotName, in string rootJointType, in string urdfName, in string srdfName)
void loadRobotModel(in string robotName, in string rootJointType, in string urdfName, in string srdfName)
void loadRobotModelFromString(in string robotName, in string rootJointType, in string urdfString, in string srdfString)
Implement CORBA interface `‘Obstacle’'.
Definition: client.hh:46