UTNuclearRoboticsPublic / netft_utils

A C++ class and a ROS node for ATI force/torque sensors connected to a Netbox.
http://wiki.ros.org/netft_utils
28 stars 29 forks source link

Multiple devices launch in ros2 #14

Closed chaitanyantr closed 4 months ago

chaitanyantr commented 4 months ago

Hi @AdamPettinger ,

Thankyou for maintaing the repo. I have multiple devices of nano17 F/T sensor. I have changed the IP_address of the devices in webpages

device-1 : 192.168.1.1 device-2 : 192.168.1.2

I launched the

ros2 run netft_utils netft_node --address 192.168.1.1

and

ros2 run netft_utils netft_node --address 192.168.1.2

in diff. terminals.

I see there is conflict in same topic names. May I know how to diff. the topic names based on the no. of devices.

image

chaitanyantr commented 4 months ago

Did changed the netft_node.cpp so it will take the ipaddress last digit and append to topic name.

// Extract the last digit of the IP address
  size_t last_dot_pos = address.find_last_of('.');
  if (last_dot_pos == string::npos) {
    cerr << "Invalid IP address format" << endl;
    exit(EXIT_FAILURE);
  }
  string last_digit = address.substr(last_dot_pos + 1);

  // Set up ROS publishers
  auto node = std::make_shared<rclcpp::Node>("netft_node" + last_digit);
  const rclcpp::QoS qos(10);
  rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr ready_pub = node->create_publisher<std_msgs::msg::Bool>("netft_ready" + last_digit, qos);
  rclcpp::Publisher<geometry_msgs::msg::WrenchStamped>::SharedPtr geo_pub = node->create_publisher<geometry_msgs::msg::WrenchStamped>("netft_data" + last_digit, 100);