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
00035
00036
00037
00038 #include <ros/ros.h>
00039 #include <geometry_msgs/Pose.h>
00040
00041
00042 #include <moveit_msgs/PlanningScene.h>
00043 #include <moveit_msgs/AttachedCollisionObject.h>
00044 #include <moveit_msgs/GetStateValidity.h>
00045 #include <moveit_msgs/DisplayRobotState.h>
00046
00047 #include <moveit/robot_model_loader/robot_model_loader.h>
00048 #include <moveit/robot_state/robot_state.h>
00049 #include <moveit/robot_state/conversions.h>
00050
00051
00052 int main(int argc, char **argv)
00053 {
00054 ros::init (argc, argv, "planning_scene_ros_api_tutorial");
00055 ros::AsyncSpinner spinner(1);
00056 spinner.start();
00057
00058 ros::NodeHandle node_handle;
00059
00060
00061
00062 ros::Publisher attached_object_publisher = node_handle.advertise<moveit_msgs::AttachedCollisionObject>("attached_collision_object", 1);
00063 while(attached_object_publisher.getNumSubscribers() < 1)
00064 {
00065 ros::WallDuration sleep_t(0.5);
00066 sleep_t.sleep();
00067 }
00068
00069
00070 moveit_msgs::AttachedCollisionObject attached_object;
00071 attached_object.link_name = "r_wrist_roll_link";
00072
00073 attached_object.object.header.frame_id = "r_wrist_roll_link";
00074
00075 attached_object.object.id = "box";
00076
00077
00078 geometry_msgs::Pose pose;
00079 pose.orientation.w = 1.0;
00080
00081
00082 shape_msgs::SolidPrimitive primitive;
00083 primitive.type = primitive.BOX;
00084 primitive.dimensions.resize(3);
00085 primitive.dimensions[0] = 0.1;
00086 primitive.dimensions[1] = 0.1;
00087 primitive.dimensions[2] = 0.1;
00088
00089 attached_object.object.primitives.push_back(primitive);
00090 attached_object.object.primitive_poses.push_back(pose);
00091
00092
00093 attached_object.object.operation = attached_object.object.ADD;
00094
00095
00096 attached_object_publisher.publish(attached_object);
00097 ros::WallDuration sleep_time(10.0);
00098 sleep_time.sleep();
00099
00100
00101
00102 moveit_msgs::AttachedCollisionObject detach_object;
00103 detach_object.object.id = "box";
00104 detach_object.link_name = "r_wrist_roll_link";
00105 detach_object.object.operation = attached_object.object.REMOVE;
00106 ROS_INFO("Detaching the object");
00107 attached_object_publisher.publish(detach_object);
00108 sleep_time.sleep();
00109
00110
00111
00112
00113 ros::Publisher collision_object_publisher = node_handle.advertise<moveit_msgs::CollisionObject>("collision_object", 1);
00114 while(collision_object_publisher.getNumSubscribers() < 1)
00115 {
00116 ros::WallDuration sleep_t(0.5);
00117 sleep_t.sleep();
00118 }
00119
00120 moveit_msgs::CollisionObject remove_object;
00121 remove_object.id = "box";
00122 remove_object.header.frame_id = "odom_combined";
00123 remove_object.operation = remove_object.REMOVE;
00124 ROS_INFO("Removing the object");
00125 collision_object_publisher.publish(remove_object);
00126 sleep_time.sleep();
00127
00128
00129
00130 ros::Publisher planning_scene_diff_publisher = node_handle.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
00131 while(planning_scene_diff_publisher.getNumSubscribers() < 1)
00132 {
00133 ros::WallDuration sleep_t(0.5);
00134 sleep_t.sleep();
00135 }
00136
00137
00138 ROS_INFO("Putting the object back into the environment");
00139 moveit_msgs::PlanningScene planning_scene;
00140 planning_scene.world.collision_objects.push_back(attached_object.object);
00141 planning_scene.is_diff = true;
00142 planning_scene_diff_publisher.publish(planning_scene);
00143 sleep_time.sleep();
00144
00145
00146 ROS_INFO("Attaching the object and removing it from the collision world");
00147 planning_scene.world.collision_objects.clear();
00148 planning_scene.world.collision_objects.push_back(remove_object);
00149 planning_scene.robot_state.attached_collision_objects.push_back(attached_object);
00150 planning_scene_diff_publisher.publish(planning_scene);
00151
00152 sleep_time.sleep();
00153
00154
00155 ROS_INFO("Detaching the object and returning it to the collision world");
00156 planning_scene.robot_state.attached_collision_objects.clear();
00157 planning_scene.robot_state.attached_collision_objects.push_back(detach_object);
00158 planning_scene.world.collision_objects.clear();
00159 planning_scene.world.collision_objects.push_back(attached_object.object);
00160 planning_scene_diff_publisher.publish(planning_scene);
00161
00162 sleep_time.sleep();
00163
00164
00165 ROS_INFO("Removing the object again");
00166 planning_scene.robot_state.attached_collision_objects.clear();
00167 planning_scene.world.collision_objects.clear();
00168 planning_scene.world.collision_objects.push_back(remove_object);
00169 planning_scene_diff_publisher.publish(planning_scene);
00170
00171 ros::shutdown();
00172 return 0;
00173 }