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

update include statements to use new pluginlib and class_loader headers #827

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
16 commits
Select commit Hold shift + click to select a range
37e388d
[moveit_ros_benchmarks] update include statements to use new pluginli…
mikaelarguedas Apr 7, 2018
14efd0f
[moveit_planners_chomp] update include statements to use new pluginli…
mikaelarguedas Apr 7, 2018
c6a5097
[sbpl_interface_ros] update include statements to use new pluginlib a…
mikaelarguedas Apr 7, 2018
73ed236
[moveit_planners_ompl] update include statements to use new pluginlib…
mikaelarguedas Apr 7, 2018
3dcf937
[moveit_controller_manager_example] update include statements to use …
mikaelarguedas Apr 7, 2018
a6d5c37
[moveit_ros_planning] update include statements to use new pluginlib …
mikaelarguedas Apr 7, 2018
7520260
[moveit_experimental] update include statements to use new pluginlib …
mikaelarguedas Apr 7, 2018
23163b3
[moveit_ros_visualization] update include statements to use new plugi…
mikaelarguedas Apr 7, 2018
4dd8fde
[moveit_ros_manipulation] update include statements to use new plugin…
mikaelarguedas Apr 7, 2018
3a6b651
[moveit_fake_controller_manager] update include statements to use new…
mikaelarguedas Apr 7, 2018
f389a52
[moveit_kinematics] update include statements to use new pluginlib an…
mikaelarguedas Apr 7, 2018
4361781
[moveit_ros_move_group] update include statements to use new pluginli…
mikaelarguedas Apr 7, 2018
7c4eabd
[moveit_ros_control_interface] update include statements to use new p…
mikaelarguedas Apr 7, 2018
27c180a
[moveit_simple_controller_manager] update include statements to use n…
mikaelarguedas Apr 7, 2018
a5d26fd
[moveit_setup_assistant] update include statements to use new pluginl…
mikaelarguedas Apr 7, 2018
f3955f4
[moveit_ros_perception] update include statements to use new pluginli…
mikaelarguedas Apr 7, 2018
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
@@ -1,5 +1,5 @@
#include <moveit/collision_distance_field/collision_detector_hybrid_plugin_loader.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>

namespace collision_detection
{
Expand Down
Expand Up @@ -40,7 +40,7 @@

#include <kinematics_cache/kinematics_cache.h>
#include <planning_models/robot_model.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>

namespace kinematics_cache_ros
{
Expand Down
Expand Up @@ -40,7 +40,7 @@
//#include <moveit/lma_kinematics_plugin/lma_kinematics_plugin.h>
#include <moveit/srv_kinematics_plugin/srv_kinematics_plugin.h>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
// register CachedIKKinematicsPlugin<KDLKinematicsPlugin> as a KinematicsBase implementation
PLUGINLIB_EXPORT_CLASS(
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin<kdl_kinematics_plugin::KDLKinematicsPlugin>,
Expand Down
Expand Up @@ -37,7 +37,7 @@
#include <moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h>
#include <ur_kinematics/ur_moveit_plugin.h>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
// register CachedIKKinematicsPlugin<URKinematicsPlugin> as a KinematicsBase implementation
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin<ur_kinematics::URKinematicsPlugin>,
kinematics::KinematicsBase);
Expand Up @@ -1373,5 +1373,5 @@ bool IKFastKinematicsPlugin::sampleRedundantJoint(kinematics::DiscretizationMeth
} // end namespace

// register IKFastKinematicsPlugin as a KinematicsBase implementation
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(ikfast_kinematics_plugin::IKFastKinematicsPlugin, kinematics::KinematicsBase);
Expand Up @@ -35,7 +35,7 @@
/* Author: Sachin Chitta, David Lu!!, Ugo Cupcic */

#include <moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>

//#include <tf/transform_datatypes.h>
#include <tf_conversions/tf_kdl.h>
Expand Down
Expand Up @@ -35,7 +35,7 @@
/* Author: Francisco Suarez-Ruiz */

#include <moveit/lma_kinematics_plugin/lma_kinematics_plugin.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>

#include <tf_conversions/tf_kdl.h>
#include <kdl_parser/kdl_parser.hpp>
Expand Down
Expand Up @@ -35,7 +35,7 @@
/* Author: Dave Coleman, Masaki Murooka */

#include <moveit/srv_kinematics_plugin/srv_kinematics_plugin.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>

// URDF, SRDF
#include <urdf_model/model.h>
Expand Down
2 changes: 1 addition & 1 deletion moveit_planners/chomp/chomp_interface/src/chomp_plugin.cpp
Expand Up @@ -40,7 +40,7 @@

#include <boost/shared_ptr.hpp>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>

namespace chomp_interface
{
Expand Down
Expand Up @@ -39,7 +39,7 @@
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/robot_state/conversions.h>
#include <moveit/profiler/profiler.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>

#include <dynamic_reconfigure/server.h>
#include "moveit_planners_ompl/OMPLDynamicReconfigureConfig.h"
Expand Down
Expand Up @@ -40,7 +40,7 @@
#include <moveit_msgs/GetMotionPlan.h>
#include <sbpl_interface/sbpl_meta_interface.h>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>

namespace sbpl_interface_ros
{
Expand Down
Expand Up @@ -40,7 +40,7 @@
#include <moveit_msgs/GetMotionPlan.h>
#include <sbpl_interface/sbpl_interface.h>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>

namespace sbpl_interface_ros
{
Expand Down
Expand Up @@ -37,7 +37,7 @@
#include <ros/ros.h>
#include <moveit/controller_manager/controller_manager.h>
#include <sensor_msgs/JointState.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <map>

namespace moveit_controller_manager_example
Expand Down
Expand Up @@ -39,7 +39,7 @@
#include <moveit/robot_state/robot_state.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <sensor_msgs/JointState.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <map>
#include <iterator>

Expand Down
Expand Up @@ -45,8 +45,8 @@
#include <controller_manager_msgs/ListControllers.h>
#include <controller_manager_msgs/SwitchController.h>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_list_macros.hpp>
#include <pluginlib/class_loader.hpp>

#include <boost/bimap.hpp>

Expand Down
Expand Up @@ -36,7 +36,7 @@

#include <ros/ros.h>
#include <moveit_ros_control_interface/ControllerHandle.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h>
#include <memory>

Expand Down
Expand Up @@ -39,7 +39,7 @@
#include <moveit_simple_controller_manager/action_based_controller_handle.h>
#include <moveit_simple_controller_manager/gripper_controller_handle.h>
#include <moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <algorithm>
#include <map>

Expand Down
Expand Up @@ -48,7 +48,7 @@
#include <moveit/warehouse/trajectory_constraints_storage.h>
#include <moveit/planning_interface/planning_interface.h>
#include <warehouse_ros/database_loader.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>

#include <map>
#include <vector>
Expand Down
Expand Up @@ -460,5 +460,5 @@ void move_group::MoveGroupPickPlaceAction::fillGrasps(moveit_msgs::PickupGoal& g
goal.possible_grasps.push_back(g);
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupPickPlaceAction, move_group::MoveGroupCapability)
Expand Up @@ -60,5 +60,5 @@ bool move_group::ApplyPlanningSceneService::applyScene(moveit_msgs::ApplyPlannin
return true;
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::ApplyPlanningSceneService, move_group::MoveGroupCapability)
Expand Up @@ -181,5 +181,5 @@ bool move_group::MoveGroupCartesianPathService::computeService(moveit_msgs::GetC
return true;
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupCartesianPathService, move_group::MoveGroupCapability)
Expand Up @@ -60,5 +60,5 @@ bool move_group::ClearOctomapService::clearOctomap(std_srvs::Empty::Request& req
return true;
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::ClearOctomapService, move_group::MoveGroupCapability)
Expand Up @@ -137,5 +137,5 @@ void MoveGroupExecuteTrajectoryAction::setExecuteTrajectoryState(MoveGroupState

} // namespace move_group

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupExecuteTrajectoryAction, move_group::MoveGroupCapability)
Expand Up @@ -108,5 +108,5 @@ bool move_group::MoveGroupExecuteService::executeTrajectoryService(moveit_msgs::
return true;
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupExecuteService, move_group::MoveGroupCapability)
Expand Up @@ -58,5 +58,5 @@ bool move_group::MoveGroupGetPlanningSceneService::getPlanningSceneService(movei
return true;
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupGetPlanningSceneService, move_group::MoveGroupCapability)
Expand Up @@ -211,5 +211,5 @@ bool move_group::MoveGroupKinematicsService::computeFKService(moveit_msgs::GetPo
return true;
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupKinematicsService, move_group::MoveGroupCapability)
Expand Up @@ -244,5 +244,5 @@ void move_group::MoveGroupMoveAction::setMoveState(MoveGroupState state)
move_action_server_->publishFeedback(move_feedback_);
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupMoveAction, move_group::MoveGroupCapability)
Expand Up @@ -73,5 +73,5 @@ bool move_group::MoveGroupPlanService::computePlanService(moveit_msgs::GetMotion
return true;
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupPlanService, move_group::MoveGroupCapability)
Expand Up @@ -125,5 +125,5 @@ bool move_group::MoveGroupQueryPlannersService::setParams(moveit_msgs::SetPlanne
return true;
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupQueryPlannersService, move_group::MoveGroupCapability)
Expand Up @@ -122,5 +122,5 @@ bool move_group::MoveGroupStateValidationService::computeService(moveit_msgs::Ge
return true;
}

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupStateValidationService, move_group::MoveGroupCapability)
2 changes: 1 addition & 1 deletion moveit_ros/move_group/src/list_capabilities.cpp
Expand Up @@ -35,7 +35,7 @@
/* Author: Ioan Sucan */

#include <moveit/move_group/move_group_capability.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>
#include <boost/algorithm/string/join.hpp>

int main(int argc, char** argv)
Expand Down
Expand Up @@ -34,7 +34,7 @@

/* Author: Ioan Sucan */

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
#include <moveit/depth_image_octomap_updater/depth_image_octomap_updater.h>

CLASS_LOADER_REGISTER_CLASS(occupancy_map_monitor::DepthImageOctomapUpdater,
Expand Down
Expand Up @@ -213,5 +213,5 @@ void mesh_filter::DepthSelfFiltering::depthCb(const sensor_msgs::ImageConstPtr&
filter(depth_msg, info_msg);
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(mesh_filter::DepthSelfFiltering, nodelet::Nodelet)
Expand Up @@ -41,7 +41,7 @@
#include <string>
#include <ros/ros.h>
#include <tf/tf.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>

#include <moveit_msgs/SaveMap.h>
#include <moveit_msgs/LoadMap.h>
Expand Down
Expand Up @@ -34,7 +34,7 @@

/* Author: Ioan Sucan */

#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
#include <moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h>

CLASS_LOADER_REGISTER_CLASS(occupancy_map_monitor::PointCloudOctomapUpdater, occupancy_map_monitor::OccupancyMapUpdater)
Expand Up @@ -33,7 +33,7 @@
*********************************************************************/

#include <moveit/collision_plugin_loader/collision_plugin_loader.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>
#include <memory>

namespace collision_detection
Expand Down
Expand Up @@ -35,7 +35,7 @@
/* Author: Ioan Sucan */

#include <moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>
#include <ros/ros.h>
#include <boost/tokenizer.hpp>
#include <memory>
Expand Down
Expand Up @@ -36,7 +36,7 @@

#include <moveit/kinematics_plugin_loader/kinematics_plugin_loader.h>
#include <moveit/rdf_loader/rdf_loader.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>
#include <boost/thread/mutex.hpp>
#include <sstream>
#include <vector>
Expand Down
Expand Up @@ -43,7 +43,7 @@
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/planning_scene_monitor/trajectory_monitor.h>
#include <moveit/sensor_manager/sensor_manager.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>

/** \brief This namespace includes functionality specific to the execution and monitoring of motion plans */
namespace plan_execution
Expand Down
Expand Up @@ -43,7 +43,7 @@

#include <moveit/planning_scene_monitor/trajectory_monitor.h>
#include <moveit/sensor_manager/sensor_manager.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>

#include <memory>

Expand Down
Expand Up @@ -39,7 +39,7 @@

#include <moveit/planning_interface/planning_interface.h>
#include <moveit/planning_request_adapter/planning_request_adapter.h>
#include <pluginlib/class_loader.h>
#include <pluginlib/class_loader.hpp>
#include <ros/ros.h>

#include <memory>
Expand Down
Expand Up @@ -37,7 +37,7 @@

#include <moveit/planning_request_adapter/planning_request_adapter.h>
#include <moveit/trajectory_processing/iterative_spline_parameterization.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
#include <ros/console.h>

namespace default_planner_request_adapters
Expand Down
Expand Up @@ -36,7 +36,7 @@

#include <moveit/planning_request_adapter/planning_request_adapter.h>
#include <moveit/trajectory_processing/iterative_time_parameterization.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
#include <ros/console.h>

namespace default_planner_request_adapters
Expand Down
Expand Up @@ -35,7 +35,7 @@
/* Author: Ioan Sucan */

#include <moveit/planning_request_adapter/planning_request_adapter.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>

namespace default_planner_request_adapters
{
Expand Down
Expand Up @@ -38,7 +38,7 @@
#include <boost/math/constants/constants.hpp>
#include <moveit/trajectory_processing/trajectory_tools.h>
#include <moveit/robot_state/conversions.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
#include <ros/ros.h>

namespace default_planner_request_adapters
Expand Down
Expand Up @@ -37,7 +37,7 @@
#include <moveit/planning_request_adapter/planning_request_adapter.h>
#include <moveit/robot_state/conversions.h>
#include <moveit/trajectory_processing/trajectory_tools.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
#include <ros/ros.h>

namespace default_planner_request_adapters
Expand Down
Expand Up @@ -37,7 +37,7 @@

#include <moveit/planning_request_adapter/planning_request_adapter.h>
#include <moveit/robot_state/conversions.h>
#include <class_loader/class_loader.h>
#include <class_loader/class_loader.hpp>
#include <moveit/trajectory_processing/trajectory_tools.h>
#include <ros/ros.h>

Expand Down