@@ -1668,21 +1668,23 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
1668
1668
#endif
1669
1669
1670
1670
// 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
1672
1672
TEST_P (TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_controller_start)
1673
1673
{
1674
1674
rclcpp::executors::SingleThreadedExecutor executor;
1675
- // default if false so it will not be actually set parameter
1676
1675
rclcpp::Parameter is_open_loop_parameters (" open_loop_control" , true );
1677
1676
1678
1677
// 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)
1686
1688
1687
1689
auto current_state_when_offset = traj_controller_->get_current_state_when_offset ();
1688
1690
@@ -1691,70 +1693,96 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_co
1691
1693
EXPECT_EQ (current_state_when_offset.positions [i], joint_state_pos_[i]);
1692
1694
1693
1695
// 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 ())
1699
1697
{
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]);
1701
1699
}
1702
1700
1703
1701
// 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 ())
1709
1703
{
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]);
1711
1705
}
1712
1706
}
1713
1707
1714
1708
executor.cancel ();
1715
1709
}
1716
1710
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
1718
1712
// are set on the hardware commands
1719
1713
TEST_P (TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_controller_start)
1720
1714
{
1721
1715
rclcpp::executors::SingleThreadedExecutor executor;
1722
- // default if false so it will not be actually set parameter
1723
1716
rclcpp::Parameter is_open_loop_parameters (" open_loop_control" , true );
1724
1717
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;
1726
1720
for (size_t i = 0 ; i < 3 ; ++i)
1727
1721
{
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 ) ;
1731
1725
}
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
1733
1731
1734
1732
auto current_state_when_offset = traj_controller_->get_current_state_when_offset ();
1735
1733
1736
1734
for (size_t i = 0 ; i < 3 ; ++i)
1737
1735
{
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 ())
1746
1738
{
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
+ }
1748
1781
}
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
1756
1783
{
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]);
1758
1786
}
1759
1787
}
1760
1788
0 commit comments