Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
2
210910794
Manage
Activity
Members
Labels
Plan
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Deploy
Releases
Package Registry
Operate
Terraform modules
Analyze
Value stream analytics
Contributor analytics
Repository analytics
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Summer2021
210910794
Commits
5a6fc036
Commit
5a6fc036
authored
5 years ago
by
Steven Macenski
Browse files
Options
Downloads
Patches
Plain Diff
getFootprint duration overrides
parent
c31e15ef
No related branches found
Branches containing commit
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp
+6
-1
6 additions, 1 deletion
...stmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp
nav2_costmap_2d/src/footprint_subscriber.cpp
+14
-4
14 additions, 4 deletions
nav2_costmap_2d/src/footprint_subscriber.cpp
with
20 additions
and
5 deletions
nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp
+
6
−
1
View file @
5a6fc036
...
...
@@ -49,11 +49,16 @@ public:
~
FootprintSubscriber
()
{}
// Returns an oriented robot footprint at current time.
bool
getFootprint
(
std
::
vector
<
geometry_msgs
::
msg
::
Point
>
&
footprint
,
rclcpp
::
Duration
&
valid_footprint_timeout
);
bool
getFootprint
(
std
::
vector
<
geometry_msgs
::
msg
::
Point
>
&
footprint
);
// Returns an oriented robot footprint.
// The second parameter is the time the fooptrint was at this orientation.
bool
getFootprint
(
std
::
vector
<
geometry_msgs
::
msg
::
Point
>
&
footprint
,
rclcpp
::
Time
&
stamp
);
bool
getFootprint
(
std
::
vector
<
geometry_msgs
::
msg
::
Point
>
&
footprint
,
rclcpp
::
Time
&
stamp
,
rclcpp
::
Duration
valid_footprint_timeout
);
protected
:
// Interfaces used for logging and creating publishers and subscribers
...
...
This diff is collapsed.
Click to expand it.
nav2_costmap_2d/src/footprint_subscriber.cpp
+
14
−
4
View file @
5a6fc036
...
...
@@ -65,7 +65,8 @@ FootprintSubscriber::FootprintSubscriber(
bool
FootprintSubscriber
::
getFootprint
(
std
::
vector
<
geometry_msgs
::
msg
::
Point
>
&
footprint
,
rclcpp
::
Time
&
stamp
)
rclcpp
::
Time
&
stamp
,
rclcpp
::
Duration
valid_footprint_timeout
)
{
if
(
!
footprint_received_
)
{
return
false
;
...
...
@@ -75,7 +76,7 @@ FootprintSubscriber::getFootprint(
std
::
make_shared
<
geometry_msgs
::
msg
::
Polygon
>
(
footprint_
->
polygon
));
auto
&
footprint_stamp
=
footprint_
->
header
.
stamp
;
if
(
stamp
-
footprint_stamp
>
footprint_timeout
_
)
{
if
(
stamp
-
footprint_stamp
>
valid_
footprint_timeout
)
{
return
false
;
}
...
...
@@ -83,10 +84,19 @@ FootprintSubscriber::getFootprint(
}
bool
FootprintSubscriber
::
getFootprint
(
std
::
vector
<
geometry_msgs
::
msg
::
Point
>
&
footprint
)
FootprintSubscriber
::
getFootprint
(
std
::
vector
<
geometry_msgs
::
msg
::
Point
>
&
footprint
,
rclcpp
::
Duration
&
valid_footprint_timeout
)
{
rclcpp
::
Time
t
=
node_clock_
->
get_clock
()
->
now
();
return
getFootprint
(
footprint
,
t
);
return
getFootprint
(
footprint
,
t
,
valid_footprint_timeout
);
}
bool
FootprintSubscriber
::
getFootprint
(
std
::
vector
<
geometry_msgs
::
msg
::
Point
>
&
footprint
)
{
return
getFootprint
(
footprint
,
footprint_timeout_
);
}
void
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
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