moveit2
The MoveIt Motion Planning Framework for ROS 2.
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/msg/joint_limits.hpp>
45 #include <random_numbers/random_numbers.h>
46 #include <Eigen/Geometry>
47 
48 #undef near
49 
50 namespace moveit
51 {
52 namespace core
53 {
55 {
57  : min_position_(0.0)
58  , max_position_(0.0)
59  , position_bounded_(false)
60  , min_velocity_(0.0)
61  , max_velocity_(0.0)
62  , velocity_bounded_(false)
63  , min_acceleration_(0.0)
64  , max_acceleration_(0.0)
65  , acceleration_bounded_(false)
66  , min_jerk_(0.0)
67  , max_jerk_(0.0)
68  , jerk_bounded_(false)
69  {
70  }
71 
72  double min_position_;
73  double max_position_;
75 
76  double min_velocity_;
77  double max_velocity_;
79 
83 
84  double min_jerk_;
85  double max_jerk_;
87 };
88 
89 class LinkModel;
90 class JointModel;
91 
93 typedef std::map<std::string, size_t> VariableIndexMap;
94 
96 using VariableBoundsMap = std::map<std::string, VariableBounds>;
97 
99 using JointModelMap = std::map<std::string, JointModel*>;
100 
102 using JointModelMapConst = std::map<std::string, const JointModel*>;
103 
117 {
118 public:
121  {
127  FIXED
128  };
129 
131  using Bounds = std::vector<VariableBounds>;
132 
140  JointModel(const std::string& name, size_t joint_index, size_t first_variable_index);
141 
142  virtual ~JointModel();
143 
145  const std::string& getName() const
146  {
147  return name_;
148  }
149 
152  {
153  return type_;
154  }
155 
157  std::string getTypeName() const;
158 
163  {
164  return parent_link_model_;
165  }
166 
169  {
170  return child_link_model_;
171  }
172 
173  void setParentLinkModel(const LinkModel* link)
174  {
175  parent_link_model_ = link;
176  }
177 
178  void setChildLinkModel(const LinkModel* link)
179  {
180  child_link_model_ = link;
181  }
182 
190  const std::vector<std::string>& getVariableNames() const
191  {
192  return variable_names_;
193  }
194 
198  const std::vector<std::string>& getLocalVariableNames() const
199  {
200  return local_variable_names_;
201  }
202 
204  bool hasVariable(const std::string& variable) const
205  {
206  return variable_index_map_.find(variable) != variable_index_map_.end();
207  }
208 
210  std::size_t getVariableCount() const
211  {
212  return variable_names_.size();
213  }
214 
216  size_t getFirstVariableIndex() const
217  {
218  return first_variable_index_;
219  }
220 
222  size_t getJointIndex() const
223  {
224  return joint_index_;
225  }
226 
228  size_t getLocalVariableIndex(const std::string& variable) const;
229 
238  void getVariableDefaultPositions(double* values) const
239  {
241  }
242 
246  virtual void getVariableDefaultPositions(double* values, const Bounds& other_bounds) const = 0;
247 
250  void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values) const
251  {
253  }
254 
257  virtual void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
258  const Bounds& other_bounds) const = 0;
259 
262  void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values, const double* near,
263  const double distance) const
264  {
266  }
267 
270  virtual void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
271  const Bounds& other_bounds, const double* near,
272  const double distance) const = 0;
273 
280  bool satisfiesPositionBounds(const double* values, double margin = 0.0) const
281  {
282  return satisfiesPositionBounds(values, variable_bounds_, margin);
283  }
284 
287  virtual bool satisfiesPositionBounds(const double* values, const Bounds& other_bounds, double margin) const = 0;
288 
292  bool enforcePositionBounds(double* values) const
293  {
294  return enforcePositionBounds(values, variable_bounds_);
295  }
296 
300  virtual bool enforcePositionBounds(double* values, const Bounds& other_bounds) const = 0;
301 
304  virtual bool harmonizePosition(double* values, const Bounds& other_bounds) const;
305  bool harmonizePosition(double* values) const
306  {
307  return harmonizePosition(values, variable_bounds_);
308  }
309 
311  bool satisfiesVelocityBounds(const double* values, double margin = 0.0) const
312  {
313  return satisfiesVelocityBounds(values, variable_bounds_, margin);
314  }
315 
317  virtual bool satisfiesVelocityBounds(const double* values, const Bounds& other_bounds, double margin) const;
318 
320  bool enforceVelocityBounds(double* values) const
321  {
322  return enforceVelocityBounds(values, variable_bounds_);
323  }
324 
326  virtual bool enforceVelocityBounds(double* values, const Bounds& other_bounds) const;
327 
329  const VariableBounds& getVariableBounds(const std::string& variable) const;
330 
332  const Bounds& getVariableBounds() const
333  {
334  return variable_bounds_;
335  }
336 
338  void setVariableBounds(const std::string& variable, const VariableBounds& bounds);
339 
341  void setVariableBounds(const std::vector<moveit_msgs::msg::JointLimits>& jlim);
342 
344  const std::vector<moveit_msgs::msg::JointLimits>& getVariableBoundsMsg() const
345  {
346  return variable_bounds_msg_;
347  }
348 
352  virtual double distance(const double* value1, const double* value2) const = 0;
353 
356  double getDistanceFactor() const
357  {
358  return distance_factor_;
359  }
360 
363  void setDistanceFactor(double factor)
364  {
365  distance_factor_ = factor;
366  }
367 
369  virtual unsigned int getStateSpaceDimension() const = 0;
370 
372  const JointModel* getMimic() const
373  {
374  return mimic_;
375  }
376 
378  double getMimicOffset() const
379  {
380  return mimic_offset_;
381  }
382 
384  double getMimicFactor() const
385  {
386  return mimic_factor_;
387  }
388 
390  void setMimic(const JointModel* mimic, double factor, double offset);
391 
393  const std::vector<const JointModel*>& getMimicRequests() const
394  {
395  return mimic_requests_;
396  }
397 
399  void addMimicRequest(const JointModel* joint);
400  void addDescendantJointModel(const JointModel* joint);
401  void addDescendantLinkModel(const LinkModel* link);
402 
404  const std::vector<const LinkModel*>& getDescendantLinkModels() const
405  {
407  }
408 
410  const std::vector<const JointModel*>& getDescendantJointModels() const
411  {
413  }
414 
416  const std::vector<const JointModel*>& getNonFixedDescendantJointModels() const
417  {
419  }
420 
422  bool isPassive() const
423  {
424  return passive_;
425  }
426 
427  void setPassive(bool flag)
428  {
429  passive_ = flag;
430  }
431 
436  virtual void interpolate(const double* from, const double* to, const double t, double* state) const = 0;
437 
439  virtual double getMaximumExtent(const Bounds& other_bounds) const = 0;
440 
441  double getMaximumExtent() const
442  {
444  }
445 
451  virtual void computeTransform(const double* joint_values, Eigen::Isometry3d& transf) const = 0;
452 
455  virtual void computeVariablePositions(const Eigen::Isometry3d& transform, double* joint_values) const = 0;
456 
459 private:
461  std::string name_;
462 
464  size_t joint_index_;
465 
467  size_t first_variable_index_;
468 
469 protected:
471 
474 
476  std::vector<std::string> local_variable_names_;
477 
479  std::vector<std::string> variable_names_;
480 
483 
484  std::vector<moveit_msgs::msg::JointLimits> variable_bounds_msg_;
485 
489 
492 
495 
498 
501 
504 
506  std::vector<const JointModel*> mimic_requests_;
507 
509  std::vector<const LinkModel*> descendant_link_models_;
510 
512  std::vector<const JointModel*> descendant_joint_models_;
513 
516  std::vector<const JointModel*> non_fixed_descendant_joint_models_;
517 
519  bool passive_;
520 
523 };
524 
526 std::ostream& operator<<(std::ostream& out, const VariableBounds& b);
527 } // namespace core
528 } // namespace moveit
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
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:162
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:190
void addMimicRequest(const JointModel *joint)
Notify this joint that there is another joint that mimics it.
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:311
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:356
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
Definition: joint_model.h:488
double getMimicFactor() const
If mimicking a joint, this is the multiplicative factor for that joint's value.
Definition: joint_model.h:384
size_t getLocalVariableIndex(const std::string &variable) const
Get the index of the variable within this joint.
Definition: joint_model.cpp:85
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:198
const JointModel * mimic_
The joint this one mimics (nullptr for joints that do not mimic)
Definition: joint_model.h:497
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 ...
void setChildLinkModel(const LinkModel *link)
Definition: joint_model.h:178
JointType type_
The type of joint.
Definition: joint_model.h:473
size_t getJointIndex() const
Get the index of this joint within the robot model.
Definition: joint_model.h:222
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
Definition: joint_model.h:168
virtual void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const =0
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
virtual unsigned int getStateSpaceDimension() const =0
Get the dimension of the state space that corresponds to this joint.
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
Definition: joint_model.h:482
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.
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:512
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:131
virtual bool enforcePositionBounds(double *values, const Bounds &other_bounds) const =0
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
double mimic_offset_
The multiplier to the mimic joint.
Definition: joint_model.h:503
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:506
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:363
virtual void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const =0
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
double mimic_factor_
The offset to the mimic joint.
Definition: joint_model.h:500
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:516
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:332
JointType
The different types of joints we support.
Definition: joint_model.h:121
const std::vector< moveit_msgs::msg::JointLimits > & getVariableBoundsMsg() const
Get the joint limits known to this model, as a message.
Definition: joint_model.h:344
JointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
Constructs a joint named name.
Definition: joint_model.cpp:47
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
Definition: joint_model.h:216
virtual bool harmonizePosition(double *values, const Bounds &other_bounds) const
Definition: joint_model.cpp:93
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....
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:250
void getVariableDefaultPositions(double *values) const
Provide a default value for the joint given the default joint variable bounds (maintained internally)...
Definition: joint_model.h:238
std::vector< moveit_msgs::msg::JointLimits > variable_bounds_msg_
Definition: joint_model.h:484
bool hasVariable(const std::string &variable) const
Check if a particular variable is known to this joint.
Definition: joint_model.h:204
bool passive_
Specify whether this joint is marked as passive in the SRDF.
Definition: joint_model.h:519
const LinkModel * parent_link_model_
The link before this joint.
Definition: joint_model.h:491
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:210
void addDescendantJointModel(const JointModel *joint)
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
double getMimicOffset() const
If mimicking a joint, this is the offset added to that joint's value.
Definition: joint_model.h:378
void setParentLinkModel(const LinkModel *link)
Definition: joint_model.h:173
void setMimic(const JointModel *mimic, double factor, double offset)
Mark this joint as mimicking mimic using factor and offset.
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:404
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)
virtual double getMaximumExtent(const Bounds &other_bounds) const =0
Get the extent of the state space (the maximum value distance() can ever report)
bool isPassive() const
Check if this joint is passive.
Definition: joint_model.h:422
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
Definition: joint_model.h:320
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
Definition: joint_model.h:476
double distance_factor_
The factor applied to the distance between two joint states.
Definition: joint_model.h:522
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...
bool enforcePositionBounds(double *values) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
Definition: joint_model.h:292
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:280
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:410
double getMaximumExtent() const
Definition: joint_model.h:441
bool harmonizePosition(double *values) const
Definition: joint_model.h:305
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:393
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:509
void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const double *near, const double distance) const
Provide random values for the joint variables (within default bounds). Enough memory is assumed to be...
Definition: joint_model.h:262
JointType getType() const
Get the type of joint.
Definition: joint_model.h:151
virtual bool satisfiesPositionBounds(const double *values, const Bounds &other_bounds, double margin) const =0
Check if the set of position values for the variables of this joint are within bounds,...
virtual void getVariableDefaultPositions(double *values, const Bounds &other_bounds) const =0
Provide a default value for the joint given the joint variable bounds. Most joints will use the defau...
void setPassive(bool flag)
Definition: joint_model.h:427
const JointModel * getMimic() const
Get the joint this one is mimicking.
Definition: joint_model.h:372
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:416
std::string getTypeName() const
Get the type of joint as a string.
Definition: joint_model.cpp:64
void addDescendantLinkModel(const LinkModel *link)
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
Definition: joint_model.h:479
const LinkModel * child_link_model_
The link after this joint.
Definition: joint_model.h:494
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
std::map< std::string, VariableBounds > VariableBoundsMap
Data type for holding mappings from variable names to their bounds.
Definition: joint_model.h:96
std::map< std::string, size_t > VariableIndexMap
Data type for holding mappings from variable names to their position in a state vector.
Definition: joint_model.h:90
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
std::map< std::string, const JointModel * > JointModelMapConst
Map of names to const instances for JointModel.
Definition: joint_model.h:102
std::map< std::string, JointModel * > JointModelMap
Map of names to instances for JointModel.
Definition: joint_model.h:99
Main namespace for MoveIt.
Definition: exceptions.h:43
name
Definition: setup.py:7