Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
homer_mapping
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
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
robbie
homer_mapping
Commits
741c2a3d
Commit
741c2a3d
authored
8 years ago
by
Florian Polster
Browse files
Options
Downloads
Patches
Plain Diff
no seperate laserCallback
parent
0b30e442
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
homer_navigation/include/homer_navigation/homer_navigation_node.h
+0
-2
0 additions, 2 deletions
...vigation/include/homer_navigation/homer_navigation_node.h
homer_navigation/src/homer_navigation_node.cpp
+2
-12
2 additions, 12 deletions
homer_navigation/src/homer_navigation_node.cpp
with
2 additions
and
14 deletions
homer_navigation/include/homer_navigation/homer_navigation_node.h
+
0
−
2
View file @
741c2a3d
...
@@ -66,7 +66,6 @@ class HomerNavigationNode {
...
@@ -66,7 +66,6 @@ class HomerNavigationNode {
void
ignoreLaserCallback
(
const
std_msgs
::
String
::
ConstPtr
&
msg
);
void
ignoreLaserCallback
(
const
std_msgs
::
String
::
ConstPtr
&
msg
);
void
poseCallback
(
const
geometry_msgs
::
PoseStamped
::
ConstPtr
&
msg
);
void
poseCallback
(
const
geometry_msgs
::
PoseStamped
::
ConstPtr
&
msg
);
void
laserDataCallback
(
const
sensor_msgs
::
LaserScan
::
ConstPtr
&
msg
);
void
laserDataCallback
(
const
sensor_msgs
::
LaserScan
::
ConstPtr
&
msg
);
void
downlaserDataCallback
(
const
sensor_msgs
::
LaserScan
::
ConstPtr
&
msg
);
void
startNavigationCallback
(
void
startNavigationCallback
(
const
homer_mapnav_msgs
::
StartNavigation
::
ConstPtr
&
msg
);
const
homer_mapnav_msgs
::
StartNavigation
::
ConstPtr
&
msg
);
void
moveBaseSimpleGoalCallback
(
void
moveBaseSimpleGoalCallback
(
...
@@ -85,7 +84,6 @@ class HomerNavigationNode {
...
@@ -85,7 +84,6 @@ class HomerNavigationNode {
virtual
void
init
();
virtual
void
init
();
void
initNewTarget
();
void
initNewTarget
();
void
processLaserScan
(
const
sensor_msgs
::
LaserScan
::
ConstPtr
&
msg
);
private
:
private
:
/** @brief Start navigation to m_Target on last_map_data_ */
/** @brief Start navigation to m_Target on last_map_data_ */
...
...
This diff is collapsed.
Click to expand it.
homer_navigation/src/homer_navigation_node.cpp
+
2
−
12
View file @
741c2a3d
...
@@ -11,7 +11,7 @@ HomerNavigationNode::HomerNavigationNode() {
...
@@ -11,7 +11,7 @@ HomerNavigationNode::HomerNavigationNode() {
m_laser_data_sub
=
nh
.
subscribe
<
sensor_msgs
::
LaserScan
>
(
m_laser_data_sub
=
nh
.
subscribe
<
sensor_msgs
::
LaserScan
>
(
"/scan"
,
1
,
&
HomerNavigationNode
::
laserDataCallback
,
this
);
"/scan"
,
1
,
&
HomerNavigationNode
::
laserDataCallback
,
this
);
m_down_laser_data_sub
=
nh
.
subscribe
<
sensor_msgs
::
LaserScan
>
(
m_down_laser_data_sub
=
nh
.
subscribe
<
sensor_msgs
::
LaserScan
>
(
"/front_scan"
,
1
,
&
HomerNavigationNode
::
down
laserDataCallback
,
this
);
"/front_scan"
,
1
,
&
HomerNavigationNode
::
laserDataCallback
,
this
);
m_start_navigation_sub
=
nh
.
subscribe
<
homer_mapnav_msgs
::
StartNavigation
>
(
m_start_navigation_sub
=
nh
.
subscribe
<
homer_mapnav_msgs
::
StartNavigation
>
(
"/homer_navigation/start_navigation"
,
1
,
"/homer_navigation/start_navigation"
,
1
,
&
HomerNavigationNode
::
startNavigationCallback
,
this
);
&
HomerNavigationNode
::
startNavigationCallback
,
this
);
...
@@ -1087,7 +1087,7 @@ void HomerNavigationNode::maxDepthMoveDistanceCallback(
...
@@ -1087,7 +1087,7 @@ void HomerNavigationNode::maxDepthMoveDistanceCallback(
calcMaxMoveDist
();
calcMaxMoveDist
();
}
}
void
HomerNavigationNode
::
processLaserScan
(
void
HomerNavigationNode
::
laserDataCallback
(
const
sensor_msgs
::
LaserScan
::
ConstPtr
&
msg
)
{
const
sensor_msgs
::
LaserScan
::
ConstPtr
&
msg
)
{
m_scan_map
[
msg
->
header
.
frame_id
]
=
msg
;
m_scan_map
[
msg
->
header
.
frame_id
]
=
msg
;
m_last_laser_time
=
ros
::
Time
::
now
();
m_last_laser_time
=
ros
::
Time
::
now
();
...
@@ -1105,16 +1105,6 @@ void HomerNavigationNode::processLaserScan(
...
@@ -1105,16 +1105,6 @@ void HomerNavigationNode::processLaserScan(
}
}
}
}
void
HomerNavigationNode
::
laserDataCallback
(
const
sensor_msgs
::
LaserScan
::
ConstPtr
&
msg
)
{
processLaserScan
(
msg
);
}
void
HomerNavigationNode
::
downlaserDataCallback
(
const
sensor_msgs
::
LaserScan
::
ConstPtr
&
msg
)
{
processLaserScan
(
msg
);
}
void
HomerNavigationNode
::
initNewTarget
()
{
void
HomerNavigationNode
::
initNewTarget
()
{
m_initial_path_reaches_target
=
false
;
m_initial_path_reaches_target
=
false
;
m_avoided_collision
=
false
;
m_avoided_collision
=
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