joint_model.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * Copyright (c) 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan */
37 
38 #pragma once
39 
40 #include <string>
41 #include <vector>
42 #include <map>
43 #include <iostream>
44 #include <moveit_msgs/JointLimits.h>
46 #include <Eigen/Geometry>
47 
48 namespace moveit
49 {
50 namespace core
51 {
52 struct VariableBounds
53 {
55  : min_position_(0.0)
56  , max_position_(0.0)
57  , position_bounded_(false)
58  , min_velocity_(0.0)
59  , max_velocity_(0.0)
60  , velocity_bounded_(false)
61  , min_acceleration_(0.0)
62  , max_acceleration_(0.0)
63  , acceleration_bounded_(false)
64  {
65  }
66 
67  double min_position_;
68  double max_position_;
69  bool position_bounded_;
70 
71  double min_velocity_;
72  double max_velocity_;
73  bool velocity_bounded_;
74 
75  double min_acceleration_;
76  double max_acceleration_;
78 };
79 
80 class LinkModel;
81 class JointModel;
82 
84 typedef std::map<std::string, int> VariableIndexMap;
85 
87 using VariableBoundsMap = std::map<std::string, VariableBounds>;
88 
90 using JointModelMap = std::map<std::string, JointModel*>;
91 
93 using JointModelMapConst = std::map<std::string, const JointModel*>;
94 
107 class JointModel
108 {
109 public:
111  enum JointType
112  {
113  UNKNOWN,
114  REVOLUTE,
115  PRISMATIC,
116  PLANAR,
117  FLOATING,
119  };
120 
122  using Bounds = std::vector<VariableBounds>;
123 
125  JointModel(const std::string& name);
126 
127  virtual ~JointModel();
128 
130  const std::string& getName() const
131  {
132  return name_;
133  }
134 
136  JointType getType() const
137  {
138  return type_;
139  }
140 
142  std::string getTypeName() const;
143 
148  {
149  return parent_link_model_;
150  }
151 
154  {
155  return child_link_model_;
156  }
157 
158  void setParentLinkModel(const LinkModel* link)
159  {
160  parent_link_model_ = link;
161  }
162 
163  void setChildLinkModel(const LinkModel* link)
164  {
165  child_link_model_ = link;
166  }
167 
175  const std::vector<std::string>& getVariableNames() const
176  {
178  }
179 
183  const std::vector<std::string>& getLocalVariableNames() const
184  {
185  return local_variable_names_;
186  }
187 
189  bool hasVariable(const std::string& variable) const
190  {
191  return variable_index_map_.find(variable) != variable_index_map_.end();
192  }
193 
195  std::size_t getVariableCount() const
196  {
197  return variable_names_.size();
198  }
199 
201  int getFirstVariableIndex() const
202  {
203  return first_variable_index_;
204  }
205 
207  void setFirstVariableIndex(int index)
208  {
210  }
211 
213  int getJointIndex() const
214  {
215  return joint_index_;
216  }
217 
219  void setJointIndex(int index)
220  {
222  }
223 
225  int getLocalVariableIndex(const std::string& variable) const;
226 
235  void getVariableDefaultPositions(double* values) const
236  {
238  }
239 
243  virtual void getVariableDefaultPositions(double* values, const Bounds& other_bounds) const = 0;
244 
248  {
250  }
251 
254  virtual void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
255  const Bounds& other_bounds) const = 0;
256 
259  void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values, const double* seed,
260  const double distance) const
261  {
263  }
264 
268  const Bounds& other_bounds, const double* seed,
269  const double distance) const = 0;
270 
277  bool satisfiesPositionBounds(const double* values, double margin = 0.0) const
278  {
279  return satisfiesPositionBounds(values, variable_bounds_, margin);
280  }
281 
284  virtual bool satisfiesPositionBounds(const double* values, const Bounds& other_bounds, double margin) const = 0;
285 
289  bool enforcePositionBounds(double* values) const
290  {
292  }
293 
297  virtual bool enforcePositionBounds(double* values, const Bounds& other_bounds) const = 0;
298 
301  virtual bool harmonizePosition(double* values, const Bounds& other_bounds) const;
302  bool harmonizePosition(double* values) const
303  {
304  return harmonizePosition(values, variable_bounds_);
305  }
306 
308  bool satisfiesVelocityBounds(const double* values, double margin = 0.0) const
309  {
310  return satisfiesVelocityBounds(values, variable_bounds_, margin);
311  }
312 
314  virtual bool satisfiesVelocityBounds(const double* values, const Bounds& other_bounds, double margin) const;
315 
317  bool enforceVelocityBounds(double* values) const
318  {
319  return enforceVelocityBounds(values, variable_bounds_);
320  }
321 
323  virtual bool enforceVelocityBounds(double* values, const Bounds& other_bounds) const;
324 
326  bool satisfiesAccelerationBounds(const double* values, double margin = 0.0) const
327  {
328  return satisfiesAccelerationBounds(values, variable_bounds_, margin);
329  }
330 
332  virtual bool satisfiesAccelerationBounds(const double* values, const Bounds& other_bounds, double margin) const;
333 
335  const VariableBounds& getVariableBounds(const std::string& variable) const;
336 
338  const Bounds& getVariableBounds() const
339  {
340  return variable_bounds_;
341  }
342 
344  void setVariableBounds(const std::string& variable, const VariableBounds& bounds);
345 
347  void setVariableBounds(const std::vector<moveit_msgs::JointLimits>& jlim);
348 
350  const std::vector<moveit_msgs::JointLimits>& getVariableBoundsMsg() const
351  {
352  return variable_bounds_msg_;
353  }
354 
358  virtual double distance(const double* value1, const double* value2) const = 0;
359 
362  double getDistanceFactor() const
363  {
364  return distance_factor_;
365  }
366 
369  void setDistanceFactor(double factor)
370  {
371  distance_factor_ = factor;
372  }
373 
375  virtual unsigned int getStateSpaceDimension() const = 0;
376 
378  const JointModel* getMimic() const
379  {
380  return mimic_;
381  }
382 
384  double getMimicOffset() const
385  {
386  return mimic_offset_;
387  }
388 
390  double getMimicFactor() const
391  {
393  }
394 
396  void setMimic(const JointModel* mimic, double factor, double offset);
397 
399  const std::vector<const JointModel*>& getMimicRequests() const
400  {
401  return mimic_requests_;
402  }
403 
405  void addMimicRequest(const JointModel* joint);
406  void addDescendantJointModel(const JointModel* joint);
407  void addDescendantLinkModel(const LinkModel* link);
408 
410  const std::vector<const LinkModel*>& getDescendantLinkModels() const
411  {
413  }
414 
416  const std::vector<const JointModel*>& getDescendantJointModels() const
417  {
419  }
420 
422  const std::vector<const JointModel*>& getNonFixedDescendantJointModels() const
423  {
425  }
426 
428  bool isPassive() const
429  {
430  return passive_;
431  }
432 
433  void setPassive(bool flag)
434  {
435  passive_ = flag;
436  }
437 
442  virtual void interpolate(const double* from, const double* to, const double t, double* state) const = 0;
443 
445  virtual double getMaximumExtent(const Bounds& other_bounds) const = 0;
446 
447  double getMaximumExtent() const
448  {
450  }
451 
457  virtual void computeTransform(const double* joint_values, Eigen::Isometry3d& transf) const = 0;
458 
461  virtual void computeVariablePositions(const Eigen::Isometry3d& transform, double* joint_values) const = 0;
462 
465 protected:
467 
469  std::string name_;
470 
473 
475  std::vector<std::string> local_variable_names_;
476 
478  std::vector<std::string> variable_names_;
479 
482 
483  std::vector<moveit_msgs::JointLimits> variable_bounds_msg_;
484 
488 
491 
494 
496  const JointModel* mimic_;
497 
500 
502  double mimic_offset_;
503 
505  std::vector<const JointModel*> mimic_requests_;
506 
508  std::vector<const LinkModel*> descendant_link_models_;
509 
511  std::vector<const JointModel*> descendant_joint_models_;
512 
515  std::vector<const JointModel*> non_fixed_descendant_joint_models_;
516 
518  bool passive_;
519 
521  double distance_factor_;
522 
525 
527  int joint_index_;
528 };
529 
531 std::ostream& operator<<(std::ostream& out, const VariableBounds& b);
532 } // namespace core
533 } // namespace moveit
moveit::core::LinkModel
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:71
moveit::core::JointModel::getNonFixedDescendantJointModels
const std::vector< const JointModel * > & getNonFixedDescendantJointModels() const
Get all the non-fixed joint models that descend from this joint, in the kinematic tree.
Definition: joint_model.h:488
random_numbers.h
moveit::core::JointModel::distance_factor_
double distance_factor_
The factor applied to the distance between two joint states.
Definition: joint_model.h:587
moveit::core::VariableBoundsMap
std::map< std::string, VariableBounds > VariableBoundsMap
Data type for holding mappings from variable names to their bounds.
Definition: joint_model.h:153
moveit::core::JointModel::enforcePositionBounds
bool enforcePositionBounds(double *values) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
Definition: joint_model.h:355
moveit::core::JointModel::descendant_link_models_
std::vector< const LinkModel * > descendant_link_models_
Pointers to all the links that will be moved if this joint changes value.
Definition: joint_model.h:574
moveit::core::JointModel::getVariableBounds
const Bounds & getVariableBounds() const
Get the variable bounds for this joint, in the same order as the names returned by getVariableNames()
Definition: joint_model.h:404
moveit::core::JointModel::getLocalVariableIndex
int getLocalVariableIndex(const std::string &variable) const
Get the index of the variable within this joint.
Definition: joint_model.cpp:151
moveit::core::operator<<
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
Definition: joint_model.cpp:309
moveit::core::JointModel::getVariableBoundsMsg
const std::vector< moveit_msgs::JointLimits > & getVariableBoundsMsg() const
Get the joint limits known to this model, as a message.
Definition: joint_model.h:416
moveit::core::JointModel::getVariableCount
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:261
moveit::core::JointModel::computeVariableBoundsMsg
void computeVariableBoundsMsg()
Definition: joint_model.cpp:253
moveit::core::JointModel::getMimicOffset
double getMimicOffset() const
If mimicking a joint, this is the offset added to that joint's value.
Definition: joint_model.h:450
moveit::core::JointModel::parent_link_model_
const LinkModel * parent_link_model_
The link before this joint.
Definition: joint_model.h:556
moveit::core::JointModel::enforceVelocityBounds
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
Definition: joint_model.h:383
moveit::core::JointModel::PLANAR
@ PLANAR
Definition: joint_model.h:182
moveit::core::JointModel::getVariableDefaultPositions
void getVariableDefaultPositions(double *values) const
Provide a default value for the joint given the default joint variable bounds (maintained internally)...
Definition: joint_model.h:301
moveit::core::VariableBounds
Definition: joint_model.h:118
moveit::core::JointModel::getDistanceFactor
double getDistanceFactor() const
Get the factor that should be applied to the value returned by distance() when that value is used in ...
Definition: joint_model.h:428
moveit::core::JointModel::getVariableRandomPositionsNearBy
void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const double *seed, const double distance) const
Provide random values for the joint variables (within default bounds). Enough memory is assumed to be...
Definition: joint_model.h:325
moveit::core::VariableBounds::max_position_
double max_position_
Definition: joint_model.h:167
moveit::core::JointModel::getDescendantLinkModels
const std::vector< const LinkModel * > & getDescendantLinkModels() const
Get all the link models that descend from this joint, in the kinematic tree.
Definition: joint_model.h:476
moveit::core::JointModel::joint_index_
int joint_index_
Index for this joint in the array of joints of the complete model.
Definition: joint_model.h:593
moveit::core::JointModel::interpolate
virtual void interpolate(const double *from, const double *to, const double t, double *state) const =0
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
moveit::core::JointModel::setFirstVariableIndex
void setFirstVariableIndex(int index)
Set the index of this joint's first variable within the full robot state.
Definition: joint_model.h:273
moveit::core::VariableIndexMap
std::map< std::string, int > VariableIndexMap
Data type for holding mappings from variable names to their position in a state vector.
Definition: joint_model.h:147
moveit::core::JointModel::variable_index_map_
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
Definition: joint_model.h:553
moveit::core::JointModel::hasVariable
bool hasVariable(const std::string &variable) const
Check if a particular variable is known to this joint.
Definition: joint_model.h:255
moveit::core::JointModel::getName
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:196
moveit::core::JointModel::getMimicFactor
double getMimicFactor() const
If mimicking a joint, this is the multiplicative factor for that joint's value.
Definition: joint_model.h:456
moveit::core::JointModel::first_variable_index_
int first_variable_index_
The index of this joint's first variable, in the complete robot state.
Definition: joint_model.h:590
moveit::core::JointModel::addDescendantLinkModel
void addDescendantLinkModel(const LinkModel *link)
Definition: joint_model.cpp:291
moveit::core::VariableBounds::min_position_
double min_position_
Definition: joint_model.h:166
moveit::core::JointModel::PRISMATIC
@ PRISMATIC
Definition: joint_model.h:181
moveit::core::JointModel::passive_
bool passive_
Specify whether this joint is marked as passive in the SRDF.
Definition: joint_model.h:584
moveit::core::JointModel::descendant_joint_models_
std::vector< const JointModel * > descendant_joint_models_
Pointers to all the joints that follow this one in the kinematic tree (including mimic joints)
Definition: joint_model.h:577
moveit::core::JointModel::setVariableBounds
void setVariableBounds(const std::string &variable, const VariableBounds &bounds)
Set the lower and upper bounds for a variable. Throw an exception if the variable was not found.
Definition: joint_model.cpp:218
moveit::core::JointModel::getType
JointType getType() const
Get the type of joint.
Definition: joint_model.h:202
moveit::core::JointModel::setParentLinkModel
void setParentLinkModel(const LinkModel *link)
Definition: joint_model.h:224
moveit::core::JointModel::REVOLUTE
@ REVOLUTE
Definition: joint_model.h:180
moveit::core::JointModel::getChildLinkModel
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
Definition: joint_model.h:219
moveit::core::JointModel::getParentLinkModel
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
Definition: joint_model.h:213
moveit::core::JointModelMap
std::map< std::string, JointModel * > JointModelMap
Map of names to instances for JointModel.
Definition: joint_model.h:156
moveit::core::VariableBounds::max_velocity_
double max_velocity_
Definition: joint_model.h:171
moveit::core::JointModel::getMaximumExtent
double getMaximumExtent() const
Definition: joint_model.h:513
moveit::core::JointModel::setMimic
void setMimic(const JointModel *mimic, double factor, double offset)
Mark this joint as mimicking mimic using factor and offset.
Definition: joint_model.cpp:272
moveit::core::JointModel::Bounds
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:188
moveit::core::JointModel::setPassive
void setPassive(bool flag)
Definition: joint_model.h:499
moveit::core::JointModel::getFirstVariableIndex
int getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
Definition: joint_model.h:267
moveit::core::JointModel::getMimicRequests
const std::vector< const JointModel * > & getMimicRequests() const
The joint models whose values would be modified if the value of this joint changed.
Definition: joint_model.h:465
moveit::core::JointModel::setChildLinkModel
void setChildLinkModel(const LinkModel *link)
Definition: joint_model.h:229
moveit::core::JointModel::variable_bounds_msg_
std::vector< moveit_msgs::JointLimits > variable_bounds_msg_
Definition: joint_model.h:549
moveit::core::JointModel::variable_bounds_
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
Definition: joint_model.h:547
moveit::core::VariableBounds::min_velocity_
double min_velocity_
Definition: joint_model.h:170
moveit::core::VariableBounds::VariableBounds
VariableBounds()
Definition: joint_model.h:153
moveit::core::JointModel::variable_names_
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
Definition: joint_model.h:544
moveit::core::JointModel::UNKNOWN
@ UNKNOWN
Definition: joint_model.h:179
moveit::core::JointModel::getStateSpaceDimension
virtual unsigned int getStateSpaceDimension() const =0
Get the dimension of the state space that corresponds to this joint.
moveit::core::JointModel::getJointIndex
int getJointIndex() const
Get the index of this joint within the robot model.
Definition: joint_model.h:279
moveit::core::JointModel::satisfiesAccelerationBounds
bool satisfiesAccelerationBounds(const double *values, double margin=0.0) const
Check if the set of accelerations for the variables of this joint are within bounds.
Definition: joint_model.h:392
moveit::core::JointModel::getLocalVariableNames
const std::vector< std::string > & getLocalVariableNames() const
Get the local names of the variable that make up the joint (suffixes that are attached to joint names...
Definition: joint_model.h:249
moveit::core::JointModel::JointType
JointType
The different types of joints we support.
Definition: joint_model.h:177
random_numbers::RandomNumberGenerator
moveit::core::JointModel::~JointModel
virtual ~JointModel()
moveit::core::JointModel::setDistanceFactor
void setDistanceFactor(double factor)
Set the factor that should be applied to the value returned by distance() when that value is used in ...
Definition: joint_model.h:435
moveit::core::JointModel::harmonizePosition
virtual bool harmonizePosition(double *values, const Bounds &other_bounds) const
Definition: joint_model.cpp:159
moveit::core::JointModel::computeTransform
virtual void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
moveit
Main namespace for MoveIt.
Definition: background_processing.h:46
values
std::vector< double > values
moveit::core::JointModel::JointModel
JointModel(const std::string &name)
Construct a joint named name.
Definition: joint_model.cpp:113
moveit::core::JointModel::getTypeName
std::string getTypeName() const
Get the type of joint as a string.
Definition: joint_model.cpp:130
moveit::core::JointModel::getMimic
const JointModel * getMimic() const
Get the joint this one is mimicking.
Definition: joint_model.h:444
moveit::core::JointModel::mimic_
const JointModel * mimic_
The joint this one mimics (NULL for joints that do not mimic)
Definition: joint_model.h:562
moveit::core::JointModel::type_
JointType type_
The type of joint.
Definition: joint_model.h:538
moveit::core::JointModel::local_variable_names_
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
Definition: joint_model.h:541
moveit::core::JointModel::name_
std::string name_
Name of the joint.
Definition: joint_model.h:535
moveit::core::JointModel::mimic_offset_
double mimic_offset_
The multiplier to the mimic joint.
Definition: joint_model.h:568
moveit::core::VariableBounds::acceleration_bounded_
bool acceleration_bounded_
Definition: joint_model.h:176
moveit::core::JointModelMapConst
std::map< std::string, const JointModel * > JointModelMapConst
Map of names to const instances for JointModel.
Definition: joint_model.h:159
moveit::core::JointModel::distance
virtual double distance(const double *value1, const double *value2) const =0
Compute the distance between two joint states of the same model (represented by the variable values)
index
unsigned int index
moveit::core::VariableBounds::velocity_bounded_
bool velocity_bounded_
Definition: joint_model.h:172
moveit::core::JointModel::addDescendantJointModel
void addDescendantJointModel(const JointModel *joint)
Definition: joint_model.cpp:284
moveit::core::JointModel::mimic_factor_
double mimic_factor_
The offset to the mimic joint.
Definition: joint_model.h:565
moveit::core::JointModel::addMimicRequest
void addMimicRequest(const JointModel *joint)
Notify this joint that there is another joint that mimics it.
Definition: joint_model.cpp:279
moveit::core::JointModel::getDescendantJointModels
const std::vector< const JointModel * > & getDescendantJointModels() const
Get all the joint models that descend from this joint, in the kinematic tree.
Definition: joint_model.h:482
moveit::core::JointModel::mimic_requests_
std::vector< const JointModel * > mimic_requests_
The set of joints that should get a value copied to them when this joint changes.
Definition: joint_model.h:571
moveit::core::JointModel::FLOATING
@ FLOATING
Definition: joint_model.h:183
moveit::core::VariableBounds::position_bounded_
bool position_bounded_
Definition: joint_model.h:168
moveit::core::JointModel::setJointIndex
void setJointIndex(int index)
Set the index of this joint within the robot model.
Definition: joint_model.h:285
moveit::core::JointModel::getVariableRandomPositions
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Provide random values for the joint variables (within default bounds). Enough memory is assumed to be...
Definition: joint_model.h:313
moveit::core::JointModel::FIXED
@ FIXED
Definition: joint_model.h:184
moveit::core::JointModel::satisfiesVelocityBounds
bool satisfiesVelocityBounds(const double *values, double margin=0.0) const
Check if the set of velocities for the variables of this joint are within bounds.
Definition: joint_model.h:374
moveit::core::JointModel::satisfiesPositionBounds
bool satisfiesPositionBounds(const double *values, double margin=0.0) const
Check if the set of values for the variables of this joint are within bounds.
Definition: joint_model.h:343
moveit::core::VariableBounds::max_acceleration_
double max_acceleration_
Definition: joint_model.h:175
moveit::core::JointModel::computeVariablePositions
virtual void computeVariablePositions(const Eigen::Isometry3d &transform, double *joint_values) const =0
Given the transform generated by joint, compute the corresponding joint values. Make sure the passed ...
moveit::core::JointModel::isPassive
bool isPassive() const
Check if this joint is passive.
Definition: joint_model.h:494
moveit::core::VariableBounds::min_acceleration_
double min_acceleration_
Definition: joint_model.h:174
moveit::core::JointModel
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:173
moveit::core::JointModel::child_link_model_
const LinkModel * child_link_model_
The link after this joint.
Definition: joint_model.h:559
moveit::core::JointModel::non_fixed_descendant_joint_models_
std::vector< const JointModel * > non_fixed_descendant_joint_models_
Pointers to all the joints that follow this one in the kinematic tree, including mimic joints,...
Definition: joint_model.h:581
moveit::core::JointModel::getVariableNames
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up this joint, in the order they appear in corresponding sta...
Definition: joint_model.h:241


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Mar 3 2024 03:23:35