hrplib
hrpModel
JointPath.h
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2008, AIST, the University of Tokyo and General Robotix Inc.
3
* All rights reserved. This program is made available under the terms of the
4
* Eclipse Public License v1.0 which accompanies this distribution, and is
5
* available at http://www.eclipse.org/legal/epl-v10.html
6
* Contributors:
7
* National Institute of Advanced Industrial Science and Technology (AIST)
8
*/
9
15
#ifndef HRPMODEL_JOINT_PATH_H_INCLUDED
16
#define HRPMODEL_JOINT_PATH_H_INCLUDED
17
18
#include <boost/shared_ptr.hpp>
19
#include <
hrpUtil/Eigen3d.h
>
20
#include "
LinkPath.h
"
21
#include "
InverseKinematics.h
"
22
#include "Config.h"
23
24
namespace
hrp
{
25
26
class
HRPMODEL_API
JointPath
:
public
InverseKinematics
27
{
28
public
:
29
30
JointPath
();
31
JointPath
(
Link
* base,
Link
* end);
32
JointPath
(
Link
* end);
33
virtual
~
JointPath
();
34
35
bool
find(
Link
* base,
Link
* end);
36
bool
find(
Link
* end);
37
38
inline
bool
empty
()
const
{
39
return
joints.empty();
40
}
41
42
inline
unsigned
int
numJoints
()
const
{
43
return
joints.size();
44
}
45
46
inline
Link
*
joint
(
int
index)
const
{
47
return
joints[index];
48
}
49
50
inline
Link
*
baseLink
()
const
{
51
return
linkPath.baseLink();
52
}
53
54
inline
Link
*
endLink
()
const
{
55
return
linkPath.endLink();
56
}
57
58
inline
bool
isJointDownward
(
int
index)
const
{
59
return
(index >= numUpwardJointConnections);
60
}
61
62
inline
void
calcForwardKinematics
(
bool
calcVelocity =
false
,
bool
calcAcceleration =
false
)
const
{
63
linkPath.calcForwardKinematics(calcVelocity, calcAcceleration);
64
}
65
66
void
calcJacobian(
dmatrix
& out_J,
const
Vector3
& local_p = Vector3::Zero())
const
;
67
68
inline
dmatrix
Jacobian
()
const
{
69
dmatrix
J;
70
calcJacobian(J);
71
return
J;
72
}
73
74
void
calcJacobianDot(
dmatrix
& out_dJ,
const
Vector3
& local_p = Vector3::Zero())
const
;
75
76
// InverseKinematics Interface
77
virtual
void
setMaxIKError(
double
e);
78
virtual
void
setBestEffortIKMode(
bool
on);
79
virtual
bool
calcInverseKinematics(
const
Vector3
& end_p,
const
Matrix33
& end_R);
80
virtual
bool
hasAnalyticalIK();
81
82
bool
calcInverseKinematics(
83
const
Vector3
& base_p,
const
Matrix33
& base_R,
const
Vector3
& end_p,
const
Matrix33
& end_R);
84
85
protected
:
86
87
virtual
void
onJointPathUpdated();
88
89
double
maxIKErrorSqr
;
90
bool
isBestEffortIKMode
;
91
92
private
:
93
94
void
initialize();
95
void
extractJoints();
96
97
LinkPath
linkPath
;
98
std::vector<Link*>
joints
;
99
int
numUpwardJointConnections
;
100
};
101
102
typedef
boost::shared_ptr<JointPath>
JointPathPtr
;
103
104
};
105
106
107
#endif
hrp::JointPath::joint
Link * joint(int index) const
Definition:
JointPath.h:46
hrp::LinkPath
Definition:
LinkPath.h:23
hrp::JointPath::isBestEffortIKMode
bool isBestEffortIKMode
Definition:
JointPath.h:90
hrp::JointPath::numUpwardJointConnections
int numUpwardJointConnections
Definition:
JointPath.h:99
hrp
Definition:
ColdetModel.h:28
LinkPath.h
hrp::JointPath::numJoints
unsigned int numJoints() const
Definition:
JointPath.h:42
hrp::Link
Definition:
Link.h:40
hrp::Vector3
Eigen::Vector3d Vector3
Definition:
EigenTypes.h:11
hrp::JointPath::Jacobian
dmatrix Jacobian() const
Definition:
JointPath.h:68
hrp::JointPath::calcForwardKinematics
void calcForwardKinematics(bool calcVelocity=false, bool calcAcceleration=false) const
Definition:
JointPath.h:62
hrp::JointPath::baseLink
Link * baseLink() const
Definition:
JointPath.h:50
hrp::JointPath::linkPath
LinkPath linkPath
Definition:
JointPath.h:97
hrp::dmatrix
Eigen::MatrixXd dmatrix
Definition:
EigenTypes.h:13
hrp::JointPath::empty
bool empty() const
Definition:
JointPath.h:38
hrp::JointPath::isJointDownward
bool isJointDownward(int index) const
Definition:
JointPath.h:58
hrp::JointPathPtr
boost::shared_ptr< JointPath > JointPathPtr
Definition:
Body.h:29
hrp::JointPath::maxIKErrorSqr
double maxIKErrorSqr
Definition:
JointPath.h:89
hrp::Matrix33
Eigen::Matrix3d Matrix33
Definition:
EigenTypes.h:12
Eigen3d.h
hrp::JointPath::joints
std::vector< Link * > joints
Definition:
JointPath.h:98
InverseKinematics.h
hrp::InverseKinematics
Definition:
InverseKinematics.h:22
hrp::JointPath::endLink
Link * endLink() const
Definition:
JointPath.h:54
hrp::JointPath
Definition:
JointPath.h:26
openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Wed Sep 7 2022 02:51:03