Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #include <ros/ros.h>
00038 #include <collision_proximity/collision_proximity_space.h>
00039 #include <planning_environment/models/model_utils.h>
00040 #include <arm_navigation_msgs/GetMotionPlan.h>
00041 #include <arm_navigation_msgs/GetStateValidity.h>
00042
00043 struct CollisionProximitySpacePlannerInterface
00044 {
00045 CollisionProximitySpacePlannerInterface(const std::string& robot_description_name)
00046 {
00047 cps_ = new collision_proximity::CollisionProximitySpace(robot_description_name);
00048
00049 ros::NodeHandle priv("~");
00050
00051 motion_planning_service_ = priv.advertiseService("get_distance_aware_plan", &CollisionProximitySpacePlannerInterface::motionPlanCallback, this);
00052
00053 get_state_validity_service_ = priv.advertiseService("get_state_validity", &CollisionProximitySpacePlannerInterface::getStateValidity, this);
00054
00055 vis_marker_publisher_ = root_handle_.advertise<visualization_msgs::Marker>("collision_proximity_markers", 128);
00056 vis_marker_array_publisher_ = root_handle_.advertise<visualization_msgs::MarkerArray>("collision_proximity_markers_array", 128);
00057
00058 }
00059
00060 ~CollisionProximitySpacePlannerInterface()
00061 {
00062 delete cps_;
00063 }
00064
00065 bool motionPlanCallback(arm_navigation_msgs::GetMotionPlan::Request &req,
00066 arm_navigation_msgs::GetMotionPlan::Response &res)
00067 {
00068 if(!req.motion_plan_request.group_name.empty()) {
00069 ROS_INFO_STREAM("Setting up for group " << req.motion_plan_request.group_name);
00070 cps_->setupForGroupQueries(req.motion_plan_request.group_name,
00071 req.motion_plan_request.start_state,
00072 current_link_names_,
00073 current_attached_body_names_);
00074 } else {
00075 return false;
00076 }
00077 return true;
00078 }
00079
00080 bool getStateValidity(arm_navigation_msgs::GetStateValidity::Request &req,
00081 arm_navigation_msgs::GetStateValidity::Response &res)
00082 {
00083 cps_->getCollisionModelsInterface()->bodiesLock();
00084 if(!cps_->getCollisionModelsInterface()->isPlanningSceneSet()) {
00085 cps_->getCollisionModelsInterface()->bodiesUnlock();
00086 return true;
00087 }
00088 planning_environment::setRobotStateAndComputeTransforms(req.robot_state,
00089 *cps_->getCollisionModelsInterface()->getPlanningSceneState());
00090 cps_->getCollisionModelsInterface()->bodiesUnlock();
00091 return true;
00092 }
00093
00094 void broadcastCollisionMarkers() {
00095 cps_->getCollisionModelsInterface()->bodiesLock();
00096 if(!cps_->getCollisionModelsInterface()->isPlanningSceneSet() || cps_->getCurrentGroupName().empty()) {
00097 cps_->getCollisionModelsInterface()->bodiesUnlock();
00098 return;
00099 }
00100 cps_->setCurrentGroupState(*cps_->getCollisionModelsInterface()->getPlanningSceneState());
00101 std::vector<collision_proximity::GradientInfo> gradients;
00102 cps_->getStateGradients(gradients);
00103
00104 visualization_msgs::MarkerArray arr;
00105 cps_->getProximityGradientMarkers(current_link_names_,
00106 current_attached_body_names_,
00107 gradients,
00108 "",
00109 arr);
00110 cps_->visualizeObjectSpheres(current_link_names_);
00111 vis_marker_array_publisher_.publish(arr);
00112 cps_->getCollisionModelsInterface()->bodiesUnlock();
00113 }
00114
00115 std::vector<std::string> current_link_names_;
00116 std::vector<std::string> current_attached_body_names_;
00117
00118 ros::NodeHandle root_handle_;
00119 ros::ServiceServer motion_planning_service_;
00120 ros::ServiceServer get_state_validity_service_;
00121 collision_proximity::CollisionProximitySpace* cps_;
00122 ros::Publisher vis_marker_publisher_;
00123 ros::Publisher vis_marker_array_publisher_;
00124 };
00125
00126
00127 int main(int argc, char** argv)
00128 {
00129 ros::init(argc, argv, "collision_proximity_server_test");
00130
00131 ros::AsyncSpinner spinner(1);
00132 spinner.start();
00133
00134 ros::NodeHandle nh;
00135 std::string robot_description_name = nh.resolveName("robot_description", true);
00136
00137 CollisionProximitySpacePlannerInterface cps(robot_description_name);
00138
00139 ros::Rate r(10.0);
00140 while(nh.ok()) {
00141 cps.broadcastCollisionMarkers();
00142 r.sleep();
00143 }
00144 ros::waitForShutdown();
00145 return 0;
00146
00147
00148 }