Skip to content

Commit

Permalink
Don't hard code plugin path to lib/ (moveit#3305)
Browse files Browse the repository at this point in the history
pluginlib will search the default paths anyhow
  • Loading branch information
jspricke authored Jan 10, 2023
1 parent 48ac87f commit a266089
Show file tree
Hide file tree
Showing 16 changed files with 21 additions and 21 deletions.
2 changes: 1 addition & 1 deletion moveit_core/collision_detector_bullet_description.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libcollision_detector_bullet_plugin">
<library path="libcollision_detector_bullet_plugin">
<class name="Bullet" type="collision_detection::CollisionDetectorBtPluginLoader"
base_class_type="collision_detection::CollisionPlugin">
<description>
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/collision_detector_fcl_description.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libcollision_detector_fcl_plugin">
<library path="libcollision_detector_fcl_plugin">
<class name="FCL" type="collision_detection::CollisionDetectorFCLPluginLoader"
base_class_type="collision_detection::CollisionPlugin">
<description>
Expand Down
8 changes: 4 additions & 4 deletions moveit_kinematics/cached_ik_kinematics_plugin_description.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libmoveit_cached_ik_kinematics_plugin">
<library path="libmoveit_cached_ik_kinematics_plugin">
<class name="cached_ik_kinematics_plugin/CachedKDLKinematicsPlugin" type="cached_ik_kinematics_plugin::CachedIKKinematicsPlugin<kdl_kinematics_plugin::KDLKinematicsPlugin>" base_class_type="kinematics::KinematicsBase">
<description>
A kinematics plugin for persistently caching IK solutions computed with the KDL kinematics plugin.
Expand All @@ -15,21 +15,21 @@
</description>
</class>-->
</library>
<!--<library path="lib/libmoveit_cached_ur3_kinematics_plugin">
<!--<library path="libmoveit_cached_ur3_kinematics_plugin">
<class name="cached_ik_kinematics_plugin/CachedUR3KinematicsPlugin" type="cached_ik_kinematics_plugin::CachedIKKinematicsPlugin<ur_kinematics::URKinematicsPlugin>" base_class_type="kinematics::KinematicsBase">
<description>
A kinematics plugin for persistently caching IK solutions computed with the UR3 kinematics plugin.
</description>
</class>
</library>
<library path="lib/libmoveit_cached_ur5_kinematics_plugin">
<library path="libmoveit_cached_ur5_kinematics_plugin">
<class name="cached_ik_kinematics_plugin/CachedUR5KinematicsPlugin" type="cached_ik_kinematics_plugin::CachedIKKinematicsPlugin<ur_kinematics::URKinematicsPlugin>" base_class_type="kinematics::KinematicsBase">
<description>
A kinematics plugin for persistently caching IK solutions computed with the UR5 kinematics plugin.
</description>
</class>
</library>
<library path="lib/libmoveit_cached_ur10_kinematics_plugin">
<library path="libmoveit_cached_ur10_kinematics_plugin">
<class name="cached_ik_kinematics_plugin/CachedUR10KinematicsPlugin" type="cached_ik_kinematics_plugin::CachedIKKinematicsPlugin<ur_kinematics::URKinematicsPlugin>" base_class_type="kinematics::KinematicsBase">
<description>
A kinematics plugin for persistently caching IK solutions computed with the UR10 kinematics plugin.
Expand Down
2 changes: 1 addition & 1 deletion moveit_kinematics/kdl_kinematics_plugin_description.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libmoveit_kdl_kinematics_plugin">
<library path="libmoveit_kdl_kinematics_plugin">
<class name="kdl_kinematics_plugin/KDLKinematicsPlugin" type="kdl_kinematics_plugin::KDLKinematicsPlugin" base_class_type="kinematics::KinematicsBase">
<description>
A implementation of kinematics as a plugin based on KDL.
Expand Down
2 changes: 1 addition & 1 deletion moveit_kinematics/lma_kinematics_plugin_description.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libmoveit_lma_kinematics_plugin">
<library path="libmoveit_lma_kinematics_plugin">
<class name="lma_kinematics_plugin/LMAKinematicsPlugin" type="lma_kinematics_plugin::LMAKinematicsPlugin" base_class_type="kinematics::KinematicsBase">
<description>
A implementation of kinematics as a plugin based on KDL ChainIkSolverPos_LMA.
Expand Down
2 changes: 1 addition & 1 deletion moveit_kinematics/srv_kinematics_plugin_description.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libmoveit_srv_kinematics_plugin">
<library path="libmoveit_srv_kinematics_plugin">
<class name="srv_kinematics_plugin/SrvKinematicsPlugin" type="srv_kinematics_plugin::SrvKinematicsPlugin" base_class_type="kinematics::KinematicsBase">
<description>
A implementation of kinematics as a plugin that uses a ROS service layer to communicate with an external IK solver
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libchomp_planner_plugin">
<library path="libchomp_planner_plugin">
<class name="chomp_interface/CHOMPPlanner" type="chomp_interface::CHOMPPlannerManager" base_class_type="planning_interface::PlannerManager">
<description>
The CHOMP motion planner plugin.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libchomp_planner_plugin">
<library path="libchomp_planner_plugin">
<class name="chomp_interface_ros/CHOMPPlanner" type="chomp_interface_ros::CHOMPPlanner" base_class_type="planning_interface::Planner">
<description>
</description>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libpilz_industrial_motion_planner">
<library path="libpilz_industrial_motion_planner">
<class type="pilz_industrial_motion_planner::CommandPlanner" base_class_type="planning_interface::PlannerManager">
<description>Pilz Industrial Motion Planner</description>
</class>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
<library path="lib/libplanning_context_loader_ptp">
<library path="libplanning_context_loader_ptp">
<class type="pilz_industrial_motion_planner::PlanningContextLoaderPTP"
base_class_type="pilz_industrial_motion_planner::PlanningContextLoader">
<description>Loader for PTP Context</description>
</class>
</library>
<library path="lib/libplanning_context_loader_lin">
<library path="libplanning_context_loader_lin">
<class type="pilz_industrial_motion_planner::PlanningContextLoaderLIN"
base_class_type="pilz_industrial_motion_planner::PlanningContextLoader">
<description>Loader for LIN Context</description>
</class>
</library>
<library path="lib/libplanning_context_loader_circ">
<library path="libplanning_context_loader_circ">
<class type="pilz_industrial_motion_planner::PlanningContextLoaderCIRC"
base_class_type="pilz_industrial_motion_planner::PlanningContextLoader">
<description>Loader for CIRC Context</description>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libsequence_capability">
<library path="libsequence_capability">
<class name="pilz_industrial_motion_planner/MoveGroupSequenceAction"
type="pilz_industrial_motion_planner::MoveGroupSequenceAction"
base_class_type="move_group::MoveGroupCapability">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libsbpl_planner_plugin">
<library path="libsbpl_planner_plugin">
<class name="sbpl_interface_ros/SBPLPlanner" type="sbpl_interface_ros::SBPLPlanner" base_class_type="planning_interface::Planner">
<description>
</description>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<class_libraries>
<library path="lib/libmoveit_ros_control_interface_plugin">
<library path="libmoveit_ros_control_interface_plugin">
<class type="moveit_ros_control_interface::MoveItControllerManager" base_class_type="moveit_controller_manager::MoveItControllerManager">
<description>ros_control controller manager interface for MoveIt</description>
</class>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<class_libraries>
<library path="lib/libmoveit_ros_control_interface_trajectory_plugin">
<library path="libmoveit_ros_control_interface_trajectory_plugin">
<class name="position_controllers/JointTrajectoryController" type="moveit_ros_control_interface::JointTrajectoryControllerAllocator" base_class_type="moveit_ros_control_interface::ControllerHandleAllocator">
<description></description>
</class>
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/perception/moveit_depth_self_filter.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libmoveit_depth_self_filter">
<library path="libmoveit_depth_self_filter">
<class name="mesh_filter/DepthSelfFiltering" type="mesh_filter::DepthSelfFiltering" base_class_type="nodelet::Nodelet">
<description>
Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where a transformation can be provided for.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<library path="lib/libtest_controller_manager_plugin">
<library path="libtest_controller_manager_plugin">
<class name="test_moveit_controller_manager/TestMoveItControllerManager" type="test_moveit_controller_manager::TestMoveItControllerManager" base_class_type="moveit_controller_manager::MoveItControllerManager">
<description>
</description>
Expand Down

0 comments on commit a266089

Please sign in to comment.