-
Notifications
You must be signed in to change notification settings - Fork 468
Description
Bug report
Required Info:
- Operating System:
- Ubuntu 18.04
- Installation type:
- from source
- Version or commit hash:
- Dashing and latest
- DDS implementation:
- Fast-RTPS
- Client library (if applicable):
- rclcpp
Steps to reproduce issue
I tested it using changed code from https://github.com/ros2/examples/blob/master/rclcpp/minimal_timer/lambda.cpp
#include <chrono>
#include <memory>
#include <glib.h>
#include "rclcpp/rclcpp.hpp"
using namespace std::chrono_literals;
class MinimalTimer : public rclcpp::Node
{
public:
MinimalTimer()
: Node("minimal_timer")
{
auto timer_callback = [this]() -> void {
RCLCPP_INFO(this->get_logger(), "Timer Expired. Timer cancel");
timer_->cancel();
};
timer_ = create_wall_timer(500ms, timer_callback);
}
// for test, set public visibility
// private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::TimerBase::SharedPtr timer2_;
};
GMainLoop *mainloop;
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> exec;
std::shared_ptr<MinimalTimer> node;
gboolean TimerExpired(gpointer data) {
if (node->timer_->is_canceled()){
RCLCPP_INFO(node->get_logger(), "Timer is cancelled and reset");
node->timer_->reset();
}else {
RCLCPP_INFO(node->get_logger(), "Timer is not cancelled");
}
return true;
}
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
node = std::make_shared<MinimalTimer>();
exec->add_node(node);
mainloop = g_main_loop_new(nullptr, false);
g_timeout_add(1000, TimerExpired, nullptr);
g_thread_new(nullptr,
[](gpointer data) -> gpointer {
exec->spin();
return nullptr;
},
static_cast<void *>(node.get()));
g_main_loop_run(mainloop);
rclcpp::shutdown();
return 0;
}
And change rclcpp/minimal_timer/CMakeLists.txt
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
+INCLUDE(FindPkgConfig)
+PKG_CHECK_MODULES(PKGS REQUIRED
+ glib-2.0
+)
+
+FOREACH(FLAG ${PKGS_CFLAGS})
+ SET(EXTRA_CXXFLAGS "${EXTRA_CXXFLAGS} ${FLAG}")
+ENDFOREACH(FLAG)
+
+SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${EXTRA_CXXFLAGS}")
+
add_executable(timer_lambda lambda.cpp)
ament_target_dependencies(timer_lambda rclcpp)
+TARGET_LINK_LIBRARIES(timer_lambda ${PKGS_LDFLAGS})
+
add_executable(timer_member_function member_function.cpp)
Expected behavior
[INFO] [minimal_timer]: Timer Expired. Timer cancel
[INFO] [minimal_timer]: Timer was cancelled and reset
[INFO] [minimal_timer]: Timer Expired. Timer cancel
[INFO] [minimal_timer]: Timer was cancelled and reset
[INFO] [minimal_timer]: Timer Expired. Timer cancel
Actual behavior
[INFO] [minimal_timer]: Timer Expired. Timer cancel
[INFO] [minimal_timer]: Timer was cancelled and reset
[INFO] [minimal_timer]: Timer was not cancelled
[INFO] [minimal_timer]: Timer was not cancelled
[INFO] [minimal_timer]: Timer was not cancelled
Additional information
Although reset a cancelled timer, the timer callback does not called because wait_set does not reset for the timer. I think guard condition should be triggered.