Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add velocity feedforward term to velocity HardwareInterfaceAdapter #227

Merged
3 changes: 2 additions & 1 deletion joint_trajectory_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ add_library(${PROJECT_NAME} src/joint_trajectory_controller.cpp
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})

if(CATKIN_ENABLE_TESTING)
find_package(catkin
find_package(catkin
REQUIRED COMPONENTS
actionlib
controller_manager
Expand Down Expand Up @@ -100,6 +100,7 @@ if(CATKIN_ENABLE_TESTING)
test/joint_trajectory_controller_vel.test
test/joint_trajectory_controller_test.cpp)
target_link_libraries(joint_trajectory_controller_vel_test ${catkin_LIBRARIES})
target_compile_definitions(joint_trajectory_controller_vel_test PRIVATE TEST_VELOCITY_FF=1)

add_rostest_gtest(joint_trajectory_controller_wrapping_test
test/joint_trajectory_controller_wrapping.test
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,5 @@
<test test-name="joint_trajectory_controller_test"
pkg="joint_trajectory_controller"
type="joint_trajectory_controller_test"
time-limit="85.0"
args="--gtest_filter=-JointTrajectoryControllerTest.jointVelocityFeedForward"/>
time-limit="85.0"/>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -981,6 +981,9 @@ TEST_F(JointTrajectoryControllerTest, ignorePartiallyOldActionTraj)
}

// Velocity FF parameter ///////////////////////////////////////////////////////////////////////////////////////////////
// This test will only be built and run for the VelocityJointInterface-based version of the JointTrajectoryController

#ifdef TEST_VELOCITY_FF
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please consider #if TEST_VELOCITY_FF to handle TEST_VELOCITY_FF=0 as well.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just noticed this comment. Updated.


TEST_F(JointTrajectoryControllerTest, jointVelocityFeedForward)
{
Expand Down Expand Up @@ -1027,6 +1030,7 @@ TEST_F(JointTrajectoryControllerTest, jointVelocityFeedForward)
ASSERT_TRUE(action_client->waitForServer(long_timeout));
}

#endif // TEST_VELOCITY_FF

// Tolerance checking //////////////////////////////////////////////////////////////////////////////////////////////////

Expand Down