moveit2
The MoveIt Motion Planning Framework for ROS 2.
prismatic_joint_model.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, 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 the Willow Garage 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 
38 #include <limits>
39 
40 namespace moveit
41 {
42 namespace core
43 {
44 PrismaticJointModel::PrismaticJointModel(const std::string& name, size_t joint_index, size_t first_variable_index)
45  : JointModel(name, joint_index, first_variable_index), axis_(0.0, 0.0, 0.0)
46 {
47  type_ = PRISMATIC;
48  variable_names_.push_back(getName());
49  variable_bounds_.resize(1);
50  variable_bounds_[0].position_bounded_ = true;
51  variable_bounds_[0].min_position_ = -std::numeric_limits<double>::max();
52  variable_bounds_[0].max_position_ = std::numeric_limits<double>::max();
55 }
56 
58 {
59  return 1;
60 }
61 
62 double PrismaticJointModel::getMaximumExtent(const Bounds& other_bounds) const
63 {
64  return variable_bounds_[0].max_position_ - other_bounds[0].min_position_;
65 }
66 
67 void PrismaticJointModel::getVariableDefaultPositions(double* values, const Bounds& bounds) const
68 {
69  // if zero is a valid value
70  if (bounds[0].min_position_ <= 0.0 && bounds[0].max_position_ >= 0.0)
71  values[0] = 0.0;
72  else
73  values[0] = (bounds[0].min_position_ + bounds[0].max_position_) / 2.0;
74 }
75 
76 bool PrismaticJointModel::satisfiesPositionBounds(const double* values, const Bounds& bounds, double margin) const
77 {
78  return !(values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin);
79 }
80 
81 void PrismaticJointModel::getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
82  const Bounds& bounds) const
83 {
84  values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
85 }
86 
87 void PrismaticJointModel::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
88  const Bounds& bounds, const double* near,
89  const double distance) const
90 {
91  values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
92  std::min(bounds[0].max_position_, near[0] + distance));
93 }
94 
95 bool PrismaticJointModel::enforcePositionBounds(double* values, const Bounds& bounds) const
96 {
97  if (values[0] < bounds[0].min_position_)
98  {
99  values[0] = bounds[0].min_position_;
100  return true;
101  }
102  else if (values[0] > bounds[0].max_position_)
103  {
104  values[0] = bounds[0].max_position_;
105  return true;
106  }
107  return false;
108 }
109 
110 double PrismaticJointModel::distance(const double* values1, const double* values2) const
111 {
112  return fabs(values1[0] - values2[0]);
113 }
114 
115 void PrismaticJointModel::interpolate(const double* from, const double* to, const double t, double* state) const
116 {
117  state[0] = from[0] + (to[0] - from[0]) * t;
118 }
119 
120 void PrismaticJointModel::computeTransform(const double* joint_values, Eigen::Isometry3d& transf) const
121 {
122  double* d = transf.data();
123  d[0] = 1.0;
124  d[1] = 0.0;
125  d[2] = 0.0;
126  d[3] = 0.0;
127 
128  d[4] = 0.0;
129  d[5] = 1.0;
130  d[6] = 0.0;
131  d[7] = 0.0;
132 
133  d[8] = 0.0;
134  d[9] = 0.0;
135  d[10] = 1.0;
136  d[11] = 0.0;
137 
138  d[12] = axis_.x() * joint_values[0];
139  d[13] = axis_.y() * joint_values[0];
140  d[14] = axis_.z() * joint_values[0];
141  d[15] = 1.0;
142 
143  // transf.setIdentity();
144  // transf.translation() = Eigen::Vector3d(axis_ * joint_values[0]);
145 }
146 
147 void PrismaticJointModel::computeVariablePositions(const Eigen::Isometry3d& transf, double* joint_values) const
148 {
149  joint_values[0] = transf.translation().dot(axis_);
150 }
151 
152 } // end of namespace core
153 } // end of namespace moveit
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
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
JointType type_
The type of joint.
Definition: joint_model.h:473
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
Definition: joint_model.h:482
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:131
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
double getMaximumExtent() const
Definition: joint_model.h:441
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
Definition: joint_model.h:479
void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const override
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
bool satisfiesPositionBounds(const double *values, const Bounds &other_bounds, double margin) const override
Check if the set of position values for the variables of this joint are within bounds,...
void interpolate(const double *from, const double *to, const double t, double *state) const override
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
void getVariableDefaultPositions(double *values, const Bounds &other_bounds) const override
Provide a default value for the joint given the joint variable bounds. Most joints will use the defau...
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const override
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
Eigen::Vector3d axis_
The axis of the joint.
void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const override
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
void computeVariablePositions(const Eigen::Isometry3d &transf, double *joint_values) const override
Given the transform generated by joint, compute the corresponding joint values. Make sure the passed ...
double distance(const double *values1, const double *values2) const override
Compute the distance between two joint states of the same model (represented by the variable values)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PrismaticJointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
unsigned int getStateSpaceDimension() const override
Get the dimension of the state space that corresponds to this joint.
bool enforcePositionBounds(double *values, const Bounds &other_bounds) const override
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
Main namespace for MoveIt.
Definition: exceptions.h:43
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
d
Definition: setup.py:4
name
Definition: setup.py:7