Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
P
panda_teaching
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
CeTI
ROS
ROS Packages
panda_teaching
Commits
e90b0e7f
Commit
e90b0e7f
authored
5 years ago
by
Johannes Mey
Browse files
Options
Downloads
Patches
Plain Diff
remove use of parameter
parent
5e1af023
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
src/teaching/pose_tf_listener.cpp
+35
-53
35 additions, 53 deletions
src/teaching/pose_tf_listener.cpp
with
35 additions
and
53 deletions
src/teaching/pose_tf_listener.cpp
+
35
−
53
View file @
e90b0e7f
...
...
@@ -12,45 +12,53 @@
void
collect
(
ros
::
NodeHandle
node_handle
,
geometry_msgs
::
TransformStamped
t
)
{
ros
::
ServiceClient
client
=
node_handle
.
serviceClient
<
panda_teaching
::
SavePose
>
(
"SaveCollectedPose"
);
panda_teaching
::
SavePose
srv
;
ros
::
ServiceClient
client
=
node_handle
.
serviceClient
<
panda_teaching
::
SavePose
>
(
"SaveCollectedPose"
);
panda_teaching
::
SavePose
srv
;
srv
.
request
.
pose
.
position
.
x
=
t
.
transform
.
translation
.
x
;
srv
.
request
.
pose
.
position
.
y
=
t
.
transform
.
translation
.
y
;
srv
.
request
.
pose
.
position
.
z
=
t
.
transform
.
translation
.
z
;
srv
.
request
.
pose
.
position
.
x
=
t
.
transform
.
translation
.
x
;
srv
.
request
.
pose
.
position
.
y
=
t
.
transform
.
translation
.
y
;
srv
.
request
.
pose
.
position
.
z
=
t
.
transform
.
translation
.
z
;
srv
.
request
.
pose
.
orientation
=
t
.
transform
.
rotation
;
srv
.
request
.
pose
.
orientation
=
t
.
transform
.
rotation
;
if
(
!
client
.
call
(
srv
))
{
ROS_ERROR
(
"Failed to call pose_storage_service."
);
return
;
}
}
void
collectPose
(
ros
::
NodeHandle
&
node_handle
){
node_handle
.
setParam
(
"collect_pose"
,
true
);
if
(
!
client
.
call
(
srv
))
{
ROS_ERROR
(
"Failed to call pose_storage_service."
);
return
;
}
}
void
cleanUp
(
ros
::
NodeHandle
&
node_handle
){
void
cleanUp
(
ros
::
NodeHandle
&
node_handle
)
{
ros
::
ServiceClient
client
=
node_handle
.
serviceClient
<
panda_teaching
::
DeletePose
>
(
"DeleteCollectedPoses"
);
panda_teaching
::
DeletePose
srv
;
if
(
!
client
.
call
(
srv
)){
if
(
!
client
.
call
(
srv
))
{
ROS_ERROR
(
"Failed to delete saved poses"
);
}
}
void
collectorCallback
(
const
std_msgs
::
String
::
ConstPtr
&
msg
,
ros
::
NodeHandle
&
node_handle
){
// global variable. should be put in class
tf2_ros
::
Buffer
tfBuffer
;
void
collectorCallback
(
const
std_msgs
::
String
::
ConstPtr
&
msg
,
ros
::
NodeHandle
&
node_handle
)
{
ROS_INFO
(
"Retrieved new pose-message..."
);
if
(
msg
->
data
.
compare
(
"collect"
)
==
0
){
if
(
msg
->
data
.
compare
(
"collect"
)
==
0
)
{
ROS_INFO
(
"Collecting new pose for gripper..."
);
collectPose
(
node_handle
);
try
{
geometry_msgs
::
TransformStamped
transformStamped
=
tfBuffer
.
lookupTransform
(
"world"
,
"panda_hand"
,
ros
::
Time
(
0
));
std
::
cout
<<
"Collected pose: "
<<
transformStamped
<<
std
::
endl
;
collect
(
node_handle
,
transformStamped
);
}
catch
(
tf2
::
TransformException
&
ex
)
{
ROS_ERROR_STREAM
(
"transform_error: "
<<
ex
.
what
()
<<
std
::
endl
);
ros
::
Duration
(
1.0
).
sleep
();
}
return
;
}
if
(
msg
->
data
.
compare
(
"clear"
)
==
0
){
if
(
msg
->
data
.
compare
(
"clear"
)
==
0
)
{
ROS_INFO
(
"Deleting saved poses..."
);
cleanUp
(
node_handle
);
return
;
...
...
@@ -58,42 +66,16 @@ void collectorCallback(const std_msgs::String::ConstPtr& msg, ros::NodeHandle &n
}
int
main
(
int
argc
,
char
**
argv
)
{
ros
::
init
(
argc
,
argv
,
"pose_tf_listener"
);
ros
::
NodeHandle
node_handle
;
ros
::
init
(
argc
,
argv
,
"pose_tf_listener"
);
ros
::
NodeHandle
node_handle
;
ros
::
Subscriber
sub
=
node_handle
.
subscribe
<
std_msgs
::
String
>
(
"collectPose"
,
1000
,
boost
::
bind
(
&
collectorCallback
,
_1
,
boost
::
ref
(
node_handle
)));
tf2_ros
::
Buffer
tfBuffer
;
tf2_ros
::
TransformListener
tfListener
(
tfBuffer
);
ros
::
Rate
rate
(
10.0
);
while
(
node_handle
.
ok
())
{
tf2_ros
::
TransformListener
tfListener
(
tfBuffer
);
geometry_msgs
::
TransformStamped
transformStamped
;
ros
::
Rate
rate
(
10.0
)
;
try
{
// world == (0, 0, 0, 0)
transformStamped
=
tfBuffer
.
lookupTransform
(
"world"
,
"panda_hand"
,
ros
::
Time
(
0
));
bool
collect_pose
=
false
;
node_handle
.
getParam
(
"collect_pose"
,
collect_pose
);
if
(
collect_pose
)
{
std
::
cout
<<
"Collected pose: "
<<
transformStamped
<<
std
::
endl
;
node_handle
.
setParam
(
"collect_pose"
,
false
);
collect
(
node_handle
,
transformStamped
);
}
}
catch
(
tf2
::
TransformException
&
ex
)
{
std
::
cout
<<
"transform_error: "
<<
ex
.
what
()
<<
std
::
endl
;
ros
::
Duration
(
1.0
).
sleep
();
continue
;
}
ros
::
spinOnce
();
}
return
0
;
};
\ No newline at end of file
ros
::
spin
();
return
0
;
};
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