Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
W
wolf_ros_node
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Deploy
Releases
Model registry
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor 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
mobile_robotics
wolf_projects
wolf_ros
wolf_ros_node
Commits
9f5d9686
Commit
9f5d9686
authored
5 years ago
by
Joan Vallvé Navarro
Browse files
Options
Downloads
Patches
Plain Diff
adapted to ts.ok()
parent
a63b5619
No related branches found
No related tags found
2 merge requests
!11
new release
,
!10
new release
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
src/node.cpp
+2
-2
2 additions, 2 deletions
src/node.cpp
with
2 additions
and
2 deletions
src/node.cpp
+
2
−
2
View file @
9f5d9686
...
@@ -117,13 +117,12 @@ bool WolfRosNode::updateTf()
...
@@ -117,13 +117,12 @@ bool WolfRosNode::updateTf()
VectorComposite
current_state
=
problem_ptr_
->
getState
(
"PO"
);
VectorComposite
current_state
=
problem_ptr_
->
getState
(
"PO"
);
TimeStamp
loc_ts
=
problem_ptr_
->
getTimeStamp
();
TimeStamp
loc_ts
=
problem_ptr_
->
getTimeStamp
();
ros
::
Time
loc_stamp
(
loc_ts
.
getSeconds
(),
loc_ts
.
getNanoSeconds
());
//Get map2base from Wolf result, and builds base2map pose
//Get map2base from Wolf result, and builds base2map pose
tf
::
Transform
T_map2base
;
tf
::
Transform
T_map2base
;
if
(
current_state
.
count
(
"P"
)
==
0
or
if
(
current_state
.
count
(
"P"
)
==
0
or
current_state
.
count
(
"O"
)
==
0
or
current_state
.
count
(
"O"
)
==
0
or
loc_ts
==
TimeStamp
(
0
))
loc_ts
.
ok
(
))
{
{
if
(
state_available_
)
if
(
state_available_
)
{
{
...
@@ -155,6 +154,7 @@ bool WolfRosNode::updateTf()
...
@@ -155,6 +154,7 @@ bool WolfRosNode::updateTf()
//gets T_map2odom_ (odom wrt map), by using tf listener, and assuming an odometry node is broadcasting odom2base
//gets T_map2odom_ (odom wrt map), by using tf listener, and assuming an odometry node is broadcasting odom2base
tf
::
StampedTransform
T_base2odom
;
tf
::
StampedTransform
T_base2odom
;
ros
::
Time
loc_stamp
(
loc_ts
.
getSeconds
(),
loc_ts
.
getNanoSeconds
());
if
(
tfl_
.
waitForTransform
(
base_frame_id_
,
odom_frame_id_
,
ros
::
Time
(
0
),
ros
::
Duration
(
0.2
))
)
if
(
tfl_
.
waitForTransform
(
base_frame_id_
,
odom_frame_id_
,
ros
::
Time
(
0
),
ros
::
Duration
(
0.2
))
)
{
{
// tfl_.lookupTransform(base_frame_id_, odom_frame_id_, loc_stamp, T_base2odom);
// tfl_.lookupTransform(base_frame_id_, odom_frame_id_, loc_stamp, T_base2odom);
...
...
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