From a6486ff08634f41b3c1592cb70ac9e71f8fc7ec2 Mon Sep 17 00:00:00 2001 From: JafarAbdi Date: Tue, 8 Oct 2024 23:55:05 +0100 Subject: [PATCH] Set joint_states_ to initial_value as well --- src/topic_based_system.cpp | 1 + test/ros2_control.test.py | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/src/topic_based_system.cpp b/src/topic_based_system.cpp index ee506dd..67a9ec9 100644 --- a/src/topic_based_system.cpp +++ b/src/topic_based_system.cpp @@ -91,6 +91,7 @@ CallbackReturn TopicBasedSystem::on_init(const hardware_interface::HardwareInfo& // Check the initial_value param is used if (!interface.initial_value.empty()) { + joint_states_[index][i] = std::stod(interface.initial_value); joint_commands_[index][i] = std::stod(interface.initial_value); } } diff --git a/test/ros2_control.test.py b/test/ros2_control.test.py index aecb540..0769f66 100644 --- a/test/ros2_control.test.py +++ b/test/ros2_control.test.py @@ -14,7 +14,6 @@ from launch.substitutions import ( LaunchConfiguration, PathJoinSubstitution, - ThisLaunchFileDir, ) from launch_ros.actions import Node