Skip to content
Open
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
1 change: 1 addition & 0 deletions isaac_ros_foundationpose/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@

<depend>message_filters</depend>
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<depend>sensor_msgs</depend>
<depend>vision_msgs</depend>
<depend>assimp</depend>
Expand Down
19 changes: 17 additions & 2 deletions isaac_ros_foundationpose/src/foundationpose_selector_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include <rclcpp/time.hpp>
#include <std_msgs/msg/empty.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/camera_info.hpp>

Expand Down Expand Up @@ -107,13 +108,18 @@ class Selector : public rclcpp::Node
this->create_subscription<isaac_ros_tensor_list_interfaces::msg::TensorList>(
"pose_estimation/pose_matrix_output", 1, std::bind(&Selector::poseResetCallback, this, _1));

// Create subscriber for reset requests
reset_request_sub_ =
this->create_subscription<std_msgs::msg::Empty>(
"reset", 1, std::bind(&Selector::resetRequestCallback, this, _1));

// reset period in ms after which pose estimation will be triggered
this->declare_parameter<int>("reset_period", 20000);
this->get_parameter("reset_period", reset_period_);

timer_ = this->create_wall_timer(
std::chrono::milliseconds(reset_period_),
std::bind(&Selector::timerCallback, this));
std::bind(&Selector::resetCallback, this));
}

void selectionCallback(
Expand Down Expand Up @@ -159,7 +165,14 @@ class Selector : public rclcpp::Node
state_ = kTracking;
}

void timerCallback()
void resetRequestCallback(const std_msgs::msg::Empty::ConstSharedPtr & request_msg)
{
(void) request_msg; // Supress unused parameter warning

resetCallback();
}

void resetCallback()
{
std::unique_lock<std::mutex> lock(mutex_);
state_ = State::kPoseEstimation;
Expand Down Expand Up @@ -198,6 +211,8 @@ class Selector : public rclcpp::Node
rclcpp::Subscription<isaac_ros_tensor_list_interfaces::msg::TensorList>::SharedPtr
pose_estimation_output_sub_;

rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr reset_request_sub_;

enum State
{
kTracking,
Expand Down