Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
P
panda_grasping
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
Package registry
Container registry
Model registry
Operate
Environments
Terraform modules
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
CeTI
ROS
ROS Packages
panda_grasping
Commits
7c7a7626
Commit
7c7a7626
authored
3 years ago
by
Sebastian Ebert
Browse files
Options
Downloads
Patches
Plain Diff
added docs
parent
1784f0d5
No related branches found
No related tags found
1 merge request
!2
Feature/public grasp side
Changes
1
Show whitespace changes
Inline
Side-by-side
Showing
1 changed file
include/grasp_util.h
+46
-45
46 additions, 45 deletions
include/grasp_util.h
with
46 additions
and
45 deletions
include/grasp_util.h
+
46
−
45
View file @
7c7a7626
...
@@ -64,44 +64,45 @@ public:
...
@@ -64,44 +64,45 @@ public:
geometry_msgs
::
Quaternion
gripper_orientation
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
geometry_msgs
::
Quaternion
gripper_orientation
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
/**
/**
*
*
Generate a pick-pose for grasping an object from its back.
* @param object_pose_msg
* @param object_pose_msg
the object pose
* @param gripper_orientation_msg
* @param gripper_orientation_msg
the target gripper orientation -> use a yaw of -M_PI_4 for an orientation orthogonal to the object
* @param object_orientation
* @param object_orientation
the objects orientation -> use (0,0,0,1) for axisymmetric orientation
* @param reach
* @param reach
specifies how far the gripper reaches around the object (0 means the center of the finger tip is at the object's corner)
* @return
* @return
the pick pose
*/
*/
geometry_msgs
::
Pose
geometry_msgs
::
Pose
getPickFromBack
(
geometry_msgs
::
Pose
&
object_pose_msg
,
geometry_msgs
::
Vector3
dimensions
,
geometry_msgs
::
Quaternion
gripper_orientation_msg
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
getPickFromBack
(
geometry_msgs
::
Pose
&
object_pose_msg
,
geometry_msgs
::
Vector3
dimensions
,
geometry_msgs
::
Quaternion
gripper_orientation_msg
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
/**
/**
*
*
* @param object_pose_msg
* Generate a pick-pose for grasping an object from its front.
* @param gripper_orientation_msg
* @param object_pose_msg the object pose
* @param object_orientation
* @param gripper_orientation_msg the target gripper orientation -> use a yaw of -M_PI_4 for an orientation orthogonal to the object
* @param reach
* @param object_orientation the objects orientation -> use (0,0,0,1) for axisymmetric orientation
* @return
* @param reach specifies how far the gripper reaches around the object (0 means the center of the finger tip is at the object's corner)
* @return the pick pose
*/
*/
geometry_msgs
::
Pose
geometry_msgs
::
Pose
getPickFromFront
(
geometry_msgs
::
Pose
&
object_pose_msg
,
geometry_msgs
::
Vector3
dimensions
,
geometry_msgs
::
Quaternion
gripper_orientation_msg
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
getPickFromFront
(
geometry_msgs
::
Pose
&
object_pose_msg
,
geometry_msgs
::
Vector3
dimensions
,
geometry_msgs
::
Quaternion
gripper_orientation_msg
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
/**
/**
*
*
Generate a pick-pose for grasping an object from left.
* @param object_pose_msg
* @param object_pose_msg
the object pose
* @param gripper_orientation_msg
* @param gripper_orientation_msg
the target gripper orientation -> use a yaw of -M_PI_4 for an orientation orthogonal to the object
* @param object_orientation
* @param object_orientation
the objects orientation -> use (0,0,0,1) for axisymmetric orientation
* @param reach
* @param reach
specifies how far the gripper reaches around the object (0 means the center of the finger tip is at the object's corner)
* @return
* @return
the pick pose
*/
*/
geometry_msgs
::
Pose
geometry_msgs
::
Pose
getPickFromLeft
(
geometry_msgs
::
Pose
&
object_pose_msg
,
geometry_msgs
::
Vector3
dimensions
,
geometry_msgs
::
Quaternion
gripper_orientation_msg
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
getPickFromLeft
(
geometry_msgs
::
Pose
&
object_pose_msg
,
geometry_msgs
::
Vector3
dimensions
,
geometry_msgs
::
Quaternion
gripper_orientation_msg
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
/**
/**
*
*
Generate a pick-pose for grasping an object from right.
* @param object_pose_msg
* @param object_pose_msg
the object pose
* @param gripper_orientation_msg
* @param gripper_orientation_msg
the target gripper orientation -> use a yaw of -M_PI_4 for an orientation orthogonal to the object
* @param object_orientation
* @param object_orientation
the objects orientation -> use (0,0,0,1) for axisymmetric orientation
* @param reach
* @param reach
specifies how far the gripper reaches around the object (0 means the center of the finger tip is at the object's corner)
* @return
* @return
the pick pose
*/
*/
geometry_msgs
::
Pose
geometry_msgs
::
Pose
getPickFromRight
(
geometry_msgs
::
Pose
&
object_pose_msg
,
geometry_msgs
::
Vector3
dimensions
,
geometry_msgs
::
Quaternion
gripper_orientation_msg
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
getPickFromRight
(
geometry_msgs
::
Pose
&
object_pose_msg
,
geometry_msgs
::
Vector3
dimensions
,
geometry_msgs
::
Quaternion
gripper_orientation_msg
,
double
reach
=
FRANKA_GRIPPER_FINGERTIP_SIZE
/
2
);
...
@@ -121,42 +122,42 @@ public:
...
@@ -121,42 +122,42 @@ public:
std
::
string
object_to_pick_id
,
bool
plan_only
=
false
);
std
::
string
object_to_pick_id
,
bool
plan_only
=
false
);
/**
/**
*
*
Pick an object from the side based on pick-pose.
* @param move_group
* @param move_group
an initialized MoveGroupInterface instance
* @param pick_pose
* @param pick_pose
pick pose for the approach
* @param object_to_pick
* @param object_to_pick
geometric description of the object
* @param open_amount
* @param open_amount
intial opening amount of the gripper
* @param supporting_surface_id
*
@param supporting_surface_id
ID of surface where object is placed on (e.g. the table)
* @param object_to_pick_id
* @param object_to_pick_id
ID of the object to place
* @param plan_only
* @param plan_only
* @return
* @return
true on success
*/
*/
bool
pickFromSide
(
moveit
::
planning_interface
::
MoveGroupInterface
&
move_group
,
geometry_msgs
::
Pose
&
pick_pose
,
bool
pickFromSide
(
moveit
::
planning_interface
::
MoveGroupInterface
&
move_group
,
geometry_msgs
::
Pose
&
pick_pose
,
shape_msgs
::
SolidPrimitive
&
object_to_pick
,
geometry_msgs
::
Vector3
&
approach_direction
,
shape_msgs
::
SolidPrimitive
&
object_to_pick
,
geometry_msgs
::
Vector3
&
approach_direction
,
double
open_amount
,
std
::
string
supporting_surface_id
,
std
::
string
object_to_pick_id
,
bool
plan_only
=
false
);
double
open_amount
,
std
::
string
supporting_surface_id
,
std
::
string
object_to_pick_id
,
bool
plan_only
=
false
);
/**
/**
*
*
Place an object from above.
* @param move_group
* @param move_group
an initialized MoveGroupInterface instance
* @param place_pose
* @param place_pose
a pre place pose
* @param open_amount
* @param open_amount
intial opening amount of the gripper
* @param supporting_surface_id
* @param supporting_surface_id
ID of surface where object is place on (e.g. the table)
* @param object_to_place
_id
* @param object_to_
pick_id ID of the object to
place
* @param plan_only
* @param plan_only
* @return
* @return
true on success
*/
*/
bool
placeFromAbove
(
moveit
::
planning_interface
::
MoveGroupInterface
&
move_group
,
geometry_msgs
::
Pose
&
place_pose
,
bool
placeFromAbove
(
moveit
::
planning_interface
::
MoveGroupInterface
&
move_group
,
geometry_msgs
::
Pose
&
place_pose
,
double
open_amount
,
std
::
string
supporting_surface_id
,
std
::
string
object_to_place_id
,
bool
plan_only
=
false
);
double
open_amount
,
std
::
string
supporting_surface_id
,
std
::
string
object_to_place_id
,
bool
plan_only
=
false
);
/**
/**
*
*
Place an object from side.
* @param move_group
* @param move_group
an initialized MoveGroupInterface instance
* @param place_pose
* @param place_pose
a pre-place pose
* @param open_amount
* @param open_amount
intial opening amount of the gripper
* @param supporting_surface_id
* @param supporting_surface_id
ID of surface where object is place on (e.g. the table)
* @param object_to_place
_id
* @param object_to_
pick_id ID of the object to
place
* @param plan_only
* @param plan_only
* @return
* @return
true on success
*/
*/
bool
placeFromSide
(
moveit
::
planning_interface
::
MoveGroupInterface
&
move_group
,
geometry_msgs
::
Pose
&
place_pose
,
bool
placeFromSide
(
moveit
::
planning_interface
::
MoveGroupInterface
&
move_group
,
geometry_msgs
::
Pose
&
place_pose
,
double
open_amount
,
std
::
string
supporting_surface_id
,
std
::
string
object_to_place_id
,
bool
plan_only
=
false
);
double
open_amount
,
std
::
string
supporting_surface_id
,
std
::
string
object_to_place_id
,
bool
plan_only
=
false
);
...
...
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