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 #include <frame_marker.h>
00038 #include <moveit/robot_interaction/interactive_marker_helpers.h>
00039
00040 #include <interactive_markers/tools.h>
00041
00042 #include <eigen_conversions/eigen_msg.h>
00043
00044 #include <boost/math/constants/constants.hpp>
00045
00046 namespace benchmark_tool
00047 {
00048
00049 const float GripperMarker::GOAL_NOT_TESTED_COLOR[4] = { 0.75, 0.75, 0.75, 1.0};
00050 const float GripperMarker::GOAL_PROCESSING_COLOR[4] = { 0.9, 0.9, 0.9, 1.0};
00051 const float GripperMarker::GOAL_NOT_REACHABLE_COLOR[4] = { 1.0, 0.0, 0.0, 1.0};
00052 const float GripperMarker::GOAL_REACHABLE_COLOR[4] = { 0.0, 1.0, 0.0, 1.0};
00053 const float GripperMarker::GOAL_COLLISION_COLOR[4] = { 1.0, 1.0, 0.0, 1.0};
00054
00055 FrameMarker::FrameMarker(Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name,
00056 const std::string &frame_id, const geometry_msgs::Pose &pose, double scale, const std_msgs::ColorRGBA &color,
00057 bool is_selected, bool visible_x, bool visible_y, bool visible_z):
00058 parent_node_(parent_node),
00059 context_(context),
00060 selected_(is_selected),
00061 visible_x_(visible_x),
00062 visible_y_(visible_y),
00063 visible_z_(visible_z),
00064 color_(color),
00065 receiver_(NULL),
00066 receiver_method_(NULL)
00067 {
00068 buildFrom(name, frame_id, pose, scale, color);
00069 }
00070
00071 FrameMarker::FrameMarker(Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name,
00072 const std::string &frame_id, const geometry_msgs::Pose &pose, double scale, const float color[4],
00073 bool is_selected, bool visible_x, bool visible_y, bool visible_z):
00074 parent_node_(parent_node),
00075 context_(context),
00076 selected_(is_selected),
00077 visible_x_(visible_x),
00078 visible_y_(visible_y),
00079 visible_z_(visible_z),
00080 receiver_(NULL),
00081 receiver_method_(NULL)
00082 {
00083 color_.r = color[0];
00084 color_.g = color[1];
00085 color_.b = color[2];
00086 color_.a = color[3];
00087 buildFrom(name, frame_id, pose, scale, color_);
00088 }
00089
00090 void FrameMarker::hide(void)
00091 {
00092 if ( isVisible() )
00093 {
00094 position_ = imarker->getPosition();
00095 orientation_ = imarker->getOrientation();
00096 imarker.reset();
00097 }
00098 }
00099
00100 void FrameMarker::show(Ogre::SceneNode *scene_node, rviz::DisplayContext *context)
00101 {
00102 if ( ! isVisible() )
00103 {
00104 rebuild();
00105 }
00106 }
00107
00108 void FrameMarker::showDescription(const std::string &description)
00109 {
00110 imarker_msg.description = description;
00111
00112 if (isVisible())
00113 {
00114 Ogre::Vector3 position = imarker->getPosition();
00115 Ogre::Quaternion orientation = imarker->getOrientation();
00116 updateMarker();
00117 imarker->setPose(position, orientation, "");
00118 }
00119 imarker->setShowDescription(true);
00120 }
00121
00122 void FrameMarker::hideDescription()
00123 {
00124 imarker->setShowDescription(false);
00125 }
00126
00127 void FrameMarker::getPosition(geometry_msgs::Point &position)
00128 {
00129 if (imarker)
00130 {
00131 position.x = imarker->getPosition().x;
00132 position.y = imarker->getPosition().y;
00133 position.z = imarker->getPosition().z;
00134 }
00135 else
00136 {
00137 position.x = position_.x;
00138 position.y = position_.y;
00139 position.z = position_.z;
00140 }
00141 }
00142
00143 void FrameMarker::getOrientation(geometry_msgs::Quaternion &orientation)
00144 {
00145 if (imarker)
00146 {
00147 orientation.x = imarker->getOrientation().x;
00148 orientation.y = imarker->getOrientation().y;
00149 orientation.z = imarker->getOrientation().z;
00150 orientation.w = imarker->getOrientation().w;
00151 }
00152 else
00153 {
00154 orientation.x = orientation_.x;
00155 orientation.y = orientation_.y;
00156 orientation.z = orientation_.z;
00157 orientation.w = orientation_.w;
00158 }
00159 }
00160
00161 void FrameMarker::getPose(Eigen::Affine3d &pose)
00162 {
00163 pose = Eigen::Affine3d(Eigen::Quaterniond(imarker->getOrientation().w, imarker->getOrientation().x,
00164 imarker->getOrientation().y, imarker->getOrientation().z));
00165 pose.translation() = Eigen::Vector3d(imarker->getPosition().x,
00166 imarker->getPosition().y,
00167 imarker->getPosition().z);
00168 }
00169
00170 void FrameMarker::setPose(Eigen::Affine3d &pose)
00171 {
00172 Eigen::Quaterniond q(pose.rotation());
00173 imarker->setPose(Ogre::Vector3(pose.translation().x(), pose.translation().y(), pose.translation().z()),
00174 Ogre::Quaternion(q.w(), q.x(), q.y(), q.z()), "");
00175 }
00176
00177 void FrameMarker::setColor(float r, float g, float b, float a)
00178 {
00179
00180 color_.r = r;
00181 color_.g = g;
00182 color_.b = b;
00183 color_.a = a;
00184
00185 for (unsigned int c = 0; c < imarker_msg.controls.size(); ++c)
00186 {
00187 for (unsigned int m = 0; m < imarker_msg.controls[c].markers.size(); ++m)
00188 {
00189 if (imarker_msg.controls[c].markers[m].type == visualization_msgs::Marker::MESH_RESOURCE ||
00190 imarker_msg.controls[c].markers[m].type == visualization_msgs::Marker::SPHERE)
00191 {
00192 imarker_msg.controls[c].markers[m].color.r = r;
00193 imarker_msg.controls[c].markers[m].color.g = g;
00194 imarker_msg.controls[c].markers[m].color.b = b;
00195 imarker_msg.controls[c].markers[m].color.a = a;
00196 }
00197 }
00198 }
00199
00200 if (isVisible())
00201 {
00202 Ogre::Vector3 position = imarker->getPosition();
00203 Ogre::Quaternion orientation = imarker->getOrientation();
00204 updateMarker();
00205 imarker->setPose(position, orientation, "");
00206 }
00207 }
00208
00209 void FrameMarker::select(void)
00210 {
00211 selected_ = true;
00212 rebuild();
00213 }
00214
00215 void FrameMarker::unselect(void)
00216 {
00217 selected_ = false;
00218 rebuild();
00219 }
00220
00221 void FrameMarker::rebuild()
00222 {
00223 geometry_msgs::Pose pose;
00224 getPosition(pose.position);
00225 getOrientation(pose.orientation);
00226 buildFrom(imarker_msg.name, imarker_msg.header.frame_id, pose, imarker_msg.scale, color_);
00227 }
00228
00229 void FrameMarker::buildFrom(const std::string &name, const std::string &frame_id, const geometry_msgs::Pose &pose, double scale, const std_msgs::ColorRGBA &color)
00230 {
00231 color_ = color;
00232
00233 visualization_msgs::InteractiveMarker int_marker;
00234 if (isSelected())
00235 {
00236 geometry_msgs::PoseStamped pose_stamped;
00237 pose_stamped.header.frame_id = frame_id;
00238 pose_stamped.pose = pose;
00239 int_marker = robot_interaction::make6DOFMarker(name, pose_stamped, scale);
00240 }
00241 else
00242 {
00243 int_marker.scale = scale;
00244 int_marker.name = name;
00245 int_marker.pose = pose;
00246 }
00247 int_marker.header.frame_id = frame_id;
00248 int_marker.header.stamp = ros::Time::now();
00249
00250 int_marker.menu_entries = menu_entries_;
00251
00252 visualization_msgs::InteractiveMarkerControl m_control;
00253 m_control.always_visible = true;
00254 m_control.interaction_mode = m_control.BUTTON;
00255
00256
00257 visualization_msgs::Marker m;
00258 m.type = visualization_msgs::Marker::SPHERE;
00259 m.scale.x = 0.1 * scale;
00260 m.scale.y = 0.1 * scale;
00261 m.scale.z = 0.1 * scale;
00262 m.ns = "goal_pose_marker";
00263 m.action = visualization_msgs::Marker::ADD;
00264 m.color = color;
00265 m_control.markers.push_back(m);
00266
00267 m.type = visualization_msgs::Marker::ARROW;
00268 m.scale.x = 0.3 * scale;
00269 m.scale.y = 0.1 * m.scale.x;
00270 m.scale.z = 0.1 * m.scale.x;
00271 m.ns = "goal_pose_marker";
00272 m.action = visualization_msgs::Marker::ADD;
00273
00274
00275 if (visible_x_)
00276 {
00277 m.color.r = 1.0f;
00278 m.color.g = 0.0f;
00279 m.color.b = 0.0f;
00280 m.color.a = 1.0f;
00281 m_control.markers.push_back(m);
00282 }
00283
00284
00285 if (visible_y_)
00286 {
00287 tf::Quaternion imq;
00288 imq = tf::createQuaternionFromRPY(0, 0, boost::math::constants::pi<double>() / 2.0);
00289 tf::quaternionTFToMsg(imq, m.pose.orientation);
00290 m.color.r = 0.0f;
00291 m.color.g = 1.0f;
00292 m.color.b = 0.0f;
00293 m.color.a = 1.0f;
00294 m_control.markers.push_back(m);
00295 }
00296
00297
00298 if (visible_z_) {
00299 tf::Quaternion imq;
00300 imq = tf::createQuaternionFromRPY(0, -boost::math::constants::pi<double>() / 2.0, 0);
00301 tf::quaternionTFToMsg(imq, m.pose.orientation);
00302 m.color.r = 0.0f;
00303 m.color.g = 0.0f;
00304 m.color.b = 1.0f;
00305 m.color.a = 1.0f;
00306 m_control.markers.push_back(m);
00307 }
00308 int_marker.controls.push_back(m_control);
00309
00310 imarker.reset(new rviz::InteractiveMarker(parent_node_, context_ ));
00311 interactive_markers::autoComplete(int_marker);
00312 imarker->processMessage(int_marker);
00313 imarker->setShowVisualAids(true);
00314 imarker->setShowAxes(false);
00315 imarker->setShowDescription(false);
00316
00317
00318 if (receiver_ && receiver_method_)
00319 {
00320 connect(receiver_, receiver_method_);
00321 }
00322
00323 imarker_msg = int_marker;
00324 }
00325
00326
00327 GripperMarker::GripperMarker(const robot_state::RobotState& robot_state, Ogre::SceneNode *parent_node, rviz::DisplayContext *context, const std::string &name,
00328 const std::string &frame_id, const robot_interaction::RobotInteraction::EndEffector &eef, const geometry_msgs::Pose &pose, double scale,
00329 const GripperMarkerState &state, bool is_selected, bool visible_x, bool visible_y, bool visible_z):
00330 FrameMarker(parent_node, context, name, frame_id, pose, scale, stateToColor(state), is_selected, visible_x, visible_y, visible_z),
00331 eef_(eef),
00332 display_gripper_mesh_(false),
00333 state_(state)
00334 {
00335 robot_state_ = &robot_state;
00336 }
00337
00338 void GripperMarker::select(bool display_gripper_mesh)
00339 {
00340 display_gripper_mesh_ = display_gripper_mesh;
00341 FrameMarker::select();
00342 }
00343
00344 void GripperMarker::unselect(bool display_gripper_mesh)
00345 {
00346 display_gripper_mesh_ = display_gripper_mesh;
00347 FrameMarker::unselect();
00348 }
00349
00350 void GripperMarker::buildFrom(const std::string &name, const std::string &frame_id, const geometry_msgs::Pose &pose, double scale, const std_msgs::ColorRGBA &color)
00351 {
00352 color_ = color;
00353
00354 visualization_msgs::InteractiveMarker int_marker;
00355 if (isSelected())
00356 {
00357 geometry_msgs::PoseStamped pose_stamped;
00358 pose_stamped.pose = pose;
00359 int_marker = robot_interaction::make6DOFMarker(name, pose_stamped, scale);
00360 }
00361 else
00362 {
00363 int_marker.scale = scale;
00364 int_marker.name = name;
00365 int_marker.pose = pose;
00366 }
00367 int_marker.header.frame_id = frame_id;
00368 int_marker.header.stamp = ros::Time::now();
00369
00370 int_marker.menu_entries = menu_entries_;
00371
00372 visualization_msgs::InteractiveMarkerControl m_control;
00373 m_control.always_visible = true;
00374 m_control.interaction_mode = m_control.BUTTON;
00375
00376 if (display_gripper_mesh_)
00377 {
00378
00379 const robot_state::JointModelGroup *joint_model_group = robot_state_->getJointModelGroup(eef_.eef_group);
00380 const std::vector<std::string> &link_names = joint_model_group->getLinkModelNames();
00381
00382 std_msgs::ColorRGBA marker_color;
00383 marker_color = color;
00384 visualization_msgs::MarkerArray marker_array;
00385 robot_state_->getRobotMarkers(marker_array, link_names, marker_color, "goal_pose_marker", ros::Duration());
00386
00387 for (std::size_t i = 0 ; i < marker_array.markers.size() ; ++i)
00388 {
00389 marker_array.markers[i].header = int_marker.header;
00390 m_control.markers.push_back(marker_array.markers[i]);
00391 }
00392
00393 Eigen::Affine3d tip_pose = robot_state_->getGlobalLinkTransform(eef_.parent_link);
00394 tf::poseEigenToMsg(tip_pose, int_marker.pose);
00395 }
00396 else
00397 {
00398
00399 visualization_msgs::Marker m;
00400 m.type = visualization_msgs::Marker::SPHERE;
00401 m.scale.x = 0.1 * scale;
00402 m.scale.y = 0.1 * scale;
00403 m.scale.z = 0.1 * scale;
00404 m.ns = "goal_pose_marker";
00405 m.action = visualization_msgs::Marker::ADD;
00406 m.color = color;
00407 m_control.markers.push_back(m);
00408
00409 m.type = visualization_msgs::Marker::ARROW;
00410 m.scale.x = 0.3 * scale;
00411 m.scale.y = 0.1 * m.scale.x;
00412 m.scale.z = 0.1 * m.scale.x;
00413 m.ns = "goal_pose_marker";
00414 m.action = visualization_msgs::Marker::ADD;
00415
00416
00417 if (visible_x_)
00418 {
00419 m.color.r = 1.0f;
00420 m.color.g = 0.0f;
00421 m.color.b = 0.0f;
00422 m.color.a = 1.0f;
00423 m_control.markers.push_back(m);
00424 }
00425
00426
00427 if (visible_y_)
00428 {
00429 tf::Quaternion imq;
00430 imq = tf::createQuaternionFromRPY(0, 0, boost::math::constants::pi<double>() / 2.0);
00431 tf::quaternionTFToMsg(imq, m.pose.orientation);
00432 m.color.r = 0.0f;
00433 m.color.g = 1.0f;
00434 m.color.b = 0.0f;
00435 m.color.a = 1.0f;
00436 m_control.markers.push_back(m);
00437 }
00438
00439
00440 if (visible_z_) {
00441 tf::Quaternion imq;
00442 imq = tf::createQuaternionFromRPY(0, -boost::math::constants::pi<double>() / 2.0, 0);
00443 tf::quaternionTFToMsg(imq, m.pose.orientation);
00444 m.color.r = 0.0f;
00445 m.color.g = 0.0f;
00446 m.color.b = 1.0f;
00447 m.color.a = 1.0f;
00448 m_control.markers.push_back(m);
00449 }
00450 }
00451
00452 int_marker.controls.push_back(m_control);
00453
00454 imarker.reset(new rviz::InteractiveMarker(parent_node_, context_ ));
00455 interactive_markers::autoComplete(int_marker);
00456 imarker->processMessage(int_marker);
00457 imarker->setShowAxes(false);
00458 imarker->setShowVisualAids(true);
00459 imarker->setShowDescription(false);
00460 imarker->setPose(Ogre::Vector3(pose.position.x, pose.position.y, pose.position.z),
00461 Ogre::Quaternion(pose.orientation.w, pose.orientation.x, pose.orientation.y, pose.orientation.z), "");
00462
00463
00464 if (receiver_ && receiver_method_)
00465 {
00466 connect(receiver_, receiver_method_);
00467 }
00468
00469 imarker_msg = int_marker;
00470 }
00471
00472 const float *GripperMarker::stateToColor(const GripperMarkerState &state)
00473 {
00474 const float *color = 0;
00475 if (state == NOT_TESTED)
00476 color = GOAL_NOT_TESTED_COLOR;
00477 else if (state == PROCESSING)
00478 color = GOAL_PROCESSING_COLOR;
00479 else if (state == REACHABLE)
00480 color = GOAL_REACHABLE_COLOR;
00481 else if (state == NOT_REACHABLE)
00482 color = GOAL_NOT_REACHABLE_COLOR;
00483 else if (state == IN_COLLISION)
00484 color = GOAL_COLLISION_COLOR;
00485 else
00486 color = GOAL_NOT_TESTED_COLOR;
00487
00488 return color;
00489 }
00490 }