moveit2
The MoveIt Motion Planning Framework for ROS 2.
planar_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 #pragma once
38 
40 
41 namespace moveit
42 {
43 namespace core
44 {
47 {
48 public:
51  {
52  HOLONOMIC, // default
54  };
55 
56  PlanarJointModel(const std::string& name, size_t joint_index, size_t first_variable_index);
57 
58  void getVariableDefaultPositions(double* values, const Bounds& other_bounds) const override;
59  void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
60  const Bounds& other_bounds) const override;
61  void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
62  const Bounds& other_bounds, const double* near,
63  const double distance) const override;
64  bool enforcePositionBounds(double* values, const Bounds& other_bounds) const override;
65  bool satisfiesPositionBounds(const double* values, const Bounds& other_bounds, double margin) const override;
66 
67  void interpolate(const double* from, const double* to, const double t, double* state) const override;
68  unsigned int getStateSpaceDimension() const override;
69  double getMaximumExtent(const Bounds& other_bounds) const override;
70  double distance(const double* values1, const double* values2) const override;
71 
72  void computeTransform(const double* joint_values, Eigen::Isometry3d& transf) const override;
73  void computeVariablePositions(const Eigen::Isometry3d& transf, double* joint_values) const override;
74 
75  double getAngularDistanceWeight() const
76  {
77  return angular_distance_weight_;
78  }
79 
80  void setAngularDistanceWeight(double weight)
81  {
82  angular_distance_weight_ = weight;
83  }
84 
86  {
87  return min_translational_distance_;
88  }
89 
90  void setMinTranslationalDistance(double min_translational_distance)
91  {
92  min_translational_distance_ = min_translational_distance;
93  }
94 
96  {
97  return motion_model_;
98  }
99 
101  {
102  motion_model_ = model;
103  }
104 
108  bool normalizeRotation(double* values) const;
109 
110 private:
111  double angular_distance_weight_;
112  MotionModel motion_model_;
114  double min_translational_distance_;
115 };
116 
129 void computeTurnDriveTurnGeometry(const double* from, const double* to, const double min_translational_distance,
130  double& dx, double& dy, double& initial_turn, double& drive_angle,
131  double& final_turn);
132 } // namespace core
133 } // namespace moveit
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:131
double getMaximumExtent() const
Definition: joint_model.h:441
bool normalizeRotation(double *values) const
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 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 ...
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 ...
void setMinTranslationalDistance(double min_translational_distance)
void setMotionModel(MotionModel model)
PlanarJointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
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 setAngularDistanceWeight(double weight)
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,...
MotionModel getMotionModel() const
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 ...
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,...
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...
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)
MotionModel
different types of planar joints we support
void computeTurnDriveTurnGeometry(const double *from, const double *to, const double min_translational_distance, double &dx, double &dy, double &initial_turn, double &drive_angle, double &final_turn)
Compute the geometry to turn toward the target point, drive straight and then turn to target orientat...
Main namespace for MoveIt.
Definition: exceptions.h:43
name
Definition: setup.py:7