@@ -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
17081708TEST_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
17551749TEST_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
0 commit comments