Skip to content

Commit a9aca64

Browse files
saikishordestoglchristophfroehlich
authored
Add new get_value API for Handles and Interfaces (#1976)
--------- Co-authored-by: Dr. Denis <[email protected]> Co-authored-by: Christoph Fröhlich <[email protected]>
1 parent 45f871e commit a9aca64

20 files changed

+1116
-812
lines changed

Diff for: controller_interface/include/semantic_components/force_torque_sensor.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ class ForceTorqueSensor : public SemanticComponentInterface<geometry_msgs::msg::
9696
{
9797
if (existing_axes_[i])
9898
{
99-
forces[i] = state_interfaces_[interface_counter].get().get_value();
99+
forces[i] = state_interfaces_[interface_counter].get().get_value<double>().value();
100100
++interface_counter;
101101
}
102102
}
@@ -123,7 +123,7 @@ class ForceTorqueSensor : public SemanticComponentInterface<geometry_msgs::msg::
123123
{
124124
if (existing_axes_[i + FORCES_SIZE])
125125
{
126-
torques[i] = state_interfaces_[torque_interface_counter].get().get_value();
126+
torques[i] = state_interfaces_[torque_interface_counter].get().get_value<double>().value();
127127
++torque_interface_counter;
128128
}
129129
}

Diff for: controller_interface/include/semantic_components/imu_sensor.hpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
5252
std::array<double, 4> orientation;
5353
for (auto i = 0u; i < orientation.size(); ++i)
5454
{
55-
orientation[i] = state_interfaces_[i].get().get_value();
55+
orientation[i] = state_interfaces_[i].get().get_value<double>().value();
5656
}
5757
return orientation;
5858
}
@@ -69,7 +69,8 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
6969
const std::size_t interface_offset{4};
7070
for (auto i = 0u; i < angular_velocity.size(); ++i)
7171
{
72-
angular_velocity[i] = state_interfaces_[interface_offset + i].get().get_value();
72+
angular_velocity[i] =
73+
state_interfaces_[interface_offset + i].get().get_value<double>().value();
7374
}
7475
return angular_velocity;
7576
}
@@ -86,7 +87,8 @@ class IMUSensor : public SemanticComponentInterface<sensor_msgs::msg::Imu>
8687
const std::size_t interface_offset{7};
8788
for (auto i = 0u; i < linear_acceleration.size(); ++i)
8889
{
89-
linear_acceleration[i] = state_interfaces_[interface_offset + i].get().get_value();
90+
linear_acceleration[i] =
91+
state_interfaces_[interface_offset + i].get().get_value<double>().value();
9092
}
9193
return linear_acceleration;
9294
}

Diff for: controller_interface/include/semantic_components/pose_sensor.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ class PoseSensor : public SemanticComponentInterface<geometry_msgs::msg::Pose>
5050
std::array<double, 3> position;
5151
for (auto i = 0u; i < position.size(); ++i)
5252
{
53-
position[i] = state_interfaces_[i].get().get_value();
53+
position[i] = state_interfaces_[i].get().get_value<double>().value();
5454
}
5555
return position;
5656
}
@@ -67,7 +67,7 @@ class PoseSensor : public SemanticComponentInterface<geometry_msgs::msg::Pose>
6767
const std::size_t interface_offset{3};
6868
for (auto i = 0u; i < orientation.size(); ++i)
6969
{
70-
orientation[i] = state_interfaces_[interface_offset + i].get().get_value();
70+
orientation[i] = state_interfaces_[interface_offset + i].get().get_value<double>().value();
7171
}
7272
return orientation;
7373
}

Diff for: controller_interface/include/semantic_components/range_sensor.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ class RangeSensor : public SemanticComponentInterface<sensor_msgs::msg::Range>
3535
*
3636
* \return value of the range in meters
3737
*/
38-
float get_range() const { return state_interfaces_[0].get().get_value(); }
38+
float get_range() const { return state_interfaces_[0].get().get_value<double>().value(); }
3939

4040
/// Return Range message with range in meters
4141
/**

Diff for: controller_interface/include/semantic_components/semantic_component_interface.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ class SemanticComponentInterface
9393
// insert all the values
9494
for (auto i = 0u; i < state_interfaces_.size(); ++i)
9595
{
96-
values.emplace_back(state_interfaces_[i].get().get_value());
96+
values.emplace_back(state_interfaces_[i].get().get_value<double>().value());
9797
}
9898
return true;
9999
}

Diff for: controller_interface/test/test_chainable_controller_interface.cpp

+8-5
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,8 @@ TEST_F(ChainableControllerInterfaceTest, export_state_interfaces)
5252
EXPECT_EQ(exported_state_interfaces[0]->get_prefix_name(), TEST_CONTROLLER_NAME);
5353
EXPECT_EQ(exported_state_interfaces[0]->get_interface_name(), "test_state");
5454

55-
EXPECT_EQ(exported_state_interfaces[0]->get_value(), EXPORTED_STATE_INTERFACE_VALUE);
55+
EXPECT_EQ(
56+
exported_state_interfaces[0]->get_value<double>().value(), EXPORTED_STATE_INTERFACE_VALUE);
5657
}
5758

5859
TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces)
@@ -72,7 +73,7 @@ TEST_F(ChainableControllerInterfaceTest, export_reference_interfaces)
7273
EXPECT_EQ(reference_interfaces[0]->get_prefix_name(), TEST_CONTROLLER_NAME);
7374
EXPECT_EQ(reference_interfaces[0]->get_interface_name(), "test_itf");
7475

75-
EXPECT_EQ(reference_interfaces[0]->get_value(), INTERFACE_VALUE);
76+
EXPECT_EQ(reference_interfaces[0]->get_value<double>().value(), INTERFACE_VALUE);
7677
}
7778

7879
TEST_F(ChainableControllerInterfaceTest, interfaces_prefix_is_not_node_name)
@@ -120,7 +121,7 @@ TEST_F(ChainableControllerInterfaceTest, setting_chained_mode)
120121
EXPECT_FALSE(controller.is_in_chained_mode());
121122

122123
// Fail setting chained mode
123-
EXPECT_EQ(reference_interfaces[0]->get_value(), INTERFACE_VALUE);
124+
EXPECT_EQ(reference_interfaces[0]->get_value<double>().value(), INTERFACE_VALUE);
124125

125126
EXPECT_FALSE(controller.set_chained_mode(true));
126127
EXPECT_FALSE(controller.is_in_chained_mode());
@@ -129,11 +130,13 @@ TEST_F(ChainableControllerInterfaceTest, setting_chained_mode)
129130
EXPECT_FALSE(controller.is_in_chained_mode());
130131

131132
// Success setting chained mode
132-
reference_interfaces[0]->set_value(0.0);
133+
(void)reference_interfaces[0]->set_value(0.0);
133134

134135
EXPECT_TRUE(controller.set_chained_mode(true));
135136
EXPECT_TRUE(controller.is_in_chained_mode());
136-
EXPECT_EQ(exported_state_interfaces[0]->get_value(), EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE);
137+
EXPECT_EQ(
138+
exported_state_interfaces[0]->get_value<double>().value(),
139+
EXPORTED_STATE_INTERFACE_VALUE_IN_CHAINMODE);
137140

138141
controller.configure();
139142
EXPECT_TRUE(controller.set_chained_mode(false));

Diff for: controller_manager/test/test_chainable_controller/test_chainable_controller.cpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -101,21 +101,23 @@ controller_interface::return_type TestChainableController::update_and_write_comm
101101

102102
for (size_t i = 0; i < command_interfaces_.size(); ++i)
103103
{
104-
command_interfaces_[i].set_value(reference_interfaces_[i] - state_interfaces_[i].get_value());
104+
(void)command_interfaces_[i].set_value(
105+
reference_interfaces_[i] - state_interfaces_[i].get_value<double>().value());
105106
}
106107
// If there is a command interface then integrate and set it to the exported state interface data
107108
for (size_t i = 0; i < exported_state_interface_names_.size() && i < command_interfaces_.size();
108109
++i)
109110
{
110-
state_interfaces_values_[i] = command_interfaces_[i].get_value() * CONTROLLER_DT;
111+
state_interfaces_values_[i] =
112+
command_interfaces_[i].get_value<double>().value() * CONTROLLER_DT;
111113
}
112114
// If there is no command interface and if there is a state interface then just forward the same
113115
// value as in the state interface
114116
for (size_t i = 0; i < exported_state_interface_names_.size() && i < state_interfaces_.size() &&
115117
command_interfaces_.empty();
116118
++i)
117119
{
118-
state_interfaces_values_[i] = state_interfaces_[i].get_value();
120+
state_interfaces_values_[i] = state_interfaces_[i].get_value<double>().value();
119121
}
120122

121123
return controller_interface::return_type::OK;
@@ -240,7 +242,7 @@ std::vector<double> TestChainableController::get_state_interface_data() const
240242
std::vector<double> state_intr_data;
241243
for (const auto & interface : state_interfaces_)
242244
{
243-
state_intr_data.push_back(interface.get_value());
245+
state_intr_data.push_back(interface.get_value<double>().value());
244246
}
245247
return state_intr_data;
246248
}

Diff for: controller_manager/test/test_controller/test_controller.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ controller_interface::return_type TestController::update(
7171
// set value to hardware to produce and test different behaviors there
7272
if (!std::isnan(set_first_command_interface_value_to))
7373
{
74-
command_interfaces_[0].set_value(set_first_command_interface_value_to);
74+
(void)command_interfaces_[0].set_value(set_first_command_interface_value_to);
7575
// reset to be easier to test
7676
set_first_command_interface_value_to = std::numeric_limits<double>::quiet_NaN();
7777
}
@@ -90,7 +90,7 @@ controller_interface::return_type TestController::update(
9090
RCLCPP_DEBUG(
9191
get_node()->get_logger(), "Setting value of command interface '%s' to %f",
9292
command_interfaces_[i].get_name().c_str(), external_commands_for_testing_[i]);
93-
command_interfaces_[i].set_value(external_commands_for_testing_[i]);
93+
(void)command_interfaces_[i].set_value(external_commands_for_testing_[i]);
9494
}
9595
}
9696

@@ -187,7 +187,7 @@ std::vector<double> TestController::get_state_interface_data() const
187187
std::vector<double> state_intr_data;
188188
for (const auto & interface : state_interfaces_)
189189
{
190-
state_intr_data.push_back(interface.get_value());
190+
state_intr_data.push_back(interface.get_value<double>().value());
191191
}
192192
return state_intr_data;
193193
}

Diff for: controller_manager/test/test_controllers_chaining_with_controller_manager.cpp

+59-20
Original file line numberDiff line numberDiff line change
@@ -520,8 +520,12 @@ class TestControllerChainingWithControllerManager
520520
// Command of DiffDrive controller are references of PID controllers
521521
EXP_LEFT_WHEEL_REF = chained_ctrl_calculation(reference[0], EXP_LEFT_WHEEL_HW_STATE);
522522
EXP_RIGHT_WHEEL_REF = chained_ctrl_calculation(reference[1], EXP_RIGHT_WHEEL_HW_STATE);
523-
ASSERT_EQ(diff_drive_controller->command_interfaces_[0].get_value(), EXP_LEFT_WHEEL_REF);
524-
ASSERT_EQ(diff_drive_controller->command_interfaces_[1].get_value(), EXP_RIGHT_WHEEL_REF);
523+
ASSERT_EQ(
524+
diff_drive_controller->command_interfaces_[0].get_value<double>().value(),
525+
EXP_LEFT_WHEEL_REF);
526+
ASSERT_EQ(
527+
diff_drive_controller->command_interfaces_[1].get_value<double>().value(),
528+
EXP_RIGHT_WHEEL_REF);
525529
ASSERT_EQ(pid_left_wheel_controller->reference_interfaces_[0], EXP_LEFT_WHEEL_REF);
526530
ASSERT_EQ(pid_right_wheel_controller->reference_interfaces_[0], EXP_RIGHT_WHEEL_REF);
527531

@@ -537,21 +541,32 @@ class TestControllerChainingWithControllerManager
537541

538542
EXP_LEFT_WHEEL_CMD = chained_ctrl_calculation(EXP_LEFT_WHEEL_REF, EXP_LEFT_WHEEL_HW_STATE);
539543
EXP_LEFT_WHEEL_HW_STATE = hardware_calculation(EXP_LEFT_WHEEL_CMD);
540-
ASSERT_EQ(pid_left_wheel_controller->command_interfaces_[0].get_value(), EXP_LEFT_WHEEL_CMD);
541-
ASSERT_EQ(pid_left_wheel_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE);
544+
ASSERT_EQ(
545+
pid_left_wheel_controller->command_interfaces_[0].get_value<double>().value(),
546+
EXP_LEFT_WHEEL_CMD);
547+
ASSERT_EQ(
548+
pid_left_wheel_controller->state_interfaces_[0].get_value<double>().value(),
549+
EXP_LEFT_WHEEL_HW_STATE);
542550
// DiffDrive uses the same state
543-
ASSERT_EQ(diff_drive_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE);
551+
ASSERT_EQ(
552+
diff_drive_controller->state_interfaces_[0].get_value<double>().value(),
553+
EXP_LEFT_WHEEL_HW_STATE);
544554
// The state doesn't change wrt to any data from the hardware calculation
545555
ASSERT_EQ(robot_localization_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X);
546556
ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X);
547557

548558
EXP_RIGHT_WHEEL_CMD = chained_ctrl_calculation(EXP_RIGHT_WHEEL_REF, EXP_RIGHT_WHEEL_HW_STATE);
549559
EXP_RIGHT_WHEEL_HW_STATE = hardware_calculation(EXP_RIGHT_WHEEL_CMD);
550-
ASSERT_EQ(pid_right_wheel_controller->command_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_CMD);
551560
ASSERT_EQ(
552-
pid_right_wheel_controller->state_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_HW_STATE);
561+
pid_right_wheel_controller->command_interfaces_[0].get_value<double>().value(),
562+
EXP_RIGHT_WHEEL_CMD);
563+
ASSERT_EQ(
564+
pid_right_wheel_controller->state_interfaces_[0].get_value<double>().value(),
565+
EXP_RIGHT_WHEEL_HW_STATE);
553566
// DiffDrive uses the same state
554-
ASSERT_EQ(diff_drive_controller->state_interfaces_[1].get_value(), EXP_RIGHT_WHEEL_HW_STATE);
567+
ASSERT_EQ(
568+
diff_drive_controller->state_interfaces_[1].get_value<double>().value(),
569+
EXP_RIGHT_WHEEL_HW_STATE);
555570
// The state doesn't change wrt to any data from the hardware calculation
556571
ASSERT_EQ(robot_localization_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y);
557572
ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y);
@@ -811,10 +826,16 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers)
811826
EXP_LEFT_WHEEL_CMD = chained_ctrl_calculation(EXP_LEFT_WHEEL_REF, EXP_LEFT_WHEEL_HW_STATE);
812827
// 32 / 2
813828
EXP_LEFT_WHEEL_HW_STATE = hardware_calculation(EXP_LEFT_WHEEL_CMD);
814-
ASSERT_EQ(pid_left_wheel_controller->command_interfaces_[0].get_value(), EXP_LEFT_WHEEL_CMD);
815-
ASSERT_EQ(pid_left_wheel_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE);
829+
ASSERT_EQ(
830+
pid_left_wheel_controller->command_interfaces_[0].get_value<double>().value(),
831+
EXP_LEFT_WHEEL_CMD);
832+
ASSERT_EQ(
833+
pid_left_wheel_controller->state_interfaces_[0].get_value<double>().value(),
834+
EXP_LEFT_WHEEL_HW_STATE);
816835
// DiffDrive uses the same state
817-
ASSERT_EQ(diff_drive_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE);
836+
ASSERT_EQ(
837+
diff_drive_controller->state_interfaces_[0].get_value<double>().value(),
838+
EXP_LEFT_WHEEL_HW_STATE);
818839
// The state doesn't change wrt to any data from the hardware calculation
819840
ASSERT_EQ(robot_localization_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X);
820841
ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[0], EXP_STATE_ODOM_X);
@@ -823,13 +844,19 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers)
823844
EXP_RIGHT_WHEEL_CMD = chained_ctrl_calculation(EXP_RIGHT_WHEEL_REF, EXP_RIGHT_WHEEL_HW_STATE);
824845
// 128 / 2
825846
EXP_RIGHT_WHEEL_HW_STATE = hardware_calculation(EXP_RIGHT_WHEEL_CMD);
826-
ASSERT_EQ(pid_right_wheel_controller->command_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_CMD);
827-
ASSERT_EQ(pid_right_wheel_controller->state_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_HW_STATE);
847+
ASSERT_EQ(
848+
pid_right_wheel_controller->command_interfaces_[0].get_value<double>().value(),
849+
EXP_RIGHT_WHEEL_CMD);
850+
ASSERT_EQ(
851+
pid_right_wheel_controller->state_interfaces_[0].get_value<double>().value(),
852+
EXP_RIGHT_WHEEL_HW_STATE);
828853
ASSERT_EQ(odom_publisher_controller->internal_counter, 2u);
829854
ASSERT_EQ(sensor_fusion_controller->internal_counter, 6u);
830855
ASSERT_EQ(robot_localization_controller->internal_counter, 4u);
831856
// DiffDrive uses the same state
832-
ASSERT_EQ(diff_drive_controller->state_interfaces_[1].get_value(), EXP_RIGHT_WHEEL_HW_STATE);
857+
ASSERT_EQ(
858+
diff_drive_controller->state_interfaces_[1].get_value<double>().value(),
859+
EXP_RIGHT_WHEEL_HW_STATE);
833860
// The state doesn't change wrt to any data from the hardware calculation
834861
ASSERT_EQ(robot_localization_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y);
835862
ASSERT_EQ(odom_publisher_controller->get_state_interface_data()[1], EXP_STATE_ODOM_Y);
@@ -1986,19 +2013,31 @@ TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_add
19862013
EXP_LEFT_WHEEL_CMD = chained_ctrl_calculation(EXP_LEFT_WHEEL_REF, EXP_LEFT_WHEEL_HW_STATE);
19872014
// 32 / 2
19882015
EXP_LEFT_WHEEL_HW_STATE = hardware_calculation(EXP_LEFT_WHEEL_CMD);
1989-
ASSERT_EQ(pid_left_wheel_controller->command_interfaces_[0].get_value(), EXP_LEFT_WHEEL_CMD);
1990-
ASSERT_EQ(pid_left_wheel_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE);
2016+
ASSERT_EQ(
2017+
pid_left_wheel_controller->command_interfaces_[0].get_value<double>().value(),
2018+
EXP_LEFT_WHEEL_CMD);
2019+
ASSERT_EQ(
2020+
pid_left_wheel_controller->state_interfaces_[0].get_value<double>().value(),
2021+
EXP_LEFT_WHEEL_HW_STATE);
19912022
// DiffDrive uses the same state
1992-
ASSERT_EQ(diff_drive_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE);
2023+
ASSERT_EQ(
2024+
diff_drive_controller->state_interfaces_[0].get_value<double>().value(),
2025+
EXP_LEFT_WHEEL_HW_STATE);
19932026

19942027
// 128 - 0
19952028
EXP_RIGHT_WHEEL_CMD = chained_ctrl_calculation(EXP_RIGHT_WHEEL_REF, EXP_RIGHT_WHEEL_HW_STATE);
19962029
// 128 / 2
19972030
EXP_RIGHT_WHEEL_HW_STATE = hardware_calculation(EXP_RIGHT_WHEEL_CMD);
1998-
ASSERT_EQ(pid_right_wheel_controller->command_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_CMD);
1999-
ASSERT_EQ(pid_right_wheel_controller->state_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_HW_STATE);
2031+
ASSERT_EQ(
2032+
pid_right_wheel_controller->command_interfaces_[0].get_value<double>().value(),
2033+
EXP_RIGHT_WHEEL_CMD);
2034+
ASSERT_EQ(
2035+
pid_right_wheel_controller->state_interfaces_[0].get_value<double>().value(),
2036+
EXP_RIGHT_WHEEL_HW_STATE);
20002037
// DiffDrive uses the same state
2001-
ASSERT_EQ(diff_drive_controller->state_interfaces_[1].get_value(), EXP_RIGHT_WHEEL_HW_STATE);
2038+
ASSERT_EQ(
2039+
diff_drive_controller->state_interfaces_[1].get_value<double>().value(),
2040+
EXP_RIGHT_WHEEL_HW_STATE);
20022041

20032042
// update all controllers at once and see that all have expected values --> also checks the order
20042043
// of controller execution

Diff for: doc/migration.rst

+24
Original file line numberDiff line numberDiff line change
@@ -75,12 +75,36 @@ hardware_interface
7575
******************
7676
* ``test_components`` was moved to its own package. Update the dependencies if you are using them. (`#1325 <https://github.com/ros-controls/ros2_control/pull/1325>`_)
7777
* With (`#1683 <https://github.com/ros-controls/ros2_control/pull/1683>`_) the ``rclcpp_lifecycle::State & get_state()`` and ``void set_state(const rclcpp_lifecycle::State & new_state)`` are replaced by ``rclcpp_lifecycle::State & get_lifecycle_state()`` and ``void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)``. This change affects controllers and hardware. This is related to (`#1240 <https://github.com/ros-controls/ros2_control/pull/1240>`_) as variant support introduces ``get_state`` and ``set_state`` methods for setting/getting state of handles.
78+
* A new ``get_value`` that returns a ``std::optional`` was added to the ``CommandInterface`` and ``StateInterface``. This can be used to check if the value is available or not. (`#1976 <https://github.com/ros-controls/ros2_control/pull/1976>`_)
7879

7980
Adaption of Command-/StateInterfaces
8081
***************************************
8182

83+
* The handles for ``Command-/StateInterfaces`` have new set/get methods to access the values.
8284
* ``Command-/StateInterfaces`` are now created and exported automatically by the framework via the ``on_export_command_interfaces()`` or ``on_export_state_interfaces()`` methods based on the interfaces defined in the ``ros2_control`` XML-tag, which get parsed and the ``InterfaceDescription`` is created accordingly (check the `hardware_info.hpp <https://github.com/ros-controls/ros2_control/tree/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/hardware_info.hpp>`__). The memory is now allocated in the handle itself.
8385

86+
Access to Command-/StateInterfaces
87+
----------------------------------
88+
89+
Earlier code will issue compile-time warnings like:
90+
91+
.. code::
92+
93+
warning: ‘double hardware_interface::Handle::get_value() const’ is deprecated: Use std::optional<T> get_value() or bool get_value(double & value) instead to retrieve the value. [-Wdeprecated-declarations]
94+
warning: ignoring return value of ‘bool hardware_interface::Handle::set_value(const T&) [with T = double]’ [-Wunused-result]
95+
96+
The old methods are deprecated and will be removed in the future. The new methods are:
97+
98+
* ``std::optional<T> get_value()`` or ``bool get_value(T & value)`` for getting the value.
99+
* ``bool set_value(const T & value)`` for setting the value.
100+
101+
The return value ``bool`` or ``std::optional<T>`` with ``get_value`` can be used to check if the value is available or not. Similarly, the ``set_value`` method returns a ``bool`` to check if the value was set or not.
102+
The ``get_value`` method will return an empty ``std::nullopt`` or ``false`` if the value is not available. The ``set_value`` method will return ``false`` if the value was not set.
103+
104+
.. note::
105+
Checking the result of these operations is important as the value might not be available or the value might not be set.
106+
This is usually the case when the ros2_control framework has some asynchronous operations due to asynchronous controllers or asynchronous hardware components where different threads are involved to access the same data.
107+
84108
Migration of Command-/StateInterfaces
85109
-------------------------------------
86110
To adapt to the new way of creating and exporting ``Command-/StateInterfaces`` follow those steps:

0 commit comments

Comments
 (0)