Skip to content

Commit 36317e2

Browse files
christophfroehlichdestogl
authored andcommitted
[JTC] Fix tests when state offset is used (backport #797)
* Simplify initialization of states * Rename read_state_from_hardware method * Don't set state_desired in on_activate --------- Co-authored-by: Dr. Denis <[email protected]>
1 parent c859569 commit 36317e2

File tree

4 files changed

+135
-82
lines changed

4 files changed

+135
-82
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -259,8 +259,14 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
259259
const rclcpp::Time & time, const JointTrajectoryPoint & desired_state,
260260
const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error);
261261

262-
void read_state_from_hardware(JointTrajectoryPoint & state);
262+
void read_state_from_state_interfaces(JointTrajectoryPoint & state);
263263

264+
/** Assign values from the command interfaces as state.
265+
* This is only possible if command AND state interfaces exist for the same type,
266+
* therefore needs check for both.
267+
* @param[out] state to be filled with values from command interfaces.
268+
* @return true if all interfaces exists and contain non-NaN values, false otherwise.
269+
*/
264270
bool read_state_from_command_interfaces(JointTrajectoryPoint & state);
265271
bool read_commands_from_command_interfaces(JointTrajectoryPoint & commands);
266272

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -195,7 +195,7 @@ controller_interface::return_type JointTrajectoryController::update(
195195

196196
// current state update
197197
state_current_.time_from_start.set__sec(0);
198-
read_state_from_hardware(state_current_);
198+
read_state_from_state_interfaces(state_current_);
199199

200200
// currently carrying out a trajectory
201201
if (has_active_trajectory())
@@ -417,7 +417,7 @@ controller_interface::return_type JointTrajectoryController::update(
417417
return controller_interface::return_type::OK;
418418
}
419419

420-
void JointTrajectoryController::read_state_from_hardware(JointTrajectoryPoint & state)
420+
void JointTrajectoryController::read_state_from_state_interfaces(JointTrajectoryPoint & state)
421421
{
422422
auto assign_point_from_interface =
423423
[&](std::vector<double> & trajectory_point_interface, const auto & joint_interface)
@@ -945,20 +945,21 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
945945

946946
subscriber_is_active_ = true;
947947

948-
// Initialize current state storage if hardware state has tracking offset
949-
read_state_from_hardware(state_current_);
950-
read_state_from_hardware(state_desired_);
951-
read_state_from_hardware(last_commanded_state_);
952-
// Handle restart of controller by reading from commands if
953-
// those are not nan
948+
// Handle restart of controller by reading from commands if those are not NaN (a controller was
949+
// running already)
954950
trajectory_msgs::msg::JointTrajectoryPoint state;
955951
resize_joint_trajectory_point(state, dof_);
956952
if (read_state_from_command_interfaces(state))
957953
{
958954
state_current_ = state;
959-
state_desired_ = state;
960955
last_commanded_state_ = state;
961956
}
957+
else
958+
{
959+
// Initialize current state storage from hardware
960+
read_state_from_state_interfaces(state_current_);
961+
read_state_from_state_interfaces(last_commanded_state_);
962+
}
962963

963964
// Should the controller start by holding position at the beginning of active state?
964965
if (params_.start_with_holding)

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 73 additions & 45 deletions
Original file line numberDiff line numberDiff line change
@@ -1704,21 +1704,23 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
17041704
#endif
17051705

17061706
// Testing that values are read from state interfaces when hardware is started for the first
1707-
// time and hardware state has offset --> this is indicated by NaN values in state interfaces
1707+
// time and hardware state has offset --> this is indicated by NaN values in command interfaces
17081708
TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_controller_start)
17091709
{
17101710
rclcpp::executors::SingleThreadedExecutor executor;
1711-
// default if false so it will not be actually set parameter
17121711
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
17131712

17141713
// set command values to NaN
1715-
for (size_t i = 0; i < 3; ++i)
1716-
{
1717-
joint_pos_[i] = std::numeric_limits<double>::quiet_NaN();
1718-
joint_vel_[i] = std::numeric_limits<double>::quiet_NaN();
1719-
joint_acc_[i] = std::numeric_limits<double>::quiet_NaN();
1720-
}
1721-
SetUpAndActivateTrajectoryController(executor, {is_open_loop_parameters}, true);
1714+
std::vector<double> initial_pos_cmd{3, std::numeric_limits<double>::quiet_NaN()};
1715+
std::vector<double> initial_vel_cmd{3, std::numeric_limits<double>::quiet_NaN()};
1716+
std::vector<double> initial_acc_cmd{3, std::numeric_limits<double>::quiet_NaN()};
1717+
1718+
SetUpAndActivateTrajectoryController(
1719+
executor, {is_open_loop_parameters}, true, 0., 1., false, initial_pos_cmd, initial_vel_cmd,
1720+
initial_acc_cmd);
1721+
1722+
// no call of update method, so the values should be read from state interfaces
1723+
// (command interface are NaN)
17221724

17231725
auto current_state_when_offset = traj_controller_->get_current_state_when_offset();
17241726

@@ -1727,70 +1729,96 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_co
17271729
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
17281730

17291731
// check velocity
1730-
if (
1731-
std::find(
1732-
state_interface_types_.begin(), state_interface_types_.end(),
1733-
hardware_interface::HW_IF_VELOCITY) != state_interface_types_.end() &&
1734-
traj_controller_->has_velocity_command_interface())
1732+
if (traj_controller_->has_velocity_state_interface())
17351733
{
1736-
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
1734+
EXPECT_EQ(current_state_when_offset.velocities[i], joint_state_vel_[i]);
17371735
}
17381736

17391737
// check acceleration
1740-
if (
1741-
std::find(
1742-
state_interface_types_.begin(), state_interface_types_.end(),
1743-
hardware_interface::HW_IF_ACCELERATION) != state_interface_types_.end() &&
1744-
traj_controller_->has_acceleration_command_interface())
1738+
if (traj_controller_->has_acceleration_state_interface())
17451739
{
1746-
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
1740+
EXPECT_EQ(current_state_when_offset.accelerations[i], joint_state_acc_[i]);
17471741
}
17481742
}
17491743

17501744
executor.cancel();
17511745
}
17521746

1753-
// Testing that values are read from state interfaces when hardware is started after some values
1747+
// Testing that values are read from command interfaces when hardware is started after some values
17541748
// are set on the hardware commands
17551749
TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_controller_start)
17561750
{
17571751
rclcpp::executors::SingleThreadedExecutor executor;
1758-
// default if false so it will not be actually set parameter
17591752
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
17601753

1761-
// set command values to NaN
1754+
// set command values to arbitrary values
1755+
std::vector<double> initial_pos_cmd, initial_vel_cmd, initial_acc_cmd;
17621756
for (size_t i = 0; i < 3; ++i)
17631757
{
1764-
joint_pos_[i] = 3.1 + static_cast<double>(i);
1765-
joint_vel_[i] = 0.25 + static_cast<double>(i);
1766-
joint_acc_[i] = 0.02 + static_cast<double>(i) / 10.0;
1758+
initial_pos_cmd.push_back(3.1 + static_cast<double>(i));
1759+
initial_vel_cmd.push_back(0.25 + static_cast<double>(i));
1760+
initial_acc_cmd.push_back(0.02 + static_cast<double>(i) / 10.0);
17671761
}
1768-
SetUpAndActivateTrajectoryController(executor, {is_open_loop_parameters}, true);
1762+
SetUpAndActivateTrajectoryController(
1763+
executor, {is_open_loop_parameters}, true, 0., 1., false, initial_pos_cmd, initial_vel_cmd,
1764+
initial_acc_cmd);
1765+
1766+
// no call of update method, so the values should be read from command interfaces
17691767

17701768
auto current_state_when_offset = traj_controller_->get_current_state_when_offset();
17711769

17721770
for (size_t i = 0; i < 3; ++i)
17731771
{
1774-
EXPECT_EQ(current_state_when_offset.positions[i], joint_pos_[i]);
1775-
1776-
// check velocity
1777-
if (
1778-
std::find(
1779-
state_interface_types_.begin(), state_interface_types_.end(),
1780-
hardware_interface::HW_IF_VELOCITY) != state_interface_types_.end() &&
1781-
traj_controller_->has_velocity_command_interface())
1772+
// check position
1773+
if (traj_controller_->has_position_command_interface())
17821774
{
1783-
EXPECT_EQ(current_state_when_offset.positions[i], joint_pos_[i]);
1775+
// check velocity
1776+
if (traj_controller_->has_velocity_state_interface())
1777+
{
1778+
if (traj_controller_->has_velocity_command_interface())
1779+
{
1780+
// check acceleration
1781+
if (traj_controller_->has_acceleration_state_interface())
1782+
{
1783+
if (traj_controller_->has_acceleration_command_interface())
1784+
{
1785+
// should have set it to last position + velocity + acceleration command
1786+
EXPECT_EQ(current_state_when_offset.positions[i], initial_pos_cmd[i]);
1787+
EXPECT_EQ(current_state_when_offset.velocities[i], initial_vel_cmd[i]);
1788+
EXPECT_EQ(current_state_when_offset.accelerations[i], initial_acc_cmd[i]);
1789+
}
1790+
else
1791+
{
1792+
// should have set it to the state interface instead
1793+
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
1794+
EXPECT_EQ(current_state_when_offset.velocities[i], joint_state_vel_[i]);
1795+
EXPECT_EQ(current_state_when_offset.accelerations[i], joint_state_acc_[i]);
1796+
}
1797+
}
1798+
else
1799+
{
1800+
// should have set it to last position + velocity command
1801+
EXPECT_EQ(current_state_when_offset.positions[i], initial_pos_cmd[i]);
1802+
EXPECT_EQ(current_state_when_offset.velocities[i], initial_vel_cmd[i]);
1803+
}
1804+
}
1805+
else
1806+
{
1807+
// should have set it to the state interface instead
1808+
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
1809+
EXPECT_EQ(current_state_when_offset.velocities[i], joint_state_vel_[i]);
1810+
}
1811+
}
1812+
else
1813+
{
1814+
// should have set it to last position command
1815+
EXPECT_EQ(current_state_when_offset.positions[i], initial_pos_cmd[i]);
1816+
}
17841817
}
1785-
1786-
// check acceleration
1787-
if (
1788-
std::find(
1789-
state_interface_types_.begin(), state_interface_types_.end(),
1790-
hardware_interface::HW_IF_ACCELERATION) != state_interface_types_.end() &&
1791-
traj_controller_->has_acceleration_command_interface())
1818+
else
17921819
{
1793-
EXPECT_EQ(current_state_when_offset.positions[i], joint_pos_[i]);
1820+
// should have set it to the state interface instead
1821+
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
17941822
}
17951823
}
17961824

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 45 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -222,7 +222,11 @@ class TrajectoryControllerTest : public ::testing::Test
222222
void SetUpAndActivateTrajectoryController(
223223
rclcpp::Executor & executor, const std::vector<rclcpp::Parameter> & parameters = {},
224224
bool separate_cmd_and_state_values = false, double k_p = 0.0, double ff = 1.0,
225-
bool angle_wraparound = false)
225+
bool angle_wraparound = false,
226+
const std::vector<double> initial_pos_joints = INITIAL_POS_JOINTS,
227+
const std::vector<double> initial_vel_joints = INITIAL_VEL_JOINTS,
228+
const std::vector<double> initial_acc_joints = INITIAL_ACC_JOINTS,
229+
const std::vector<double> initial_eff_joints = INITIAL_EFF_JOINTS)
226230
{
227231
SetUpTrajectoryController(executor);
228232

@@ -241,12 +245,17 @@ class TrajectoryControllerTest : public ::testing::Test
241245

242246
traj_controller_->get_node()->configure();
243247

244-
ActivateTrajectoryController(separate_cmd_and_state_values);
248+
ActivateTrajectoryController(
249+
separate_cmd_and_state_values, initial_pos_joints, initial_vel_joints, initial_acc_joints,
250+
initial_eff_joints);
245251
}
246252

247253
void ActivateTrajectoryController(
248254
bool separate_cmd_and_state_values = false,
249-
const std::vector<double> initial_pos_joints = INITIAL_POS_JOINTS)
255+
const std::vector<double> initial_pos_joints = INITIAL_POS_JOINTS,
256+
const std::vector<double> initial_vel_joints = INITIAL_VEL_JOINTS,
257+
const std::vector<double> initial_acc_joints = INITIAL_ACC_JOINTS,
258+
const std::vector<double> initial_eff_joints = INITIAL_EFF_JOINTS)
250259
{
251260
std::vector<hardware_interface::LoanedCommandInterface> cmd_interfaces;
252261
std::vector<hardware_interface::LoanedStateInterface> state_interfaces;
@@ -282,14 +291,17 @@ class TrajectoryControllerTest : public ::testing::Test
282291
cmd_interfaces.emplace_back(pos_cmd_interfaces_.back());
283292
cmd_interfaces.back().set_value(initial_pos_joints[i]);
284293
cmd_interfaces.emplace_back(vel_cmd_interfaces_.back());
285-
cmd_interfaces.back().set_value(INITIAL_VEL_JOINTS[i]);
294+
cmd_interfaces.back().set_value(initial_vel_joints[i]);
286295
cmd_interfaces.emplace_back(acc_cmd_interfaces_.back());
287-
cmd_interfaces.back().set_value(INITIAL_ACC_JOINTS[i]);
296+
cmd_interfaces.back().set_value(initial_acc_joints[i]);
288297
cmd_interfaces.emplace_back(eff_cmd_interfaces_.back());
289-
cmd_interfaces.back().set_value(INITIAL_EFF_JOINTS[i]);
290-
joint_state_pos_[i] = initial_pos_joints[i];
291-
joint_state_vel_[i] = INITIAL_VEL_JOINTS[i];
292-
joint_state_acc_[i] = INITIAL_ACC_JOINTS[i];
298+
cmd_interfaces.back().set_value(initial_eff_joints[i]);
299+
if (separate_cmd_and_state_values)
300+
{
301+
joint_state_pos_[i] = INITIAL_POS_JOINTS[i];
302+
joint_state_vel_[i] = INITIAL_VEL_JOINTS[i];
303+
joint_state_acc_[i] = INITIAL_ACC_JOINTS[i];
304+
}
293305
state_interfaces.emplace_back(pos_state_interfaces_.back());
294306
state_interfaces.emplace_back(vel_state_interfaces_.back());
295307
state_interfaces.emplace_back(acc_state_interfaces_.back());
@@ -491,27 +503,33 @@ class TrajectoryControllerTest : public ::testing::Test
491503
// --> set kp > 0.0 in test
492504
if (traj_controller_->has_velocity_command_interface())
493505
{
494-
EXPECT_TRUE(is_same_sign_or_zero(point.at(0) - joint_state_pos_[0], joint_vel_[0]))
495-
<< "current error: " << point.at(0) - joint_state_pos_[0] << ", velocity command is "
496-
<< joint_vel_[0];
497-
EXPECT_TRUE(is_same_sign_or_zero(point.at(1) - joint_state_pos_[1], joint_vel_[1]))
498-
<< "current error: " << point.at(1) - joint_state_pos_[1] << ", velocity command is "
499-
<< joint_vel_[1];
500-
EXPECT_TRUE(is_same_sign_or_zero(point.at(2) - joint_state_pos_[2], joint_vel_[2]))
501-
<< "current error: " << point.at(2) - joint_state_pos_[2] << ", velocity command is "
502-
<< joint_vel_[2];
506+
EXPECT_TRUE(
507+
is_same_sign_or_zero(point.at(0) - pos_state_interfaces_[0].get_value(), joint_vel_[0]))
508+
<< "current error: " << point.at(0) - pos_state_interfaces_[0].get_value()
509+
<< ", velocity command is " << joint_vel_[0];
510+
EXPECT_TRUE(
511+
is_same_sign_or_zero(point.at(1) - pos_state_interfaces_[1].get_value(), joint_vel_[1]))
512+
<< "current error: " << point.at(1) - pos_state_interfaces_[1].get_value()
513+
<< ", velocity command is " << joint_vel_[1];
514+
EXPECT_TRUE(
515+
is_same_sign_or_zero(point.at(2) - pos_state_interfaces_[2].get_value(), joint_vel_[2]))
516+
<< "current error: " << point.at(2) - pos_state_interfaces_[2].get_value()
517+
<< ", velocity command is " << joint_vel_[2];
503518
}
504519
if (traj_controller_->has_effort_command_interface())
505520
{
506-
EXPECT_TRUE(is_same_sign_or_zero(point.at(0) - joint_state_pos_[0], joint_eff_[0]))
507-
<< "current error: " << point.at(0) - joint_state_pos_[0] << ", effort command is "
508-
<< joint_eff_[0];
509-
EXPECT_TRUE(is_same_sign_or_zero(point.at(1) - joint_state_pos_[1], joint_eff_[1]))
510-
<< "current error: " << point.at(1) - joint_state_pos_[1] << ", effort command is "
511-
<< joint_eff_[1];
512-
EXPECT_TRUE(is_same_sign_or_zero(point.at(2) - joint_state_pos_[2], joint_eff_[2]))
513-
<< "current error: " << point.at(2) - joint_state_pos_[2] << ", effort command is "
514-
<< joint_eff_[2];
521+
EXPECT_TRUE(
522+
is_same_sign_or_zero(point.at(0) - pos_state_interfaces_[0].get_value(), joint_eff_[0]))
523+
<< "current error: " << point.at(0) - pos_state_interfaces_[0].get_value()
524+
<< ", effort command is " << joint_eff_[0];
525+
EXPECT_TRUE(
526+
is_same_sign_or_zero(point.at(1) - pos_state_interfaces_[1].get_value(), joint_eff_[1]))
527+
<< "current error: " << point.at(1) - pos_state_interfaces_[1].get_value()
528+
<< ", effort command is " << joint_eff_[1];
529+
EXPECT_TRUE(
530+
is_same_sign_or_zero(point.at(2) - pos_state_interfaces_[2].get_value(), joint_eff_[2]))
531+
<< "current error: " << point.at(2) - pos_state_interfaces_[2].get_value()
532+
<< ", effort command is " << joint_eff_[2];
515533
}
516534
}
517535
}

0 commit comments

Comments
 (0)