Skip to content

[CI] test_force_torque_sensor_broadcaster regularily times out (backport #1639) #1641

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

Closed
wants to merge 1 commit into from
Closed
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
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,12 @@ controller_interface::CallbackReturn ForceTorqueSensorBroadcaster::on_configure(
{
force_torque_sensor_ = std::make_unique<semantic_components::ForceTorqueSensor>(
semantic_components::ForceTorqueSensor(params_.sensor_name));

// TODO(juliaj): remove the logging after resolving
// https://github.com/ros-controls/ros2_controllers/issues/1574
RCLCPP_INFO(
get_node()->get_logger(), "Initialized force_torque_sensor with sensor name %s",
params_.sensor_name.c_str());
}
else
{
Expand All @@ -85,6 +91,14 @@ controller_interface::CallbackReturn ForceTorqueSensorBroadcaster::on_configure(
semantic_components::ForceTorqueSensor(
force_names.x, force_names.y, force_names.z, torque_names.x, torque_names.y,
torque_names.z));

// TODO(juliaj): remove the logging after resolving
// https://github.com/ros-controls/ros2_controllers/issues/1574
RCLCPP_INFO(
get_node()->get_logger(),
"Initialized force_torque_sensor with interface names %s, %s, %s, %s, %s, %s",
force_names.x.c_str(), force_names.y.c_str(), force_names.z.c_str(), torque_names.x.c_str(),
torque_names.y.c_str(), torque_names.z.c_str());
}

try
Expand All @@ -102,11 +116,19 @@ controller_interface::CallbackReturn ForceTorqueSensorBroadcaster::on_configure(
return controller_interface::CallbackReturn::ERROR;
}

// TODO(juliaj): remove the logging after resolving
// https://github.com/ros-controls/ros2_controllers/issues/1574
RCLCPP_INFO(get_node()->get_logger(), "Locking realtime publisher");
realtime_publisher_->lock();
RCLCPP_INFO(get_node()->get_logger(), "Locked realtime publisher");

realtime_publisher_->msg_.header.frame_id = params_.frame_id;

RCLCPP_INFO(get_node()->get_logger(), "Unlocking realtime publisher");
realtime_publisher_->unlock();
RCLCPP_INFO(get_node()->get_logger(), "Unlocked realtime publisher");

RCLCPP_DEBUG(get_node()->get_logger(), "configure successful");
RCLCPP_INFO(get_node()->get_logger(), "Configure successful");
return controller_interface::CallbackReturn::SUCCESS;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,13 @@ void ForceTorqueSensorBroadcasterTest::SetUp()
fts_broadcaster_ = std::make_unique<FriendForceTorqueSensorBroadcaster>();
}

void ForceTorqueSensorBroadcasterTest::TearDown() { fts_broadcaster_.reset(nullptr); }
void ForceTorqueSensorBroadcasterTest::TearDown()
{
// TODO(juliaj): remove the logging after resolving
// https://github.com/ros-controls/ros2_controllers/issues/1574
RCLCPP_INFO(fts_broadcaster_->get_node()->get_logger(), "In TearDown");
fts_broadcaster_.reset(nullptr);
}

void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster()
{
Expand All @@ -67,6 +73,9 @@ void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster()
state_ifs.emplace_back(fts_torque_z_);

fts_broadcaster_->assign_interfaces({}, std::move(state_ifs));
// TODO(juliaj): remove the logging after resolving
// https://github.com/ros-controls/ros2_controllers/issues/1574
RCLCPP_INFO(fts_broadcaster_->get_node()->get_logger(), "FTSBroadcaster setup done");
}

void ForceTorqueSensorBroadcasterTest::subscribe_and_get_message(
Expand Down Expand Up @@ -181,13 +190,19 @@ TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Configure_Success)
{
SetUpFTSBroadcaster();

// TODO(juliaj): remove the logging after resolving
// https://github.com/ros-controls/ros2_controllers/issues/1574
RCLCPP_INFO(fts_broadcaster_->get_node()->get_logger(), "Setting up interface names");

// set the 'interface_names'
fts_broadcaster_->get_node()->set_parameter({"interface_names.force.x", "fts_sensor/force.x"});
fts_broadcaster_->get_node()->set_parameter({"interface_names.torque.z", "fts_sensor/torque.z"});

RCLCPP_INFO(fts_broadcaster_->get_node()->get_logger(), "Setting up frame_id");
// set the 'frame_id'
fts_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});

RCLCPP_INFO(fts_broadcaster_->get_node()->get_logger(), "Calling on_configure");
// configure passed
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
}
Expand Down
Loading