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
00039
00040
00041 #include <ros/ros.h>
00042 #include "interactive_robot.h"
00043 #include "pose_string.h"
00044
00045
00046 #include <moveit/robot_model/robot_model.h>
00047 #include <moveit/robot_state/robot_state.h>
00048 #include <moveit/planning_scene/planning_scene.h>
00049 #include <moveit/collision_detection_fcl/collision_world_fcl.h>
00050 #include <moveit/collision_detection_fcl/collision_robot_fcl.h>
00051 #include <moveit/collision_detection/collision_tools.h>
00052
00053
00054 planning_scene::PlanningScene* g_planning_scene = 0;
00055 shapes::ShapePtr g_world_cube_shape;
00056 ros::Publisher *g_marker_array_publisher = 0;
00057 visualization_msgs::MarkerArray g_collision_points;
00058
00059
00060 void help()
00061 {
00062 ROS_INFO("#####################################################");
00063 ROS_INFO("RVIZ SETUP");
00064 ROS_INFO("----------");
00065 ROS_INFO(" Global options:");
00066 ROS_INFO(" FixedFrame = /base_footprint");
00067 ROS_INFO(" Add a RobotState display:");
00068 ROS_INFO(" RobotDescription = robot_description");
00069 ROS_INFO(" RobotStateTopic = interactive_robot_state");
00070 ROS_INFO(" Add a Marker display:");
00071 ROS_INFO(" MarkerTopic = interactive_robot_markers");
00072 ROS_INFO(" Add an InteractiveMarker display:");
00073 ROS_INFO(" UpdateTopic = interactive_robot_imarkers/update");
00074 ROS_INFO(" Add a MarkerArray display:");
00075 ROS_INFO(" MarkerTopic = interactive_robot_marray");
00076 ROS_INFO("#####################################################");
00077 }
00078
00079 void publishMarkers(visualization_msgs::MarkerArray& markers)
00080 {
00081
00082 if (g_collision_points.markers.size())
00083 {
00084 for (int i=0; i<g_collision_points.markers.size(); i++)
00085 g_collision_points.markers[i].action = visualization_msgs::Marker::DELETE;
00086
00087 g_marker_array_publisher->publish(g_collision_points);
00088 }
00089
00090
00091 std::swap(g_collision_points.markers, markers.markers);
00092
00093
00094 if (g_collision_points.markers.size())
00095 g_marker_array_publisher->publish(g_collision_points);
00096 }
00097
00098
00099 void userCallback(InteractiveRobot& robot)
00100 {
00101
00102 Eigen::Affine3d world_cube_pose;
00103 double world_cube_size;
00104 robot.getWorldGeometry(world_cube_pose, world_cube_size);
00105 g_planning_scene->getWorldNonConst()->moveShapeInObject("world_cube", g_world_cube_shape, world_cube_pose);
00106
00107
00108 collision_detection::CollisionRequest c_req;
00109 collision_detection::CollisionResult c_res;
00110 c_req.group_name = robot.getGroupName();
00111 c_req.contacts = true;
00112 c_req.max_contacts = 100;
00113 c_req.max_contacts_per_pair = 5;
00114 c_req.verbose = false;
00115
00116
00117 g_planning_scene->checkCollision(c_req, c_res, *robot.robotState());
00118
00119
00120 if (c_res.collision)
00121 {
00122 ROS_INFO("COLLIDING contact_point_count=%d",(int)c_res.contact_count);
00123
00124
00125 if (c_res.contact_count > 0)
00126 {
00127 std_msgs::ColorRGBA color;
00128 color.r = 1.0;
00129 color.g = 0.0;
00130 color.b = 1.0;
00131 color.a = 0.5;
00132 visualization_msgs::MarkerArray markers;
00133 collision_detection::getCollisionMarkersFromContacts(markers,
00134 "base_footprint",
00135 c_res.contacts,
00136 color,
00137 ros::Duration(),
00138 0.01);
00139 publishMarkers(markers);
00140 }
00141 }
00142 else
00143 {
00144 ROS_INFO("Not colliding");
00145
00146
00147 visualization_msgs::MarkerArray empty_marker_array;
00148 publishMarkers(empty_marker_array);
00149 }
00150 }
00151
00152
00153 int main(int argc, char **argv)
00154 {
00155 ros::init (argc, argv, "acorn_play");
00156 ros::NodeHandle nh;
00157
00158 InteractiveRobot robot;
00159
00160
00161 g_planning_scene = new planning_scene::PlanningScene(robot.robotModel());
00162
00163
00164 Eigen::Affine3d world_cube_pose;
00165 double world_cube_size;
00166 robot.getWorldGeometry(world_cube_pose, world_cube_size);
00167 g_world_cube_shape.reset(new shapes::Box(world_cube_size, world_cube_size, world_cube_size));
00168 g_planning_scene->getWorldNonConst()->addToObject("world_cube", g_world_cube_shape, world_cube_pose);
00169
00170
00171 g_marker_array_publisher = new ros::Publisher(nh.advertise<visualization_msgs::MarkerArray>("interactive_robot_marray",100));
00172
00173 robot.setUserCallback(userCallback);
00174
00175 help();
00176
00177 ros::spin();
00178
00179 delete g_planning_scene;
00180 delete g_marker_array_publisher;;
00181
00182 ros::shutdown();
00183 return 0;
00184 }