Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
I
iri_tiago_nav_module
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
Package Registry
Model registry
Operate
Environments
Terraform modules
Monitor
Incidents
Service Desk
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
labrobotica
ros
platforms
TIAGo
iri_tiago_nav_module
Commits
8ba23ddb
Commit
8ba23ddb
authored
4 years ago
by
Sergi Hernandez
Browse files
Options
Downloads
Patches
Plain Diff
Changed the names of some of the variables in the dynamic reconfigure
file.
parent
9043db68
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/tiago_nav_module.cpp
+8
-8
8 additions, 8 deletions
src/tiago_nav_module.cpp
with
8 additions
and
8 deletions
src/tiago_nav_module.cpp
+
8
−
8
View file @
8ba23ddb
...
@@ -40,7 +40,7 @@ CTiagoNavModule::CTiagoNavModule(const std::string &name,const std::string &name
...
@@ -40,7 +40,7 @@ CTiagoNavModule::CTiagoNavModule(const std::string &name,const std::string &name
this
->
transform_orientation
=
false
;
this
->
transform_orientation
=
false
;
// costmaps
// costmaps
this
->
clear_costmaps_timer
=
this
->
module_nh
.
createTimer
(
ros
::
Duration
(
1.0
/
this
->
config
.
c
m
_auto_clear_rate_hz
),
&
CTiagoNavModule
::
clear_costmaps_call
,
this
);
this
->
clear_costmaps_timer
=
this
->
module_nh
.
createTimer
(
ros
::
Duration
(
1.0
/
this
->
config
.
c
lear_costmap
_auto_clear_rate_hz
),
&
CTiagoNavModule
::
clear_costmaps_call
,
this
);
this
->
clear_costmaps_timer
.
stop
();
this
->
clear_costmaps_timer
.
stop
();
this
->
enable_auto_clear
=
false
;
this
->
enable_auto_clear
=
false
;
...
@@ -348,7 +348,7 @@ void CTiagoNavModule::reconfigure_callback(tiago_nav_module::TiagoNavModuleConfi
...
@@ -348,7 +348,7 @@ void CTiagoNavModule::reconfigure_callback(tiago_nav_module::TiagoNavModuleConfi
this
->
dynamic_reconfigure
(
config
,
"nav_module"
);
this
->
dynamic_reconfigure
(
config
,
"nav_module"
);
/* move base action parameters */
/* move base action parameters */
this
->
move_base_action
.
dynamic_reconfigure
(
config
,
"move_base"
);
this
->
move_base_action
.
dynamic_reconfigure
(
config
,
"move_base"
);
this
->
goal_frame_id
=
config
.
m
b
_frame_id
;
this
->
goal_frame_id
=
config
.
m
ove_base
_frame_id
;
/* go to point of interest action parameters */
/* go to point of interest action parameters */
this
->
poi_action
.
dynamic_reconfigure
(
config
,
"move_poi"
);
this
->
poi_action
.
dynamic_reconfigure
(
config
,
"move_poi"
);
/* waypoints action parameters */
/* waypoints action parameters */
...
@@ -357,9 +357,9 @@ void CTiagoNavModule::reconfigure_callback(tiago_nav_module::TiagoNavModuleConfi
...
@@ -357,9 +357,9 @@ void CTiagoNavModule::reconfigure_callback(tiago_nav_module::TiagoNavModuleConfi
#endif
#endif
// costmaps
// costmaps
this
->
clear_costmaps
.
dynamic_reconfigure
(
config
,
"clear_costmap"
);
this
->
clear_costmaps
.
dynamic_reconfigure
(
config
,
"clear_costmap"
);
if
(
config
.
c
m
_enable_auto_clear
)
if
(
config
.
c
lear_costmap
_enable_auto_clear
)
{
{
this
->
clear_costmaps_timer
.
setPeriod
(
ros
::
Duration
(
1.0
/
config
.
c
m
_auto_clear_rate_hz
));
this
->
clear_costmaps_timer
.
setPeriod
(
ros
::
Duration
(
1.0
/
config
.
c
lear_costmap
_auto_clear_rate_hz
));
this
->
clear_costmaps_timer
.
start
();
this
->
clear_costmaps_timer
.
start
();
this
->
enable_auto_clear
=
true
;
this
->
enable_auto_clear
=
true
;
}
}
...
@@ -473,7 +473,7 @@ bool CTiagoNavModule::check_op_mode(pal_navigation_msgs::Acknowledgment &msg)
...
@@ -473,7 +473,7 @@ bool CTiagoNavModule::check_op_mode(pal_navigation_msgs::Acknowledgment &msg)
bool
CTiagoNavModule
::
go_to_orientation
(
double
yaw
,
double
heading_tol
)
bool
CTiagoNavModule
::
go_to_orientation
(
double
yaw
,
double
heading_tol
)
{
{
this
->
lock
();
this
->
lock
();
if
(
this
->
config
.
m
b
_cancel_prev
&&
!
this
->
is_finished
())
if
(
this
->
config
.
m
ove_base
_cancel_prev
&&
!
this
->
is_finished
())
this
->
move_base_action
.
cancel
();
this
->
move_base_action
.
cancel
();
if
(
heading_tol
!=
DEFAULT_HEADING_TOL
)
if
(
heading_tol
!=
DEFAULT_HEADING_TOL
)
{
{
...
@@ -516,7 +516,7 @@ bool CTiagoNavModule::go_to_orientation(double yaw,double heading_tol)
...
@@ -516,7 +516,7 @@ bool CTiagoNavModule::go_to_orientation(double yaw,double heading_tol)
bool
CTiagoNavModule
::
go_to_position
(
double
x
,
double
y
,
double
x_y_pos_tol
)
bool
CTiagoNavModule
::
go_to_position
(
double
x
,
double
y
,
double
x_y_pos_tol
)
{
{
this
->
lock
();
this
->
lock
();
if
(
this
->
config
.
m
b
_cancel_prev
&&
!
this
->
is_finished
())
if
(
this
->
config
.
m
ove_base
_cancel_prev
&&
!
this
->
is_finished
())
this
->
move_base_action
.
cancel
();
this
->
move_base_action
.
cancel
();
if
(
x_y_pos_tol
!=
DEFAULT_X_Y_POS_TOL
)
if
(
x_y_pos_tol
!=
DEFAULT_X_Y_POS_TOL
)
{
{
...
@@ -561,7 +561,7 @@ bool CTiagoNavModule::go_to_position(double x,double y,double x_y_pos_tol)
...
@@ -561,7 +561,7 @@ bool CTiagoNavModule::go_to_position(double x,double y,double x_y_pos_tol)
bool
CTiagoNavModule
::
go_to_pose
(
double
x
,
double
y
,
double
yaw
,
double
heading_tol
,
double
x_y_pos_tol
)
bool
CTiagoNavModule
::
go_to_pose
(
double
x
,
double
y
,
double
yaw
,
double
heading_tol
,
double
x_y_pos_tol
)
{
{
this
->
lock
();
this
->
lock
();
if
(
this
->
config
.
m
b
_cancel_prev
&&
!
this
->
is_finished
())
if
(
this
->
config
.
m
ove_base
_cancel_prev
&&
!
this
->
is_finished
())
this
->
move_base_action
.
cancel
();
this
->
move_base_action
.
cancel
();
if
(
heading_tol
!=
DEFAULT_HEADING_TOL
)
if
(
heading_tol
!=
DEFAULT_HEADING_TOL
)
{
{
...
@@ -734,7 +734,7 @@ void CTiagoNavModule::costmaps_enable_auto_clear(double rate_hz)
...
@@ -734,7 +734,7 @@ void CTiagoNavModule::costmaps_enable_auto_clear(double rate_hz)
this
->
lock
();
this
->
lock
();
if
(
!
this
->
enable_auto_clear
)
if
(
!
this
->
enable_auto_clear
)
{
{
this
->
clear_costmaps_timer
.
setPeriod
(
ros
::
Duration
(
1.0
/
config
.
c
m
_auto_clear_rate_hz
));
this
->
clear_costmaps_timer
.
setPeriod
(
ros
::
Duration
(
1.0
/
config
.
c
lear_costmap
_auto_clear_rate_hz
));
this
->
clear_costmaps_timer
.
start
();
this
->
clear_costmaps_timer
.
start
();
this
->
enable_auto_clear
=
true
;
this
->
enable_auto_clear
=
true
;
}
}
...
...
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