Skip to content

Commit 60f8c0f

Browse files
added PLUGINLIB_EXPORT_CLASS
1 parent d9f2b65 commit 60f8c0f

File tree

2 files changed

+8
-2
lines changed

2 files changed

+8
-2
lines changed

mep3_navigation/params/nav2_params_big.yaml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -184,6 +184,7 @@
184184
plugin: "nav2_behaviors/Wait"
185185
move:
186186
plugin: "mep3_navigation::MoveBehavior"
187+
plugin: "mep3_navigation::StuckBehavior"
187188
global_frame: odom
188189
robot_base_frame: base_link
189190
transform_tolerance: 0.1
@@ -192,7 +193,7 @@
192193
min_rotational_vel: 0.4
193194
rotational_acc_lim: 3.2
194195
simulate_ahead_time: 0.3
195-
196+
196197
# Move
197198
simulate_ahead_distance: 0.2
198199
debouncing_duration: 0.05

mep3_navigation/src/stuck_behavior/stuck_behavior.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,11 @@
11
#include "mep3_navigation/stuck_behavior/stuck_behavior.hpp"
2-
2+
#include "pluginlib/class_list_macros.hpp"
33

44
mep3_navigation::StuckBehavior::StuckBehavior() :
55
nav2_behaviors::TimedBehavior<ActionT>()
66
{
7+
std::cout << "STUCK BEHAVIOR CONSTRUCTOR" << std::endl << std::endl;
8+
RCLCPP_WARN(this->logger_, "STUCK BEHAVIOR CONSTRUCTOR!");
79
}
810

911
mep3_navigation::StuckBehavior::~StuckBehavior() = default;
@@ -19,3 +21,6 @@ nav2_behaviors::Status mep3_navigation::StuckBehavior::onCycleUpdate()
1921
RCLCPP_INFO(this->logger_, "onCycleUpdate successful!");
2022
return nav2_behaviors::Status::RUNNING;
2123
}
24+
25+
PLUGINLIB_EXPORT_CLASS(mep3_navigation::StuckBehavior, nav2_core::Behavior)
26+

0 commit comments

Comments
 (0)