|
1 |
| -#include <ros/ros.h> |
2 |
| - |
3 | 1 | #include "franka_ros_interface/sensor_data/sensor_subscriber_handler.h"
|
4 | 2 |
|
5 | 3 | int main(int argc, char **argv) {
|
6 |
| - ros::init(argc, argv, "sensor_subscriber_node", ros::init_options::AnonymousName); |
| 4 | + ros::init(argc, argv, "sensor_data_subscriber_node", ros::init_options::AnonymousName); |
7 | 5 |
|
8 |
| - ros::NodeHandle n; |
| 6 | + ros::NodeHandle n("~"); |
9 | 7 | franka_ros_interface::SensorSubscriberHandler handler(n);
|
10 |
| - std::string robot_num; |
11 |
| - if (n.getParam("robot_num", robot_num)) |
| 8 | + int robot_num; |
| 9 | + n.param("robot_num", robot_num, 1); |
| 10 | + ros::Subscriber sub; |
| 11 | + if (robot_num == 1) |
12 | 12 | {
|
13 |
| - if (robot_num == "1") |
14 |
| - { |
15 |
| - ros::Subscriber sub = n.subscribe("franka_ros_interface/sensor", 10, &franka_ros_interface::SensorSubscriberHandler::SensorSubscriberCallback, &handler); |
16 |
| - } |
17 |
| - else |
18 |
| - { |
19 |
| - ros::Subscriber sub = n.subscribe("franka_ros_interface_"+robot_num+"/sensor", 10, &franka_ros_interface::SensorSubscriberHandler::SensorSubscriberCallback, &handler); |
20 |
| - } |
| 13 | + sub = n.subscribe("/franka_ros_interface/sensor", 10, &franka_ros_interface::SensorSubscriberHandler::SensorSubscriberCallback, &handler); |
21 | 14 | }
|
22 | 15 | else
|
23 | 16 | {
|
24 |
| - ros::Subscriber sub = n.subscribe("franka_ros_interface/sensor", 10, &franka_ros_interface::SensorSubscriberHandler::SensorSubscriberCallback, &handler); |
| 17 | + std::string robot_num_string = std::to_string(robot_num); |
| 18 | + sub = n.subscribe("/franka_ros_interface_"+robot_num_string+"/sensor", 10, &franka_ros_interface::SensorSubscriberHandler::SensorSubscriberCallback, &handler); |
25 | 19 | }
|
26 | 20 |
|
27 | 21 | ros::spin();
|
|
0 commit comments