floating_joint_model.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #ifndef MOVEIT_CORE_ROBOT_MODEL_FLOATING_JOINT_MODEL_
38 #define MOVEIT_CORE_ROBOT_MODEL_FLOATING_JOINT_MODEL_
39 
41 
42 namespace moveit
43 {
44 namespace core
45 {
48 {
49 public:
50  FloatingJointModel(const std::string& name);
51 
52  virtual void getVariableDefaultPositions(double* values, const Bounds& other_bounds) const;
53  virtual void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
54  const Bounds& other_bounds) const;
56  const Bounds& other_bounds, const double* near,
57  const double distance) const;
58  virtual bool enforcePositionBounds(double* values, const Bounds& other_bounds) const;
59  virtual bool satisfiesPositionBounds(const double* values, const Bounds& other_bounds, double margin) const;
60 
61  virtual void interpolate(const double* from, const double* to, const double t, double* state) const;
62  virtual unsigned int getStateSpaceDimension() const;
63  virtual double getMaximumExtent(const Bounds& other_bounds) const;
64  virtual double distance(const double* values1, const double* values2) const;
65 
66  virtual void computeTransform(const double* joint_values, Eigen::Affine3d& transf) const;
67  virtual void computeVariablePositions(const Eigen::Affine3d& transf, double* joint_values) const;
68 
69  double getAngularDistanceWeight() const
70  {
72  }
73 
74  void setAngularDistanceWeight(double weight)
75  {
76  angular_distance_weight_ = weight;
77  }
78 
81  bool normalizeRotation(double* values) const;
82 
84  double distanceRotation(const double* values1, const double* values2) const;
85 
87  double distanceTranslation(const double* values1, const double* values2) const;
88 
89 private:
91 };
92 }
93 }
94 
95 #endif
virtual bool satisfiesPositionBounds(const double *values, const Bounds &other_bounds, double margin) const
Check if the set of position values for the variables of this joint are within bounds, up to some margin.
virtual bool enforcePositionBounds(double *values, const Bounds &other_bounds) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi. Return true if changes were made.
double distanceRotation(const double *values1, const double *values2) const
Get the distance between the rotation components of two states.
double distanceTranslation(const double *values1, const double *values2) const
Get the distance between the translation components of two states.
virtual void computeTransform(const double *joint_values, Eigen::Affine3d &transf) const
Given the joint values for a joint, compute the corresponding transform.
virtual void getVariableDefaultPositions(double *values, const Bounds &other_bounds) const
Provide a default value for the joint given the joint variable bounds. Most joints will use the defau...
virtual unsigned int getStateSpaceDimension() const
Get the dimension of the state space that corresponds to this joint.
FloatingJointModel(const std::string &name)
double getMaximumExtent() const
Definition: joint_model.h:431
virtual void computeVariablePositions(const Eigen::Affine3d &transf, double *joint_values) const
Given the transform generated by joint, compute the corresponding joint values.
virtual void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
virtual void interpolate(const double *from, const double *to, const double t, double *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
virtual double distance(const double *values1, const double *values2) const
Compute the distance between two joint states of the same model (represented by the variable values) ...
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
Definition: joint_model.h:108
void setAngularDistanceWeight(double weight)
Main namespace for MoveIt!
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:123
virtual void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
bool normalizeRotation(double *values) const


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:05