Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
H
hpp-manipulation
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Container Registry
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Guilhem Saurel
hpp-manipulation
Commits
97ebeb6a
Commit
97ebeb6a
authored
5 years ago
by
Joseph Mirabel
Browse files
Options
Downloads
Patches
Plain Diff
Add steeringMethod::EndEffectorTrajectory::makePiecewiseLinearTrajectory
parent
36eeee4b
No related branches found
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
include/hpp/manipulation/steering-method/end-effector-trajectory.hh
+4
-0
4 additions, 0 deletions
...p/manipulation/steering-method/end-effector-trajectory.hh
src/steering-method/end-effector-trajectory.cc
+24
-0
24 additions, 0 deletions
src/steering-method/end-effector-trajectory.cc
with
28 additions
and
0 deletions
include/hpp/manipulation/steering-method/end-effector-trajectory.hh
+
4
−
0
View file @
97ebeb6a
...
...
@@ -46,6 +46,10 @@ namespace hpp {
return
ptr
;
}
/// Build a trajectory in SE(3).
/// \param points a Nx7 matrix whose rows corresponds to a pose.
static
PathPtr_t
makePiecewiseLinearTrajectory
(
matrixIn_t
points
);
/// Set the constraint whose right hand side will vary.
void
trajectoryConstraint
(
const
constraints
::
ImplicitPtr_t
&
ic
);
...
...
This diff is collapsed.
Click to expand it.
src/steering-method/end-effector-trajectory.cc
+
24
−
0
View file @
97ebeb6a
...
...
@@ -27,6 +27,7 @@
#include
<hpp/core/config-projector.hh>
#include
<hpp/core/path.hh>
#include
<hpp/core/path-vector.hh>
#include
<hpp/core/problem.hh>
#include
<hpp/core/straight-path.hh>
...
...
@@ -80,6 +81,29 @@ namespace hpp {
};
}
PathPtr_t
EndEffectorTrajectory
::
makePiecewiseLinearTrajectory
(
matrixIn_t
points
)
{
if
(
points
.
cols
()
!=
7
)
throw
std
::
invalid_argument
(
"The input matrix should have 7 columns"
);
LiegroupSpacePtr_t
se3
=
LiegroupSpace
::
SE3
();
if
(
points
.
rows
()
==
1
)
return
core
::
StraightPath
::
create
(
se3
,
points
.
row
(
0
),
points
.
row
(
0
),
interval_t
(
0
,
0
));
core
::
PathVectorPtr_t
path
=
core
::
PathVector
::
create
(
7
,
6
);
for
(
size_type
i
=
1
;
i
<
points
.
rows
();
++
i
)
{
value_type
d
=
(
se3
->
elementConstRef
(
points
.
row
(
i
))
-
se3
->
elementConstRef
(
points
.
row
(
i
-
1
))
).
norm
();
path
->
appendPath
(
core
::
StraightPath
::
create
(
se3
,
points
.
row
(
i
-
1
),
points
.
row
(
i
),
interval_t
(
0
,
d
)));
}
return
path
;
}
void
EndEffectorTrajectory
::
trajectoryConstraint
(
const
constraints
::
ImplicitPtr_t
&
ic
)
{
constraint_
=
ic
;
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment