Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
C
crosbot
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
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
GitLab community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Crosbot
crosbot
Commits
12bffb24
Commit
12bffb24
authored
8 years ago
by
Timothy Wiley
Browse files
Options
Downloads
Patches
Plain Diff
crosbot_fastslam: make sub/pub topics configurable
parent
d42cb7c4
Branches
Branches containing commit
No related tags found
No related merge requests found
Changes
2
Show whitespace changes
Inline
Side-by-side
Showing
2 changed files
crosbot_fastslam/include/crosbot_fastslam/module.hpp
+5
-1
5 additions, 1 deletion
crosbot_fastslam/include/crosbot_fastslam/module.hpp
crosbot_fastslam/src/module.cpp
+10
-6
10 additions, 6 deletions
crosbot_fastslam/src/module.cpp
with
15 additions
and
7 deletions
crosbot_fastslam/include/crosbot_fastslam/module.hpp
+
5
−
1
View file @
12bffb24
...
...
@@ -34,7 +34,11 @@ protected:
std
::
string
baseFrame
;
std
::
string
mapFrame
;
std
::
string
odomFrame
;
std
::
string
pubParticles
;
std
::
string
pub_historyName
;
std
::
string
pub_mapName
;
std
::
string
pub_particlesName
;
std
::
string
sub_scanName
;
std
::
string
sub_snapName
;
ros
::
Subscriber
scanSub
;
ros
::
Subscriber
snapSub
;
...
...
This diff is collapsed.
Click to expand it.
crosbot_fastslam/src/module.cpp
+
10
−
6
View file @
12bffb24
...
...
@@ -68,14 +68,18 @@ void FastSLAMModule::initialize(ros::NodeHandle& nh) {
paramNH
.
param
<
std
::
string
>
(
"base_frame"
,
baseFrame
,
DEFAULT_BASEFRAME
);
paramNH
.
param
<
std
::
string
>
(
"map_frame"
,
mapFrame
,
DEFAULT_MAPFRAME
);
paramNH
.
param
<
std
::
string
>
(
"odom_frame"
,
odomFrame
,
DEFAULT_ODOMFRAME
);
paramNH
.
param
<
std
::
string
>
(
"pub_particles"
,
pubParticles
,
"/crosbot_fastslam/particles"
);
paramNH
.
param
<
std
::
string
>
(
"pub_history"
,
pub_historyName
,
"/crosbot_fastslam/history"
);
paramNH
.
param
<
std
::
string
>
(
"pub_map"
,
pub_mapName
,
"/crosbot_fastslam/map"
);
paramNH
.
param
<
std
::
string
>
(
"pub_particles"
,
pub_particlesName
,
"/crosbot_fastslam/particles"
);
paramNH
.
param
<
std
::
string
>
(
"sub_scan"
,
sub_scanName
,
"/scan"
);
paramNH
.
param
<
std
::
string
>
(
"sub_snap"
,
sub_snapName
,
"/crosbot_fastslam/snaps"
);
ROS_INFO
(
"%s map: %s, odom: %s, base: %s"
,
LOG_START
,
mapFrame
.
c_str
(),
odomFrame
.
c_str
(),
baseFrame
.
c_str
());
scanSub
=
nh
.
subscribe
(
"scan"
,
1
,
&
FastSLAMModule
::
callbackScan
,
this
);
snapSub
=
nh
.
subscribe
(
"snap"
,
1000
,
&
FastSLAMModule
::
callbackSnap
,
this
);
gridPub
=
nh
.
advertise
<
nav_msgs
::
OccupancyGrid
>
(
"map"
,
1
,
true
);
historyPub
=
nh
.
advertise
<
nav_msgs
::
Path
>
(
"
history
"
,
1
);
particlesPub
=
nh
.
advertise
<
geometry_msgs
::
PoseArray
>
(
pub
P
articles
,
1
);
scanSub
=
nh
.
subscribe
(
sub_scanName
,
1
,
&
FastSLAMModule
::
callbackScan
,
this
);
snapSub
=
nh
.
subscribe
(
sub_snapName
,
1000
,
&
FastSLAMModule
::
callbackSnap
,
this
);
gridPub
=
nh
.
advertise
<
nav_msgs
::
OccupancyGrid
>
(
pub_mapName
,
1
,
true
);
historyPub
=
nh
.
advertise
<
nav_msgs
::
Path
>
(
pub_
history
Name
,
1
);
particlesPub
=
nh
.
advertise
<
geometry_msgs
::
PoseArray
>
(
pub
_p
articles
Name
,
1
);
// read configuration/parameters
ConfigElementPtr
config
=
new
ROSConfigElement
(
paramNH
);
...
...
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