Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

control mode only available in commanding active (#236) #240

Merged
merged 1 commit into from
Dec 14, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 12 additions & 12 deletions lbr_fri_ros2/src/async_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,19 @@ void AsyncClient::onStateChange(KUKA::FRI::ESessionState old_state,
// initialize command
state_interface_ptr_->set_state(robotState());
command_interface_ptr_->init_command(state_interface_ptr_->get_state());
}

void AsyncClient::monitor() { state_interface_ptr_->set_state(robotState()); };

void AsyncClient::waitForCommand() {
KUKA::FRI::LBRClient::waitForCommand();
state_interface_ptr_->set_state(robotState());
command_interface_ptr_->init_command(state_interface_ptr_->get_state());
command_interface_ptr_->buffered_command_to_fri(robotCommand(),
state_interface_ptr_->get_state());
}

void AsyncClient::command() {
// if robot is in impedance or Cartesian impedance control mode, override open_loop_ to false
// also refer to https://github.com/lbr-stack/lbr_fri_ros2_stack/issues/226
auto control_mode = robotState().getControlMode();
Expand All @@ -84,19 +96,7 @@ void AsyncClient::onStateChange(KUKA::FRI::ESessionState old_state,
open_loop_ = false;
}
}
}

void AsyncClient::monitor() { state_interface_ptr_->set_state(robotState()); };

void AsyncClient::waitForCommand() {
KUKA::FRI::LBRClient::waitForCommand();
state_interface_ptr_->set_state(robotState());
command_interface_ptr_->init_command(state_interface_ptr_->get_state());
command_interface_ptr_->buffered_command_to_fri(robotCommand(),
state_interface_ptr_->get_state());
}

void AsyncClient::command() {
if (open_loop_) {
state_interface_ptr_->set_state_open_loop(robotState(),
command_interface_ptr_->get_command().joint_position);
Expand Down
6 changes: 0 additions & 6 deletions lbr_ros2_control/src/system_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,12 +228,6 @@ controller_interface::CallbackReturn SystemInterface::on_activate(const rclcpp_l
RCLCPP_INFO_STREAM(rclcpp::get_logger(LOGGER_NAME), lbr_fri_ros2::ColorScheme::OKGREEN
<< "Robot connected"
<< lbr_fri_ros2::ColorScheme::ENDC);
RCLCPP_INFO_STREAM(rclcpp::get_logger(LOGGER_NAME),
"Control mode '"
<< lbr_fri_ros2::EnumMaps::control_mode_map(
async_client_ptr_->get_state_interface()->get_state().control_mode)
.c_str()
<< "'");
RCLCPP_INFO(rclcpp::get_logger(LOGGER_NAME), "Sample time %.3f s / %.1f Hz",
async_client_ptr_->get_state_interface()->get_state().sample_time,
1. / async_client_ptr_->get_state_interface()->get_state().sample_time);
Expand Down
Loading