get_joint_trajectory_validity_service.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <arm_navigation_msgs/SetPlanningSceneDiff.h>
00003 #include <arm_navigation_msgs/GetJointTrajectoryValidity.h>
00004 #include <planning_environment/models/collision_models.h>
00005 #include <planning_environment/models/model_utils.h>
00006 
00007 static const std::string SET_PLANNING_SCENE_DIFF_NAME = "/environment_server/set_planning_scene_diff";
00008 static const std::string GET_JOINT_TRAJECTORY_VALIDITY_NAME = "/planning_scene_validity_server/get_trajectory_validity";
00009 
00010 int main(int argc, char **argv){
00011   ros::init (argc, argv, "get_joint_trajectory_validity_service_test");
00012   ros::NodeHandle rh;
00013 
00014   ros::Publisher vis_marker_publisher_;
00015   ros::Publisher vis_marker_array_publisher_;
00016 
00017   vis_marker_publisher_ = rh.advertise<visualization_msgs::Marker>("state_validity_markers", 128);
00018   vis_marker_array_publisher_ = rh.advertise<visualization_msgs::MarkerArray>("state_validity_markers_array", 128);
00019 
00020   ros::service::waitForService(SET_PLANNING_SCENE_DIFF_NAME);
00021   ros::ServiceClient set_planning_scene_diff_client = 
00022     rh.serviceClient<arm_navigation_msgs::SetPlanningSceneDiff>(SET_PLANNING_SCENE_DIFF_NAME);
00023   ros::ServiceClient get_joint_trajectory_validity_client = 
00024     rh.serviceClient<arm_navigation_msgs::GetJointTrajectoryValidity>(GET_JOINT_TRAJECTORY_VALIDITY_NAME);
00025 
00026   arm_navigation_msgs::SetPlanningSceneDiff::Request planning_scene_req;
00027   arm_navigation_msgs::SetPlanningSceneDiff::Response planning_scene_res;
00028 
00029   if(!set_planning_scene_diff_client.call(planning_scene_req, planning_scene_res)) {
00030     ROS_WARN("Can't get planning scene");
00031     return -1;
00032   }
00033 
00034   planning_environment::CollisionModels collision_models("robot_description");
00035   planning_models::KinematicState* state = 
00036     collision_models.setPlanningScene(planning_scene_res.planning_scene);
00037 
00038   std::vector<std::string> arm_names = 
00039     collision_models.getKinematicModel()->getModelGroup("right_arm")->getUpdatedLinkModelNames();
00040   std::vector<std::string> joint_names = 
00041     collision_models.getKinematicModel()->getModelGroup("right_arm")->getJointModelNames();
00042 
00043   trajectory_msgs::JointTrajectory trajectory;
00044   trajectory.joint_names.push_back("r_shoulder_pan_joint");
00045   trajectory.points.resize(100);
00046 
00047   std::map<std::string, double> start_vals;
00048   state->getKinematicStateValues(start_vals);
00049   double start_angle = start_vals["r_shoulder_pan_joint"];
00050 
00051   double goal_angle = .9;
00052   if(argc > 1) {
00053     std::stringstream s(argv[1]);
00054     s >> goal_angle;
00055   } else {
00056     ROS_ERROR_STREAM("Must supply goal argument");
00057     collision_models.revertPlanningScene(state);
00058     ros::shutdown();
00059     return -1;
00060   }
00061 
00062   for(unsigned int i=0; i < 100; i++)
00063   {    
00064     trajectory.points[i].positions.push_back(start_angle+i*(goal_angle-start_angle)/100.0);
00065   }
00066 
00067   std_msgs::ColorRGBA good_color, collision_color, joint_limits_color;
00068   good_color.a = collision_color.a = joint_limits_color.a = .8;
00069 
00070   good_color.g = 1.0;
00071   collision_color.r = 1.0;
00072   joint_limits_color.b = 1.0;
00073 
00074   std_msgs::ColorRGBA point_markers;
00075   point_markers.a = 1.0;
00076   point_markers.r = 1.0;
00077   point_markers.g = .8;
00078 
00079   visualization_msgs::MarkerArray arr;
00080 
00081   arm_navigation_msgs::GetJointTrajectoryValidity::Request vreq;
00082   arm_navigation_msgs::GetJointTrajectoryValidity::Response vres;
00083 
00084   vreq.trajectory = trajectory;
00085   vreq.check_joint_limits = true;
00086   vreq.check_collisions = true;
00087 
00088   if(!get_joint_trajectory_validity_client.call(vreq, vres)) {
00089     ROS_WARN("Can't get validity");
00090     collision_models.revertPlanningScene(state);
00091     ros::shutdown();
00092     return -1;
00093   }
00094 
00095   std::map<std::string, double> state_vals;
00096   if(vres.error_code.val != arm_navigation_msgs::ArmNavigationErrorCodes::SUCCESS) {
00097     std_msgs::ColorRGBA color;
00098     state_vals["r_shoulder_pan_joint"] = trajectory.points[vres.trajectory_error_codes.size()-1].positions[0];
00099     state->setKinematicState(state_vals);
00100     if(vres.error_code.val == arm_navigation_msgs::ArmNavigationErrorCodes::JOINT_LIMITS_VIOLATED) {
00101       color = joint_limits_color;
00102     } else {
00103       color = collision_color;
00104       collision_models.getAllCollisionPointMarkers(*state,
00105                                                    arr,
00106                                                    point_markers,
00107                                                    ros::Duration(0.2));
00108     }
00109     collision_models.getRobotMarkersGivenState(*state,
00110                                                arr,
00111                                                color,
00112                                                "right_arm_invalid",
00113                                                ros::Duration(0.2),
00114                                                &arm_names);
00115   }
00116   state_vals["r_shoulder_pan_joint"] = trajectory.points.back().positions[0];
00117   state->setKinematicState(state_vals);
00118   collision_models.getRobotMarkersGivenState(*state,
00119                                              arr,
00120                                              good_color,
00121                                              "right_arm_goal",
00122                                              ros::Duration(0.2),
00123                                              &arm_names);
00124 
00125   while(ros::ok()) {    
00126     vis_marker_array_publisher_.publish(arr);
00127     ros::spinOnce();
00128     ros::Duration(.1).sleep();
00129   }
00130   collision_models.revertPlanningScene(state);
00131   ros::shutdown();
00132 }
00133 


pr2_arm_navigation_tutorials
Author(s): Sachin Chitta
autogenerated on Sat Dec 28 2013 17:22:53