Skip to content

Commit b13ae5b

Browse files
[JTC] Fix tests when state offset is used (#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 f1a5397 commit b13ae5b

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

+7-1
Original file line numberDiff line numberDiff line change
@@ -261,8 +261,14 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
261261
const rclcpp::Time & time, const JointTrajectoryPoint & desired_state,
262262
const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error);
263263

264-
void read_state_from_hardware(JointTrajectoryPoint & state);
264+
void read_state_from_state_interfaces(JointTrajectoryPoint & state);
265265

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

joint_trajectory_controller/src/joint_trajectory_controller.cpp

+10-9
Original file line numberDiff line numberDiff line change
@@ -175,7 +175,7 @@ controller_interface::return_type JointTrajectoryController::update(
175175

176176
// current state update
177177
state_current_.time_from_start.set__sec(0);
178-
read_state_from_hardware(state_current_);
178+
read_state_from_state_interfaces(state_current_);
179179

180180
// currently carrying out a trajectory
181181
if (has_active_trajectory())
@@ -397,7 +397,7 @@ controller_interface::return_type JointTrajectoryController::update(
397397
return controller_interface::return_type::OK;
398398
}
399399

400-
void JointTrajectoryController::read_state_from_hardware(JointTrajectoryPoint & state)
400+
void JointTrajectoryController::read_state_from_state_interfaces(JointTrajectoryPoint & state)
401401
{
402402
auto assign_point_from_interface =
403403
[&](std::vector<double> & trajectory_point_interface, const auto & joint_interface)
@@ -951,20 +951,21 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
951951

952952
subscriber_is_active_ = true;
953953

954-
// Initialize current state storage if hardware state has tracking offset
955-
read_state_from_hardware(state_current_);
956-
read_state_from_hardware(state_desired_);
957-
read_state_from_hardware(last_commanded_state_);
958-
// Handle restart of controller by reading from commands if
959-
// those are not nan
954+
// Handle restart of controller by reading from commands if those are not NaN (a controller was
955+
// running already)
960956
trajectory_msgs::msg::JointTrajectoryPoint state;
961957
resize_joint_trajectory_point(state, dof_);
962958
if (read_state_from_command_interfaces(state))
963959
{
964960
state_current_ = state;
965-
state_desired_ = state;
966961
last_commanded_state_ = state;
967962
}
963+
else
964+
{
965+
// Initialize current state storage from hardware
966+
read_state_from_state_interfaces(state_current_);
967+
read_state_from_state_interfaces(last_commanded_state_);
968+
}
968969

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

joint_trajectory_controller/test/test_trajectory_controller.cpp

+73-45
Original file line numberDiff line numberDiff line change
@@ -1668,21 +1668,23 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
16681668
#endif
16691669

16701670
// Testing that values are read from state interfaces when hardware is started for the first
1671-
// time and hardware state has offset --> this is indicated by NaN values in state interfaces
1671+
// time and hardware state has offset --> this is indicated by NaN values in command interfaces
16721672
TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_controller_start)
16731673
{
16741674
rclcpp::executors::SingleThreadedExecutor executor;
1675-
// default if false so it will not be actually set parameter
16761675
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
16771676

16781677
// set command values to NaN
1679-
for (size_t i = 0; i < 3; ++i)
1680-
{
1681-
joint_pos_[i] = std::numeric_limits<double>::quiet_NaN();
1682-
joint_vel_[i] = std::numeric_limits<double>::quiet_NaN();
1683-
joint_acc_[i] = std::numeric_limits<double>::quiet_NaN();
1684-
}
1685-
SetUpAndActivateTrajectoryController(executor, {is_open_loop_parameters}, true);
1678+
std::vector<double> initial_pos_cmd{3, std::numeric_limits<double>::quiet_NaN()};
1679+
std::vector<double> initial_vel_cmd{3, std::numeric_limits<double>::quiet_NaN()};
1680+
std::vector<double> initial_acc_cmd{3, std::numeric_limits<double>::quiet_NaN()};
1681+
1682+
SetUpAndActivateTrajectoryController(
1683+
executor, {is_open_loop_parameters}, true, 0., 1., false, initial_pos_cmd, initial_vel_cmd,
1684+
initial_acc_cmd);
1685+
1686+
// no call of update method, so the values should be read from state interfaces
1687+
// (command interface are NaN)
16861688

16871689
auto current_state_when_offset = traj_controller_->get_current_state_when_offset();
16881690

@@ -1691,70 +1693,96 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_co
16911693
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
16921694

16931695
// check velocity
1694-
if (
1695-
std::find(
1696-
state_interface_types_.begin(), state_interface_types_.end(),
1697-
hardware_interface::HW_IF_VELOCITY) != state_interface_types_.end() &&
1698-
traj_controller_->has_velocity_command_interface())
1696+
if (traj_controller_->has_velocity_state_interface())
16991697
{
1700-
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
1698+
EXPECT_EQ(current_state_when_offset.velocities[i], joint_state_vel_[i]);
17011699
}
17021700

17031701
// check acceleration
1704-
if (
1705-
std::find(
1706-
state_interface_types_.begin(), state_interface_types_.end(),
1707-
hardware_interface::HW_IF_ACCELERATION) != state_interface_types_.end() &&
1708-
traj_controller_->has_acceleration_command_interface())
1702+
if (traj_controller_->has_acceleration_state_interface())
17091703
{
1710-
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
1704+
EXPECT_EQ(current_state_when_offset.accelerations[i], joint_state_acc_[i]);
17111705
}
17121706
}
17131707

17141708
executor.cancel();
17151709
}
17161710

1717-
// Testing that values are read from state interfaces when hardware is started after some values
1711+
// Testing that values are read from command interfaces when hardware is started after some values
17181712
// are set on the hardware commands
17191713
TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_controller_start)
17201714
{
17211715
rclcpp::executors::SingleThreadedExecutor executor;
1722-
// default if false so it will not be actually set parameter
17231716
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
17241717

1725-
// set command values to NaN
1718+
// set command values to arbitrary values
1719+
std::vector<double> initial_pos_cmd, initial_vel_cmd, initial_acc_cmd;
17261720
for (size_t i = 0; i < 3; ++i)
17271721
{
1728-
joint_pos_[i] = 3.1 + static_cast<double>(i);
1729-
joint_vel_[i] = 0.25 + static_cast<double>(i);
1730-
joint_acc_[i] = 0.02 + static_cast<double>(i) / 10.0;
1722+
initial_pos_cmd.push_back(3.1 + static_cast<double>(i));
1723+
initial_vel_cmd.push_back(0.25 + static_cast<double>(i));
1724+
initial_acc_cmd.push_back(0.02 + static_cast<double>(i) / 10.0);
17311725
}
1732-
SetUpAndActivateTrajectoryController(executor, {is_open_loop_parameters}, true);
1726+
SetUpAndActivateTrajectoryController(
1727+
executor, {is_open_loop_parameters}, true, 0., 1., false, initial_pos_cmd, initial_vel_cmd,
1728+
initial_acc_cmd);
1729+
1730+
// no call of update method, so the values should be read from command interfaces
17331731

17341732
auto current_state_when_offset = traj_controller_->get_current_state_when_offset();
17351733

17361734
for (size_t i = 0; i < 3; ++i)
17371735
{
1738-
EXPECT_EQ(current_state_when_offset.positions[i], joint_pos_[i]);
1739-
1740-
// check velocity
1741-
if (
1742-
std::find(
1743-
state_interface_types_.begin(), state_interface_types_.end(),
1744-
hardware_interface::HW_IF_VELOCITY) != state_interface_types_.end() &&
1745-
traj_controller_->has_velocity_command_interface())
1736+
// check position
1737+
if (traj_controller_->has_position_command_interface())
17461738
{
1747-
EXPECT_EQ(current_state_when_offset.positions[i], joint_pos_[i]);
1739+
// check velocity
1740+
if (traj_controller_->has_velocity_state_interface())
1741+
{
1742+
if (traj_controller_->has_velocity_command_interface())
1743+
{
1744+
// check acceleration
1745+
if (traj_controller_->has_acceleration_state_interface())
1746+
{
1747+
if (traj_controller_->has_acceleration_command_interface())
1748+
{
1749+
// should have set it to last position + velocity + acceleration command
1750+
EXPECT_EQ(current_state_when_offset.positions[i], initial_pos_cmd[i]);
1751+
EXPECT_EQ(current_state_when_offset.velocities[i], initial_vel_cmd[i]);
1752+
EXPECT_EQ(current_state_when_offset.accelerations[i], initial_acc_cmd[i]);
1753+
}
1754+
else
1755+
{
1756+
// should have set it to the state interface instead
1757+
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
1758+
EXPECT_EQ(current_state_when_offset.velocities[i], joint_state_vel_[i]);
1759+
EXPECT_EQ(current_state_when_offset.accelerations[i], joint_state_acc_[i]);
1760+
}
1761+
}
1762+
else
1763+
{
1764+
// should have set it to last position + velocity command
1765+
EXPECT_EQ(current_state_when_offset.positions[i], initial_pos_cmd[i]);
1766+
EXPECT_EQ(current_state_when_offset.velocities[i], initial_vel_cmd[i]);
1767+
}
1768+
}
1769+
else
1770+
{
1771+
// should have set it to the state interface instead
1772+
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
1773+
EXPECT_EQ(current_state_when_offset.velocities[i], joint_state_vel_[i]);
1774+
}
1775+
}
1776+
else
1777+
{
1778+
// should have set it to last position command
1779+
EXPECT_EQ(current_state_when_offset.positions[i], initial_pos_cmd[i]);
1780+
}
17481781
}
1749-
1750-
// check acceleration
1751-
if (
1752-
std::find(
1753-
state_interface_types_.begin(), state_interface_types_.end(),
1754-
hardware_interface::HW_IF_ACCELERATION) != state_interface_types_.end() &&
1755-
traj_controller_->has_acceleration_command_interface())
1782+
else
17561783
{
1757-
EXPECT_EQ(current_state_when_offset.positions[i], joint_pos_[i]);
1784+
// should have set it to the state interface instead
1785+
EXPECT_EQ(current_state_when_offset.positions[i], joint_state_pos_[i]);
17581786
}
17591787
}
17601788

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

+45-27
Original file line numberDiff line numberDiff line change
@@ -220,7 +220,11 @@ class TrajectoryControllerTest : public ::testing::Test
220220
void SetUpAndActivateTrajectoryController(
221221
rclcpp::Executor & executor, const std::vector<rclcpp::Parameter> & parameters = {},
222222
bool separate_cmd_and_state_values = false, double k_p = 0.0, double ff = 1.0,
223-
bool angle_wraparound = false)
223+
bool angle_wraparound = false,
224+
const std::vector<double> initial_pos_joints = INITIAL_POS_JOINTS,
225+
const std::vector<double> initial_vel_joints = INITIAL_VEL_JOINTS,
226+
const std::vector<double> initial_acc_joints = INITIAL_ACC_JOINTS,
227+
const std::vector<double> initial_eff_joints = INITIAL_EFF_JOINTS)
224228
{
225229
SetUpTrajectoryController(executor);
226230

@@ -239,12 +243,17 @@ class TrajectoryControllerTest : public ::testing::Test
239243

240244
traj_controller_->get_node()->configure();
241245

242-
ActivateTrajectoryController(separate_cmd_and_state_values);
246+
ActivateTrajectoryController(
247+
separate_cmd_and_state_values, initial_pos_joints, initial_vel_joints, initial_acc_joints,
248+
initial_eff_joints);
243249
}
244250

245251
void ActivateTrajectoryController(
246252
bool separate_cmd_and_state_values = false,
247-
const std::vector<double> initial_pos_joints = INITIAL_POS_JOINTS)
253+
const std::vector<double> initial_pos_joints = INITIAL_POS_JOINTS,
254+
const std::vector<double> initial_vel_joints = INITIAL_VEL_JOINTS,
255+
const std::vector<double> initial_acc_joints = INITIAL_ACC_JOINTS,
256+
const std::vector<double> initial_eff_joints = INITIAL_EFF_JOINTS)
248257
{
249258
std::vector<hardware_interface::LoanedCommandInterface> cmd_interfaces;
250259
std::vector<hardware_interface::LoanedStateInterface> state_interfaces;
@@ -280,14 +289,17 @@ class TrajectoryControllerTest : public ::testing::Test
280289
cmd_interfaces.emplace_back(pos_cmd_interfaces_.back());
281290
cmd_interfaces.back().set_value(initial_pos_joints[i]);
282291
cmd_interfaces.emplace_back(vel_cmd_interfaces_.back());
283-
cmd_interfaces.back().set_value(INITIAL_VEL_JOINTS[i]);
292+
cmd_interfaces.back().set_value(initial_vel_joints[i]);
284293
cmd_interfaces.emplace_back(acc_cmd_interfaces_.back());
285-
cmd_interfaces.back().set_value(INITIAL_ACC_JOINTS[i]);
294+
cmd_interfaces.back().set_value(initial_acc_joints[i]);
286295
cmd_interfaces.emplace_back(eff_cmd_interfaces_.back());
287-
cmd_interfaces.back().set_value(INITIAL_EFF_JOINTS[i]);
288-
joint_state_pos_[i] = initial_pos_joints[i];
289-
joint_state_vel_[i] = INITIAL_VEL_JOINTS[i];
290-
joint_state_acc_[i] = INITIAL_ACC_JOINTS[i];
296+
cmd_interfaces.back().set_value(initial_eff_joints[i]);
297+
if (separate_cmd_and_state_values)
298+
{
299+
joint_state_pos_[i] = INITIAL_POS_JOINTS[i];
300+
joint_state_vel_[i] = INITIAL_VEL_JOINTS[i];
301+
joint_state_acc_[i] = INITIAL_ACC_JOINTS[i];
302+
}
291303
state_interfaces.emplace_back(pos_state_interfaces_.back());
292304
state_interfaces.emplace_back(vel_state_interfaces_.back());
293305
state_interfaces.emplace_back(acc_state_interfaces_.back());
@@ -489,27 +501,33 @@ class TrajectoryControllerTest : public ::testing::Test
489501
// --> set kp > 0.0 in test
490502
if (traj_controller_->has_velocity_command_interface())
491503
{
492-
EXPECT_TRUE(is_same_sign_or_zero(point.at(0) - joint_state_pos_[0], joint_vel_[0]))
493-
<< "current error: " << point.at(0) - joint_state_pos_[0] << ", velocity command is "
494-
<< joint_vel_[0];
495-
EXPECT_TRUE(is_same_sign_or_zero(point.at(1) - joint_state_pos_[1], joint_vel_[1]))
496-
<< "current error: " << point.at(1) - joint_state_pos_[1] << ", velocity command is "
497-
<< joint_vel_[1];
498-
EXPECT_TRUE(is_same_sign_or_zero(point.at(2) - joint_state_pos_[2], joint_vel_[2]))
499-
<< "current error: " << point.at(2) - joint_state_pos_[2] << ", velocity command is "
500-
<< joint_vel_[2];
504+
EXPECT_TRUE(
505+
is_same_sign_or_zero(point.at(0) - pos_state_interfaces_[0].get_value(), joint_vel_[0]))
506+
<< "current error: " << point.at(0) - pos_state_interfaces_[0].get_value()
507+
<< ", velocity command is " << joint_vel_[0];
508+
EXPECT_TRUE(
509+
is_same_sign_or_zero(point.at(1) - pos_state_interfaces_[1].get_value(), joint_vel_[1]))
510+
<< "current error: " << point.at(1) - pos_state_interfaces_[1].get_value()
511+
<< ", velocity command is " << joint_vel_[1];
512+
EXPECT_TRUE(
513+
is_same_sign_or_zero(point.at(2) - pos_state_interfaces_[2].get_value(), joint_vel_[2]))
514+
<< "current error: " << point.at(2) - pos_state_interfaces_[2].get_value()
515+
<< ", velocity command is " << joint_vel_[2];
501516
}
502517
if (traj_controller_->has_effort_command_interface())
503518
{
504-
EXPECT_TRUE(is_same_sign_or_zero(point.at(0) - joint_state_pos_[0], joint_eff_[0]))
505-
<< "current error: " << point.at(0) - joint_state_pos_[0] << ", effort command is "
506-
<< joint_eff_[0];
507-
EXPECT_TRUE(is_same_sign_or_zero(point.at(1) - joint_state_pos_[1], joint_eff_[1]))
508-
<< "current error: " << point.at(1) - joint_state_pos_[1] << ", effort command is "
509-
<< joint_eff_[1];
510-
EXPECT_TRUE(is_same_sign_or_zero(point.at(2) - joint_state_pos_[2], joint_eff_[2]))
511-
<< "current error: " << point.at(2) - joint_state_pos_[2] << ", effort command is "
512-
<< joint_eff_[2];
519+
EXPECT_TRUE(
520+
is_same_sign_or_zero(point.at(0) - pos_state_interfaces_[0].get_value(), joint_eff_[0]))
521+
<< "current error: " << point.at(0) - pos_state_interfaces_[0].get_value()
522+
<< ", effort command is " << joint_eff_[0];
523+
EXPECT_TRUE(
524+
is_same_sign_or_zero(point.at(1) - pos_state_interfaces_[1].get_value(), joint_eff_[1]))
525+
<< "current error: " << point.at(1) - pos_state_interfaces_[1].get_value()
526+
<< ", effort command is " << joint_eff_[1];
527+
EXPECT_TRUE(
528+
is_same_sign_or_zero(point.at(2) - pos_state_interfaces_[2].get_value(), joint_eff_[2]))
529+
<< "current error: " << point.at(2) - pos_state_interfaces_[2].get_value()
530+
<< ", effort command is " << joint_eff_[2];
513531
}
514532
}
515533
}

0 commit comments

Comments
 (0)