Skip to content

Commit 82328ca

Browse files
committed
Added check on active condition
1 parent 4065035 commit 82328ca

File tree

1 file changed

+16
-10
lines changed

1 file changed

+16
-10
lines changed

ur_controllers/src/freedrive_mode_controller.cpp

Lines changed: 16 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -169,6 +169,9 @@ ur_controllers::FreedriveModeController::on_deactivate(const rclcpp_lifecycle::S
169169
abort_command_interface_->get().set_value(1.0);
170170
freedrive_active_ = false;
171171

172+
freedrive_sub_timer_.reset();
173+
timer_started_ = false;
174+
172175
stop_logging_thread();
173176

174177
return CallbackReturn::SUCCESS;
@@ -224,17 +227,20 @@ controller_interface::return_type ur_controllers::FreedriveModeController::updat
224227
void FreedriveModeController::readFreedriveModeCmd(const std_msgs::msg::Bool::SharedPtr msg)
225228
{
226229
// Process the freedrive_mode command.
227-
if(msg->data)
230+
if (get_node()->get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
228231
{
229-
if((!freedrive_active_) && (!change_requested_)){
230-
freedrive_active_ = true;
231-
change_requested_ = true;
232-
start_timer();
233-
}
234-
} else{
235-
if((freedrive_active_) && (!change_requested_)){
236-
freedrive_active_ = false;
237-
change_requested_ = true;
232+
if(msg->data)
233+
{
234+
if((!freedrive_active_) && (!change_requested_)){
235+
freedrive_active_ = true;
236+
change_requested_ = true;
237+
start_timer();
238+
}
239+
} else{
240+
if((freedrive_active_) && (!change_requested_)){
241+
freedrive_active_ = false;
242+
change_requested_ = true;
243+
}
238244
}
239245
}
240246

0 commit comments

Comments
 (0)