00001 #include <ros/ros.h>
00002 #include <planning_environment_msgs/GetStateValidity.h>
00003
00004 int main(int argc, char **argv){
00005 ros::init (argc, argv, "get_state_validity_test");
00006 ros::NodeHandle rh;
00007
00008 ros::service::waitForService("environment_server_right_arm/get_state_validity");
00009 ros::ServiceClient check_state_validity_client_ = rh.serviceClient<planning_environment_msgs::GetStateValidity>("environment_server_right_arm/get_state_validity");
00010
00011 planning_environment_msgs::GetStateValidity::Request req;
00012 planning_environment_msgs::GetStateValidity::Response res;
00013
00014 req.robot_state.joint_state.name.push_back("r_shoulder_pan_joint");
00015 req.robot_state.joint_state.name.push_back("r_shoulder_lift_joint");
00016 req.robot_state.joint_state.name.push_back("r_upper_arm_roll_joint");
00017 req.robot_state.joint_state.name.push_back("r_elbow_flex_joint");
00018 req.robot_state.joint_state.name.push_back("r_forearm_roll_joint");
00019 req.robot_state.joint_state.name.push_back("r_wrist_flex_joint");
00020 req.robot_state.joint_state.name.push_back("r_wrist_roll_joint");
00021 req.robot_state.joint_state.position.resize(7,0.0);
00022
00023
00024 req.robot_state.joint_state.position[0] = 0.0;
00025
00026 req.robot_state.joint_state.header.stamp = ros::Time::now();
00027 req.check_collisions = true;
00028 if(check_state_validity_client_.call(req,res))
00029 {
00030 if(res.error_code.val == res.error_code.SUCCESS)
00031 ROS_INFO("Requested state is not in collision");
00032 else
00033 ROS_INFO("Requested state is in collision. Error code: %d",res.error_code.val);
00034 }
00035 else
00036 {
00037 ROS_ERROR("Service call to check state validity failed %s",check_state_validity_client_.getService().c_str());
00038 return false;
00039 }
00040 ros::shutdown();
00041 }