00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #ifndef PLANNING_MODELS_KINEMATIC_STATE_
00038 #define PLANNING_MODELS_KINEMATIC_STATE_
00039
00040 #include "kinematic_model.h"
00041
00043 namespace planning_models
00044 {
00045
00049 class KinematicState
00050 {
00051
00052 public:
00053
00054 class JointState; ;
00055
00056 class LinkState;
00058 class AttachedBodyState;
00060 class JointGroupState;
00062 class JointState
00063 {
00064 public:
00065
00067 JointState(const KinematicModel::JointModel* jm);
00068
00069 ~JointState()
00070 {
00071 }
00072
00074 bool setJointStateValues(const std::map<std::string, double>& joint_value_map);
00075
00077 bool setJointStateValues(const std::vector<double>& joint_value_vector);
00078
00080 bool setJointStateValues(const btTransform& transform);
00081
00084 bool allJointStateValuesAreDefined(const std::map<std::string, double>& joint_value_map) const;
00085
00088 bool getJointValueBounds(const std::string& value_name, double& low, double& high) const;
00089
00091 const std::map<std::string, std::pair<double, double> >& getAllJointValueBounds() const;
00092
00094 bool areJointStateValuesWithinBounds() const;
00095
00096 const std::string& getName() const
00097 {
00098 return joint_model_->getName();
00099 }
00100
00102 unsigned int getDimension()
00103 {
00104 return joint_state_values_.size();
00105 }
00106
00108 const std::vector<double>& getJointStateValues() const;
00109
00111 const std::vector<std::string>& getJointStateNameOrder() const;
00112
00114 const btTransform& getVariableTransform() const
00115 {
00116 return variable_transform_;
00117 }
00118
00120 const KinematicModel::JointModel* getJointModel() const
00121 {
00122 return joint_model_;
00123 }
00124
00125 const std::map<std::string, unsigned int>& getJointStateIndexMap() const
00126 {
00127 return joint_state_index_map_;
00128 }
00129
00130 const std::string& getParentFrameId() const
00131 {
00132 return joint_model_->getParentFrameId();
00133 }
00134
00135 const std::string& getChildFrameId() const
00136 {
00137 return joint_model_->getChildFrameId();
00138 }
00139
00140 private:
00141
00142 const KinematicModel::JointModel* joint_model_;
00143
00145 btTransform variable_transform_;
00146
00147 std::map<std::string, unsigned int> joint_state_index_map_;
00148
00149 std::vector<std::string> joint_state_name_order_;
00150
00151 std::vector<double> joint_state_values_;
00152 };
00153
00154 class LinkState
00155 {
00156 public:
00157 LinkState(const KinematicModel::LinkModel* lm);
00158
00159 ~LinkState();
00160
00161 const std::string& getName() const
00162 {
00163 return link_model_->getName();
00164 }
00165
00166 void setParentJointState(const JointState* js)
00167 {
00168 parent_joint_state_ = js;
00169 }
00170
00171 void setParentLinkState(const LinkState* ls)
00172 {
00173 parent_link_state_ = ls;
00174 }
00175
00176 void updateGivenGlobalLinkTransform(const btTransform& transform)
00177 {
00178 global_link_transform_ = transform;
00179 global_collision_body_transform_.mult(global_link_transform_, link_model_->getCollisionOriginTransform());
00180 updateAttachedBodies();
00181 }
00182
00184 void computeTransform(void);
00185
00186
00187 void updateAttachedBodies();
00188
00189 const KinematicModel::LinkModel* getLinkModel() const
00190 {
00191 return link_model_;
00192 }
00193
00194 const JointState* getParentJointState() const
00195 {
00196 return parent_joint_state_;
00197 }
00198
00199 const LinkState* getParentLinkState() const
00200 {
00201 return parent_link_state_;
00202 }
00203
00204 const std::vector<AttachedBodyState*>& getAttachedBodyStateVector() const
00205 {
00206 return attached_body_state_vector_;
00207 }
00208
00209 const btTransform& getGlobalLinkTransform() const
00210 {
00211 return global_link_transform_;
00212 }
00213
00214 const btTransform& getGlobalCollisionBodyTransform() const
00215 {
00216 return global_collision_body_transform_;
00217 }
00218
00219 private:
00220
00221 const KinematicModel::LinkModel* link_model_;
00222
00223 const JointState* parent_joint_state_;
00224
00225 const LinkState* parent_link_state_;
00226
00227 std::vector<AttachedBodyState*> attached_body_state_vector_;
00228
00230 btTransform global_link_transform_;
00231
00233 btTransform global_collision_body_transform_;
00234 };
00235
00236 class AttachedBodyState
00237 {
00238 public:
00239 AttachedBodyState(const KinematicModel::AttachedBodyModel* abm, const LinkState* parent_link_state);
00240
00241 ~AttachedBodyState()
00242 {
00243 }
00244
00245 const std::string& getName() const
00246 {
00247 return attached_body_model_->getName();
00248 }
00249
00250 const std::string& getAttachedLinkName() const
00251 {
00252 return attached_body_model_->getAttachedLinkModel()->getName();
00253 }
00254
00255 const KinematicModel::AttachedBodyModel* getAttachedBodyModel() const
00256 {
00257 return attached_body_model_;
00258 }
00259
00261 void computeTransform(void);
00262
00263 const std::vector<btTransform>& getGlobalCollisionBodyTransforms() const
00264 {
00265 return global_collision_body_transforms_;
00266 }
00267
00268 private:
00269 const KinematicModel::AttachedBodyModel* attached_body_model_;
00270
00271 const LinkState* parent_link_state_;
00272
00274 std::vector<btTransform> global_collision_body_transforms_;
00275
00276 };
00277
00278 class JointStateGroup
00279 {
00280 public:
00281
00282 JointStateGroup(const KinematicModel::JointModelGroup* jmg, const KinematicState* owner);
00283
00284
00285
00286 ~JointStateGroup(void)
00287 {
00288 }
00289
00290 const KinematicModel::JointModelGroup* getJointModelGroup() {
00291 return joint_model_group_;
00292 }
00293
00294 const std::string& getName() const;
00295
00296 unsigned int getDimension() const
00297 {
00298 return dimension_;
00299 }
00300
00305 bool setKinematicState(const std::vector<double>& joint_state_values);
00306
00311 bool setKinematicState(const std::map<std::string, double>& joint_state_map);
00312
00314 void updateKinematicLinks();
00315
00317 bool hasJointState(const std::string &joint) const;
00318
00320 bool updatesLinkState(const std::string& joint) const;
00321
00323 JointState* getJointState(const std::string &joint) const;
00324
00325 void getKinematicStateValues(std::vector<double>& joint_state_values) const;
00326
00327 void getKinematicStateValues(std::map<std::string, double>& joint_state_values) const;
00328
00332 void setKinematicStateToDefault();
00333
00334 const std::vector<JointState*>& getJointRoots() const
00335 {
00336 return joint_roots_;
00337 }
00338
00339 const std::map<std::string, unsigned int>& getKinematicStateIndexMap() const
00340 {
00341 return kinematic_state_index_map_;
00342 }
00343
00344 const std::vector<std::string>& getJointNames() const
00345 {
00346 return joint_names_;
00347 }
00348
00349 const std::vector<JointState*>& getJointStateVector() const
00350 {
00351 return joint_state_vector_;
00352 }
00353
00354 private:
00355
00357 boost::shared_ptr<KinematicModel> kinematic_model_;
00358
00359 const KinematicModel::JointModelGroup* joint_model_group_;
00360
00361 unsigned int dimension_;
00362 std::map<std::string, unsigned int> kinematic_state_index_map_;
00363
00365 std::vector<std::string> joint_names_;
00366
00368 std::vector<JointState*> joint_state_vector_;
00369
00371 std::map<std::string, JointState*> joint_state_map_;
00372
00374 std::vector<JointState*> joint_roots_;
00375
00377 std::vector<LinkState*> updated_links_;
00378 };
00379
00380 KinematicState(const boost::shared_ptr<const KinematicModel> kinematic_model);
00381
00382 KinematicState(const KinematicState* state);
00383
00384 ~KinematicState(void);
00385
00386 bool setKinematicState(const std::vector<double>& joint_state_values);
00387
00388 bool setKinematicState(const std::map<std::string, double>& joint_state_map);
00389
00390 void getKinematicStateValues(std::vector<double>& joint_state_values) const;
00391
00392 void getKinematicStateValues(std::map<std::string, double>& joint_state_values) const;
00393
00394 void updateKinematicLinks();
00395
00396 bool updateKinematicStateWithLinkAt(const std::string& link_name, const btTransform& transform);
00397
00398 const boost::shared_ptr<const KinematicModel> getKinematicModel() const
00399 {
00400 return kinematic_model_;
00401 }
00402
00403 unsigned int getDimension() const {
00404 return dimension_;
00405 }
00406
00407 std::vector<LinkState*> getChildLinkStates(const std::string& link_name) const;
00408
00409 void setKinematicStateToDefault();
00410
00411 bool areJointsWithinBounds(const std::vector<std::string>& joints) const;
00412
00413 bool isJointWithinBounds(const std::string& joint) const;
00414
00416 const JointStateGroup* getJointStateGroup(const std::string &name) const;
00417
00419 JointStateGroup* getJointStateGroup(const std::string &name);
00420
00422 bool hasJointStateGroup(const std::string &name) const;
00423
00425 bool hasJointState(const std::string &joint) const;
00426
00428 bool hasLinkState(const std::string& joint) const;
00429
00431 JointState* getJointState(const std::string &joint) const;
00432
00434 LinkState* getLinkState(const std::string &link) const;
00435
00437 AttachedBodyState* getAttachedBodyState(const std::string &attached) const;
00438
00439 const std::vector<JointState*>& getJointStateVector() const
00440 {
00441 return joint_state_vector_;
00442 }
00443
00444 std::vector<JointState*>& getJointStateVector()
00445 {
00446 return joint_state_vector_;
00447 }
00448
00449 const std::vector<LinkState*>& getLinkStateVector() const
00450 {
00451 return link_state_vector_;
00452 }
00453
00454 const std::vector<const AttachedBodyState*>& getAttachedBodyStateVector() const
00455 {
00456 return attached_body_state_vector_;
00457 }
00458
00459 const std::map<std::string, JointStateGroup*>& getJointStateGroupMap() const
00460 {
00461 return joint_state_group_map_;
00462 }
00463
00464 void getJointStateGroupNames(std::vector<std::string>& names) const;
00465
00466 const std::map<std::string, unsigned int> getKinematicStateIndexMap() const
00467 {
00468 return kinematic_state_index_map_;
00469 }
00470
00472 void printStateInfo(std::ostream &out = std::cout) const;
00473
00475 void printTransforms(std::ostream &out = std::cout) const;
00476
00477 void printTransform(const std::string &st, const btTransform &t, std::ostream &out = std::cout) const;
00478
00479 private:
00480
00481 void setLinkStatesParents();
00482
00483 const boost::shared_ptr<const KinematicModel> kinematic_model_;
00484
00485 unsigned int dimension_;
00486 std::map<std::string, unsigned int> kinematic_state_index_map_;
00487
00488 std::vector<JointState*> joint_state_vector_;
00489 std::map<std::string, JointState*> joint_state_map_;
00490
00491 std::vector<LinkState*> link_state_vector_;
00492 std::map<std::string, LinkState*> link_state_map_;
00493
00494
00495 std::vector<const AttachedBodyState*> attached_body_state_vector_;
00496
00497 std::map<std::string, JointStateGroup*> joint_state_group_map_;
00498 };
00499
00500 }
00501
00502 #endif