Skip to content

Commit d099cff

Browse files
authored
Add support for positional target frame arguments for transform wrench node (#2040)
1 parent 36cfca8 commit d099cff

File tree

3 files changed

+55
-3
lines changed

3 files changed

+55
-3
lines changed

force_torque_sensor_broadcaster/doc/userdoc.rst

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,11 +44,20 @@ The node subscribes to wrench messages from the broadcaster (either raw or filte
4444

4545
Usage
4646
^^^^^
47-
The wrench transformer node can be launched as a standalone executable:
47+
The wrench transformer can be launched with target frames passed directly as positional arguments:
4848

4949
.. code-block:: bash
5050
51-
ros2 run force_torque_sensor_broadcaster wrench_transformer_node
51+
ros2 run force_torque_sensor_broadcaster wrench_transformer_node frame1 frame2
52+
53+
Target frames may also be set via the ``target_frames`` parameter:
54+
55+
.. code-block:: bash
56+
57+
ros2 run force_torque_sensor_broadcaster wrench_transformer_node \
58+
--ros-args -p target_frames:="['frame1','frame2']"
59+
60+
Positional arguments override the parameter value when both are provided.
5261

5362
Wrench Transformer Parameters
5463
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

force_torque_sensor_broadcaster/src/wrench_transformer.cpp

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
#include <limits>
2222
#include <memory>
2323
#include <string>
24+
#include <vector>
2425

2526
#include "tf2/utils.hpp"
2627

@@ -186,8 +187,17 @@ void WrenchTransformer::setup_publishers()
186187

187188
int run_wrench_transformer(int argc, char ** argv)
188189
{
189-
rclcpp::init(argc, argv);
190+
std::vector<std::string> non_ros_args = rclcpp::init_and_remove_ros_arguments(argc, argv);
191+
std::vector<std::string> target_frames_args;
192+
for (size_t i = 1; i < non_ros_args.size(); ++i)
193+
{
194+
target_frames_args.push_back(non_ros_args[i]);
195+
}
190196
rclcpp::NodeOptions options;
197+
if (!target_frames_args.empty())
198+
{
199+
options.append_parameter_override("target_frames", rclcpp::ParameterValue(target_frames_args));
200+
}
191201
auto node = std::make_shared<WrenchTransformer>(options);
192202
node->init();
193203
rclcpp::spin(node);

force_torque_sensor_broadcaster/test/test_wrench_transformer.cpp

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -688,6 +688,39 @@ TEST_F(TestWrenchTransformer, RunWrenchTransformerFunction)
688688
rclcpp::init(0, nullptr);
689689
}
690690

691+
TEST_F(TestWrenchTransformer, RunWrenchTransformerWithPositionalArgs)
692+
{
693+
rclcpp::shutdown();
694+
695+
// Prepare test arguments with positional arguments
696+
// This simulates how the node would be launched with positional arguments directly
697+
int argc = 3;
698+
char arg0[] = "test_wrench_transformer";
699+
char arg1[] = "base_link";
700+
char arg2[] = "end_effector";
701+
char * argv[] = {arg0, arg1, arg2, nullptr};
702+
703+
std::atomic<bool> function_started{false};
704+
std::thread test_thread(
705+
[&]()
706+
{
707+
function_started = true;
708+
force_torque_sensor_broadcaster::run_wrench_transformer(argc, argv);
709+
});
710+
711+
std::this_thread::sleep_for(std::chrono::milliseconds(300));
712+
EXPECT_TRUE(function_started);
713+
714+
rclcpp::shutdown();
715+
716+
if (test_thread.joinable())
717+
{
718+
test_thread.join();
719+
}
720+
721+
rclcpp::init(0, nullptr);
722+
}
723+
691724
int main(int argc, char ** argv)
692725
{
693726
::testing::InitGoogleMock(&argc, argv);

0 commit comments

Comments
 (0)