diff --git a/CMakeLists.txt b/CMakeLists.txt index 540c7b4..d13ba49 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,12 +14,12 @@ add_definitions(-W -Wall -Wextra find_package(catkin REQUIRED COMPONENTS descartes_core descartes_moveit - descartes_trajectory descartes_planner + descartes_trajectory moveit_core + moveit_ros_move_group moveit_ros_planning moveit_visual_tools - moveit_ros_move_group roscpp roslint rospy @@ -34,12 +34,12 @@ find_package(Eigen3 REQUIRED) ################################### catkin_package( CATKIN_DEPENDS - roscpp - rospy moveit_core - moveit_ros_planning moveit_ros_move_group + moveit_ros_planning moveit_visual_tools + roscpp + rospy INCLUDE_DIRS include LIBRARIES @@ -123,7 +123,7 @@ install(PROGRAMS ) install(FILES - descartes_capability_plugin_description.xml + ${PROJECT_NAME}_plugin_description.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) ############# @@ -133,8 +133,6 @@ install(FILES if(CATKIN_ENABLE_TESTING) find_package(rostest REQUIRED) find_package(pluginlib REQUIRED) - find_package(moveit_resources REQUIRED) - include_directories(${moveit_resources_INCLUDE_DIRS}) add_rostest_gtest(descartes_path_service_capability_test test/descartes_path_service_capability_test.test test/descartes_path_service_capability_test.cpp) target_link_libraries(descartes_path_service_capability_test diff --git a/include/descartes_capability/descartes_path_service_capability.h b/include/descartes_capability/descartes_path_service_capability.h index ac4fee0..71a980f 100644 --- a/include/descartes_capability/descartes_path_service_capability.h +++ b/include/descartes_capability/descartes_path_service_capability.h @@ -80,8 +80,8 @@ class MoveGroupDescartesPathService : public move_group::MoveGroupCapability double computeMaxJointDelta(const std::vector& joints1, const std::vector& joints2); /** \brief Interpolates between start and end poses and appends them to deense_waypoints **/ - void createDensePath(const Eigen::Isometry3d& start, const Eigen::Isometry3d& end, double max_step, - EigenSTL::vector_Isometry3d& dense_waypoints); + static void createDensePath(const Eigen::Isometry3d& start, const Eigen::Isometry3d& end, double max_step, + EigenSTL::vector_Isometry3d& dense_waypoints); /** \brief Transforms each point in a vector of affine**/ void createDescartesTrajectory(const EigenSTL::vector_Isometry3d& dense_waypoints, @@ -128,6 +128,6 @@ class MoveGroupDescartesPathService : public move_group::MoveGroupCapability // For Rviz visualizations moveit_visual_tools::MoveItVisualToolsPtr visual_tools_; }; -} +} // namespace descartes_capability #endif // MOVEIT_MOVE_GROUP_DESCARTES_PATH_SERVICE_CAPABILITY_ diff --git a/src/descartes_path_service_capability.cpp b/src/descartes_path_service_capability.cpp index f98f492..796a341 100644 --- a/src/descartes_path_service_capability.cpp +++ b/src/descartes_path_service_capability.cpp @@ -54,10 +54,15 @@ namespace descartes_capability MoveGroupDescartesPathService::MoveGroupDescartesPathService() : MoveGroupCapability("DescartesPathService") , nh_("~") + , positional_tolerance_(0.0) + , positional_tolerance_increment_(0.0) + , roll_orientation_tolerance_(0.0) + , pitch_orientation_tolerance_(0.0) + , yaw_orientation_tolerance_(0.0) + , orientation_tolerance_increment_(0.0) + , verbose_debug_(false) + , visual_debug_(false) , display_computed_paths_(true) - , current_group_name_("") - , current_world_frame_("") - , current_tcp_frame_("") { } @@ -122,9 +127,8 @@ void MoveGroupDescartesPathService::createDescartesTrajectory( const EigenSTL::vector_Isometry3d& dense_waypoints, std::vector& input_descartes_trajectory) { - for (std::size_t i = 0; i < dense_waypoints.size(); ++i) + for (auto eigen_pose : dense_waypoints) { - const Eigen::Isometry3d eigen_pose = dense_waypoints[i]; const Eigen::Quaterniond rotation(eigen_pose.rotation()); if (verbose_debug_) @@ -258,10 +262,9 @@ bool MoveGroupDescartesPathService::initializeDescartesModel(const std::string& { // Setup Descartes model descartes_model_.reset(new descartes_moveit::MoveitStateAdapter); - descartes_moveit::MoveitStateAdapter* moveit_state_adapter = - dynamic_cast(descartes_model_.get()); - bool model_init = - moveit_state_adapter->initialize(context_->planning_scene_monitor_, group_name, world_frame, tcp_frame); + auto* moveit_state_adapter = dynamic_cast(descartes_model_.get()); + bool model_init = moveit_state_adapter->initialize(context_->planning_scene_monitor_->getRobotModel(), group_name, + world_frame, tcp_frame); if (!model_init) { @@ -332,7 +335,7 @@ bool MoveGroupDescartesPathService::computeService(moveit_msgs::GetCartesianPath Eigen::Isometry3d current_pose; descartes_model_->getFK(current_joints, current_pose); - if (req.waypoints.size() < 1) + if (req.waypoints.empty()) { ROS_ERROR_NAMED(name_, "Must provide at least 1 input trajectory point %zu provided", req.waypoints.size()); res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE; @@ -428,7 +431,7 @@ bool MoveGroupDescartesPathService::computeService(moveit_msgs::GetCartesianPath if (!descartes_planner.planPath(descartes_trajectory)) { valid_path = false; - ROS_ERROR_STREAM_NAMED(name_, "Could not solve for a valid path."); + ROS_INFO_STREAM_NAMED(name_, "Could not solve for a valid path."); } else { @@ -439,7 +442,7 @@ bool MoveGroupDescartesPathService::computeService(moveit_msgs::GetCartesianPath if (!descartes_planner.getPath(descartes_result)) { valid_path = false; - ROS_ERROR_STREAM_NAMED(name_, "Could not retrieve path."); + ROS_INFO_STREAM_NAMED(name_, "Could not retrieve path."); } if (valid_path && verbose_debug_) @@ -447,7 +450,7 @@ bool MoveGroupDescartesPathService::computeService(moveit_msgs::GetCartesianPath if (!valid_path) { - ROS_ERROR_STREAM_NAMED(name_, "Unable to generate a plan using Descartes."); + ROS_INFO_STREAM_NAMED(name_, "Unable to generate a plan using Descartes."); res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE; res.fraction = 0.0; return true; @@ -499,9 +502,9 @@ void MoveGroupDescartesPathService::printJoints(const std::vector& joint { std::stringstream o; - for (std::size_t i = 0; i < joints.size(); ++i) + for (double joint : joints) { - o << "\t" << std::fixed << std::setw(6) << std::setprecision(3) << joints[i]; + o << "\t" << std::fixed << std::setw(6) << std::setprecision(3) << joint; } ROS_DEBUG_STREAM_NAMED(name_, o.str()); } @@ -510,9 +513,9 @@ void MoveGroupDescartesPathService::printJointsNamed(const std::string& name, co { std::stringstream o; o << name; - for (std::size_t i = 0; i < joints1.size(); ++i) + for (double i : joints1) { - o << "\t" << std::fixed << std::setw(6) << std::setprecision(3) << joints1[i]; + o << "\t" << std::fixed << std::setw(6) << std::setprecision(3) << i; } ROS_DEBUG_STREAM_NAMED(name_, o.str()); }