Skip to content

Commit

Permalink
Formatting pass
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Jul 24, 2024
1 parent 58eff93 commit 0b75099
Show file tree
Hide file tree
Showing 5 changed files with 39 additions and 45 deletions.
2 changes: 1 addition & 1 deletion moveit_ros/trajectory_cache/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,4 @@ Changelog for package nexus_motion_planner

0.1.0 (2024-05-17)
------------------
* Add ``moveit_ros_trajectory_cache`` package for trajectory caching.
* Add ``moveit_ros_trajectory_cache`` package for trajectory caching.
52 changes: 25 additions & 27 deletions moveit_ros/trajectory_cache/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,45 +19,43 @@ find_package(warehouse_ros_sqlite REQUIRED)

include_directories(include)

set (trajectory_cache_dependencies
geometry_msgs
moveit_ros_planning_interface
moveit_ros_warehouse
rclcpp
tf2
tf2_ros
trajectory_msgs
warehouse_ros
warehouse_ros_sqlite
)

#===============================================================================
set(TRAJECTORY_CACHE_LIBRARY_NAME trajectory_cache)
set(trajectory_cache_dependencies
geometry_msgs
moveit_ros_planning_interface
moveit_ros_warehouse
rclcpp
tf2
tf2_ros
trajectory_msgs
warehouse_ros
warehouse_ros_sqlite)

# ==============================================================================

# Motion plan cache library
add_library(${TRAJECTORY_CACHE_LIBRARY_NAME} src/trajectory_cache.cpp)
ament_target_dependencies(${TRAJECTORY_CACHE_LIBRARY_NAME} ${trajectory_cache_dependencies})
target_include_directories(${TRAJECTORY_CACHE_LIBRARY_NAME} PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)
add_library(trajectory_cache src/trajectory_cache.cpp)
ament_target_dependencies(trajectory_cache ${trajectory_cache_dependencies})
target_include_directories(
trajectory_cache
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}>)

#===============================================================================
# ==============================================================================

if(BUILD_TESTING)
find_package(ament_cmake_pytest REQUIRED)
find_package(launch_testing_ament_cmake REQUIRED)
find_package(rmf_utils REQUIRED)

# This test executable is run by the pytest_test, since a node is required for testing move groups
# This test executable is run by the pytest_test, since a node is required for
# testing move groups
add_executable(test_trajectory_cache test/test_trajectory_cache.cpp)
target_link_libraries(test_trajectory_cache ${TRAJECTORY_CACHE_LIBRARY_NAME})
target_link_libraries(test_trajectory_cache trajectory_cache)

install(TARGETS
test_trajectory_cache
RUNTIME DESTINATION lib/${PROJECT_NAME}
)
install(TARGETS test_trajectory_cache RUNTIME DESTINATION lib/${PROJECT_NAME})

ament_add_pytest_test(test_trajectory_cache_py "test/test_trajectory_cache.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
)
ament_add_pytest_test(
test_trajectory_cache_py "test/test_trajectory_cache.py" WORKING_DIRECTORY
"${CMAKE_CURRENT_BINARY_DIR}")

endif()

Expand Down
4 changes: 2 additions & 2 deletions moveit_ros/trajectory_cache/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -124,8 +124,8 @@ Since this is an initial release, the following features are unsupported because
- If your planning scene is expected to change between cache lookups, do NOT use this cache, fetched trajectories are likely to result in collision then.
- To handle collisions this class will need to hash the planning scene world msg (after zeroing out std_msgs/Header timestamps and sequences) and do an appropriate lookup, or do more complicated checks to see if the scene world is "close enough" or is a less obstructed version of the scene in the cache entry.
- !!! This cache does NOT support keying on joint velocities and efforts.
- The cache only keys on joint positions.
- The cache only keys on joint positions.
- !!! This cache does NOT support multi-DOF joints.
- !!! This cache does NOT support certain constraints
- Including: path, constraint regions, everything related to collision.
- The fuzzy lookup can't be configured on a per-joint basis.
- The fuzzy lookup can't be configured on a per-joint basis.
Original file line number Diff line number Diff line change
Expand Up @@ -257,4 +257,4 @@ class TrajectoryCache
};

} // namespace trajectory_cache
} // namespace moveit_ros
} // namespace moveit_ros
24 changes: 10 additions & 14 deletions moveit_ros/trajectory_cache/test/test_trajectory_cache.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,7 @@ def robot_fixture(moveit_config):
package="tf2_ros",
executable="static_transform_publisher",
output="log",
arguments=["0.0", "0.0", "0.0", "0.0",
"0.0", "0.0", "world", "panda_link0"],
arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "world", "panda_link0"],
)

robot_state_publisher = Node(
Expand Down Expand Up @@ -87,8 +86,7 @@ def robot_fixture(moveit_config):
]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner {}".format(
controller)],
cmd=["ros2 run controller_manager spawner {}".format(controller)],
shell=True,
output="log",
)
Expand All @@ -99,7 +97,7 @@ def robot_fixture(moveit_config):
static_tf,
robot_state_publisher,
ros2_control_node,
*load_controllers
*load_controllers,
]


Expand All @@ -111,24 +109,22 @@ def trajectory_cache_test_runner_node(moveit_config):
name="test_trajectory_cache_node",
output="screen",
cached_output=True,
parameters=[moveit_config.to_dict()]
parameters=[moveit_config.to_dict()],
)


@launch_pytest.fixture
def launch_description(trajectory_cache_test_runner_node, robot_fixture):
return LaunchDescription(
robot_fixture +
[
trajectory_cache_test_runner_node,
launch_pytest.actions.ReadyToTest()
]
robot_fixture
+ [trajectory_cache_test_runner_node, launch_pytest.actions.ReadyToTest()]
)


def validate_stream(expected):
def wrapped(output):
assert expected in output.splitlines(
assert (
expected in output.splitlines()
), f"Did not get expected: {expected} in output:\n\n{output}"
return wrapped

Expand All @@ -140,15 +136,15 @@ def test_all_tests_pass(trajectory_cache_test_runner_node, launch_context):
launch_context,
trajectory_cache_test_runner_node,
lambda x: x.count("[PASS]") == 165, # All test cases passed.
timeout=30
timeout=30,
)

# Check no occurrences of [FAIL] in output
assert not process_tools.wait_for_output_sync(
launch_context,
trajectory_cache_test_runner_node,
lambda x: "[FAIL]" in x,
timeout=10
timeout=10,
)

yield

0 comments on commit 0b75099

Please sign in to comment.