41 #include <moveit_msgs/DisplayTrajectory.h> 42 #include <moveit_msgs/CollisionObject.h> 68 planning_scene_monitor::PlanningSceneMonitorPtr psm)
69 : RvizVisualTools::RvizVisualTools(base_frame, marker_topic)
77 robot_model::RobotModelConstPtr robot_model)
88 "already been set for Visual Tools");
103 if (
psm_->getPlanningScene())
115 planning_scene->setName(
"visual_tools_scene");
132 scene->getCurrentStateNonConst().update();
133 scene->processCollisionObjectMsg(msg);
134 scene->setObjectColor(msg.id,
getColor(color));
151 scene->processAttachedCollisionObjectMsg(msg);
172 moveit_msgs::CollisionObject collision_obj;
175 collision_obj.id = name;
176 collision_obj.operation = moveit_msgs::CollisionObject::MOVE;
178 collision_obj.primitive_poses.resize(1);
179 collision_obj.primitive_poses[0] = pose;
239 const std::vector<double>& ee_joint_pos)
253 if (ee_joint_pos.size() > 0)
255 if (ee_joint_pos.size() != ee_jmg->getActiveJointModels().size())
258 << ee_joint_pos.size() <<
") does not match the number of active joints in " 259 << ee_jmg->getName() <<
"(" << ee_jmg->getActiveJointModels().size() <<
")");
274 static std::size_t marker_id_offset = 0;
283 const std::vector<std::string>& ee_link_names = ee_jmg->getLinkModelNames();
292 const std::string& ee_parent_link_name = ee_jmg->getEndEffectorParentGroup().second;
296 Eigen::Affine3d ee_marker_global_transform =
shared_robot_state_->getGlobalLinkTransform(ee_parent_link);
297 Eigen::Affine3d ee_marker_pose;
300 for (std::size_t i = 0; i <
ee_markers_map_[ee_jmg].markers.size(); ++i)
306 if (
ee_markers_map_[ee_jmg].markers[i].type == visualization_msgs::Marker::MESH_RESOURCE)
344 if (!robot_state_topic.empty())
357 const std::vector<double>& ee_joint_pos,
371 Eigen::Affine3d eigen_goal_ee_pose =
convertPose(pose);
372 Eigen::Affine3d eigen_this_marker;
378 for (std::size_t i = 0; i <
ee_markers_map_[ee_jmg].markers.size(); ++i)
397 eigen_this_marker = eigen_goal_ee_pose *
ee_poses_map_[ee_jmg][i];
409 const robot_model::JointModelGroup* ee_jmg,
double animate_speed)
412 << ee_jmg->getName());
415 for (std::size_t i = 0; i < possible_grasps.size(); ++i)
429 const robot_model::JointModelGroup* ee_jmg,
double animate_speed)
432 << ee_jmg->getName() <<
" at speed " << animate_speed);
435 for (std::size_t i = 0; i < possible_grasps.size(); ++i)
448 const robot_model::JointModelGroup* ee_jmg,
double animate_speed)
451 geometry_msgs::Pose grasp_pose = grasp.grasp_pose.pose;
461 Eigen::Affine3d grasp_pose_eigen;
465 geometry_msgs::Pose pre_grasp_pose;
466 Eigen::Affine3d pre_grasp_pose_eigen;
469 Eigen::Vector3d pre_grasp_approach_direction_local;
479 double animation_resulution = 0.1;
480 for (
double percent = 0; percent < 1; percent += animation_resulution)
486 pre_grasp_pose_eigen = grasp_pose_eigen;
490 Eigen::Vector3d pre_grasp_approach_direction = Eigen::Vector3d(
491 -1 * grasp.pre_grasp_approach.direction.vector.x * grasp.pre_grasp_approach.min_distance * (1 - percent),
492 -1 * grasp.pre_grasp_approach.direction.vector.y * grasp.pre_grasp_approach.min_distance * (1 - percent),
493 -1 * grasp.pre_grasp_approach.direction.vector.z * grasp.pre_grasp_approach.min_distance * (1 - percent));
497 const std::string& ee_parent_link_name = ee_jmg->getEndEffectorParentGroup().second;
499 if (grasp.pre_grasp_approach.direction.header.frame_id == ee_parent_link_name)
503 pre_grasp_approach_direction_local = grasp_pose_eigen.rotation() * pre_grasp_approach_direction;
507 pre_grasp_approach_direction_local = pre_grasp_approach_direction;
512 pre_grasp_pose_eigen.translation() += pre_grasp_approach_direction_local;
531 const robot_model::JointModelGroup* arm_jmg,
double display_time)
533 if (ik_solutions.empty())
544 trajectory_msgs::JointTrajectoryPoint trajectory_pt_timed;
547 moveit_msgs::RobotTrajectory trajectory_msg;
548 trajectory_msg.joint_trajectory.header.frame_id =
base_frame_;
549 trajectory_msg.joint_trajectory.joint_names = arm_jmg->getActiveJointModelNames();
552 double running_time = 0;
555 for (std::size_t i = 0; i < ik_solutions.size(); ++i)
557 trajectory_pt_timed = ik_solutions[i];
558 trajectory_pt_timed.time_from_start =
ros::Duration(running_time);
559 trajectory_msg.joint_trajectory.points.push_back(trajectory_pt_timed);
561 running_time += display_time;
565 trajectory_pt_timed = trajectory_msg.joint_trajectory.points.back();
566 trajectory_pt_timed.time_from_start =
ros::Duration(running_time);
567 trajectory_msg.joint_trajectory.points.push_back(trajectory_pt_timed);
577 scene->removeAllCollisionObjects();
586 moveit_msgs::CollisionObject co;
590 co.operation = moveit_msgs::CollisionObject::REMOVE;
598 moveit_msgs::AttachedCollisionObject aco;
603 aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
611 moveit_msgs::AttachedCollisionObject aco;
615 aco.object.id = name;
616 aco.object.operation = moveit_msgs::CollisionObject::ADD;
619 aco.link_name = ee_parent_link;
627 moveit_msgs::CollisionObject collision_obj;
630 collision_obj.id = name;
631 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
633 collision_obj.primitives.resize(1);
634 collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
635 collision_obj.primitives[0].dimensions.resize(
637 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = block_size;
638 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = block_size;
639 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = block_size;
640 collision_obj.primitive_poses.resize(1);
641 collision_obj.primitive_poses[0] = block_pose;
657 moveit_msgs::CollisionObject collision_obj;
660 collision_obj.id = name;
661 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
664 collision_obj.primitive_poses.resize(1);
665 collision_obj.primitive_poses[0].position.x = (point1.x - point2.x) / 2.0 + point2.x;
666 collision_obj.primitive_poses[0].position.y = (point1.y - point2.y) / 2.0 + point2.y;
667 collision_obj.primitive_poses[0].position.z = (point1.z - point2.z) / 2.0 + point2.z;
670 collision_obj.primitives.resize(1);
671 collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
672 collision_obj.primitives[0].dimensions.resize(
674 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = fabs(point1.x - point2.x);
675 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = fabs(point1.y - point2.y);
676 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = fabs(point1.z - point2.z);
679 if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X])
681 if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y])
683 if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z])
693 geometry_msgs::Pose pose_msg;
699 double height,
const std::string& name,
702 moveit_msgs::CollisionObject collision_obj;
705 collision_obj.id = name;
706 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
709 collision_obj.primitive_poses.resize(1);
710 collision_obj.primitive_poses[0] = pose;
713 collision_obj.primitives.resize(1);
714 collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
715 collision_obj.primitives[0].dimensions.resize(
717 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = width;
718 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = depth;
719 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = height;
722 if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X])
724 if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y])
726 if (!collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z])
736 geometry_msgs::Point point1;
737 geometry_msgs::Point point2;
751 const std::string& object_name,
double radius,
758 const std::string& object_name,
double radius,
762 double height = (a - b).lpNorm<2>();
768 Eigen::Affine3d pose;
772 Eigen::Affine3d rotation;
773 rotation = Eigen::AngleAxisd(0.5 *
M_PI, Eigen::Vector3d::UnitY());
774 pose = pose * rotation;
788 moveit_msgs::CollisionObject collision_obj;
791 collision_obj.id = object_name;
792 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
793 collision_obj.primitives.resize(1);
794 collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::CYLINDER;
795 collision_obj.primitives[0].dimensions.resize(
797 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::CYLINDER_HEIGHT] = height;
798 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::CYLINDER_RADIUS] = radius;
799 collision_obj.primitive_poses.resize(1);
800 collision_obj.primitive_poses[0] = object_pose;
823 if (!
publishCollisionMesh(object_pose, object_name, boost::get<shape_msgs::Mesh>(shape_msg), color))
840 moveit_msgs::CollisionObject collision_obj;
843 collision_obj.id = object_name;
844 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
845 collision_obj.mesh_poses.resize(1);
846 collision_obj.mesh_poses[0] = object_pose;
847 collision_obj.meshes.resize(1);
848 collision_obj.meshes[0] = mesh_msg;
859 moveit_msgs::CollisionObject collision_obj;
862 collision_obj.id = object_name;
863 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
866 typedef std::pair<std::size_t, std::size_t> node_ids;
867 std::set<node_ids> added_edges;
868 std::pair<std::set<node_ids>::iterator,
bool> return_value;
870 Eigen::Vector3d a, b;
871 for (std::size_t i = 0; i < graph.nodes.size(); ++i)
873 for (std::size_t j = 0; j < graph.edges[i].node_ids.size(); ++j)
876 return_value = added_edges.insert(node_ids(i, j));
877 if (return_value.second ==
false)
885 b =
convertPoint(graph.nodes[graph.edges[i].node_ids[j]]);
888 added_edges.insert(node_ids(j, i));
891 double height = (a - b).lpNorm<2>();
897 Eigen::Affine3d pose;
901 Eigen::Affine3d rotation;
902 rotation = Eigen::AngleAxisd(0.5 *
M_PI, Eigen::Vector3d::UnitY());
903 pose = pose * rotation;
906 shape_msgs::SolidPrimitive cylinder;
907 cylinder.type = shape_msgs::SolidPrimitive::CYLINDER;
908 cylinder.dimensions.resize(
910 cylinder.dimensions[shape_msgs::SolidPrimitive::CYLINDER_HEIGHT] = height;
911 cylinder.dimensions[shape_msgs::SolidPrimitive::CYLINDER_RADIUS] = radius;
914 collision_obj.primitives.push_back(cylinder);
917 collision_obj.primitive_poses.push_back(
convertPose(pose));
926 const std::string name, moveit_msgs::CollisionObject& collision_obj)
930 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
931 collision_obj.primitives.resize(1);
932 collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
933 collision_obj.primitives[0].dimensions.resize(
936 geometry_msgs::Pose rec_pose;
940 collision_obj.id = name;
945 rec_pose.position.x = x;
946 rec_pose.position.y = y;
947 rec_pose.position.z = height / 2 + z;
950 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = depth;
951 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = width;
952 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = height;
955 Eigen::Quaterniond quat(Eigen::AngleAxis<double>(static_cast<double>(angle), Eigen::Vector3d::UnitZ()));
956 rec_pose.orientation.x = quat.x();
957 rec_pose.orientation.y = quat.y();
958 rec_pose.orientation.z = quat.z();
959 rec_pose.orientation.w = quat.w();
961 collision_obj.primitive_poses.resize(1);
962 collision_obj.primitive_poses[0] = rec_pose;
974 moveit_msgs::CollisionObject collision_obj;
981 double depth,
const std::string name,
984 geometry_msgs::Pose table_pose;
987 table_pose.position.x = x;
988 table_pose.position.y = y;
989 table_pose.position.z = z + height / 2.0;
992 Eigen::Quaterniond quat(Eigen::AngleAxis<double>(static_cast<double>(angle), Eigen::Vector3d::UnitZ()));
993 table_pose.orientation.x = quat.x();
994 table_pose.orientation.y = quat.y();
995 table_pose.orientation.z = quat.z();
996 table_pose.orientation.w = quat.w();
998 moveit_msgs::CollisionObject collision_obj;
1001 collision_obj.id = name;
1002 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
1003 collision_obj.primitives.resize(1);
1004 collision_obj.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
1005 collision_obj.primitives[0].dimensions.resize(
1009 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = depth;
1010 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = width;
1011 collision_obj.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = height;
1013 collision_obj.primitive_poses.resize(1);
1014 collision_obj.primitive_poses[0] = table_pose;
1026 std::ifstream fin(path.c_str());
1034 scene->loadGeometryFromStream(fin, offset);
1055 "Planning_Workspace", 1);
1076 visualization_msgs::MarkerArray arr;
1081 if (arr.markers.empty())
1085 for (std::size_t i = 0; i < arr.markers.size(); ++i)
1087 arr.markers[i].ns =
"Collision";
1088 arr.markers[i].scale.x = 0.04;
1089 arr.markers[i].scale.y = 0.04;
1090 arr.markers[i].scale.z = 0.04;
1091 arr.markers[i].color =
getColor(color);
1100 const std::string& planning_group,
double display_time)
1103 const robot_model::JointModelGroup* jmg =
robot_model_->getJointModelGroup(planning_group);
1112 trajectory_msgs::JointTrajectoryPoint trajectory_pt_timed = trajectory_pt;
1113 trajectory_pt_timed.time_from_start =
ros::Duration(display_time);
1116 moveit_msgs::RobotTrajectory trajectory_msg;
1117 trajectory_msg.joint_trajectory.header.frame_id =
base_frame_;
1118 trajectory_msg.joint_trajectory.joint_names = jmg->getJointModelNames();
1119 trajectory_msg.joint_trajectory.points.push_back(trajectory_pt);
1120 trajectory_msg.joint_trajectory.points.push_back(trajectory_pt_timed);
1132 double duration_from_previous = 0;
1133 for (std::size_t k = 0; k < trajectory.size(); ++k)
1135 duration_from_previous += speed;
1136 robot_trajectory->addSuffixWayPoint(trajectory[k], duration_from_previous);
1140 moveit_msgs::RobotTrajectory trajectory_msg;
1141 robot_trajectory->getRobotTrajectoryMsg(trajectory_msg);
1153 moveit_msgs::RobotTrajectory trajectory_msg;
1157 if (trajectory_msg.joint_trajectory.points.size() > 1)
1159 if (trajectory_msg.joint_trajectory.points[1].time_from_start ==
ros::Duration(0))
1161 for (std::size_t i = 0; i < trajectory_msg.joint_trajectory.points.size(); ++i)
1163 trajectory_msg.joint_trajectory.points[i].time_from_start =
ros::Duration(i * 2);
1172 const robot_state::RobotStateConstPtr robot_state,
bool blocking)
1181 moveit_msgs::RobotState robot_state_msg;
1182 robot_state::robotStateToRobotStateMsg(robot_state, robot_state_msg);
1187 const moveit_msgs::RobotState& robot_state,
bool blocking)
1190 if (!trajectory_msg.joint_trajectory.points.size())
1197 moveit_msgs::DisplayTrajectory display_trajectory_msg;
1198 display_trajectory_msg.model_id =
robot_model_->getName();
1199 display_trajectory_msg.trajectory.resize(1);
1200 display_trajectory_msg.trajectory[0] = trajectory_msg;
1201 display_trajectory_msg.trajectory_start = robot_state;
1211 double duration = trajectory_msg.joint_trajectory.points.back().time_from_start.toSec();
1214 if (duration < std::numeric_limits<double>::epsilon())
1216 duration = 0.05 * trajectory_msg.joint_trajectory.points.size();
1222 static const double CHECK_TIME_INTERVAL = 0.25;
1223 while (
ros::ok() && counter <= duration)
1225 counter += CHECK_TIME_INTERVAL;
1235 const robot_model::JointModelGroup* arm_jmg,
1268 if (!ee_parent_link)
1280 const Eigen::Affine3d& tip_pose = robot_trajectory.
getWayPoint(i).getGlobalLinkTransform(ee_parent_link);
1283 if (tip_pose.translation().x() != tip_pose.translation().x())
1289 path.push_back(tip_pose.translation());
1293 const double radius = 0.005;
1300 const robot_model::JointModelGroup* arm_jmg,
1303 std::vector<const moveit::core::LinkModel*> tips;
1304 if (!arm_jmg->getEndEffectorTips(tips))
1321 const robot_model::JointModelGroup* arm_jmg,
1328 const robot_model::JointModelGroup* arm_jmg,
1331 std::vector<const moveit::core::LinkModel*> tips;
1332 if (!arm_jmg->getEndEffectorTips(tips))
1353 for (std::size_t i = 0; i < robot_state_trajectory.size(); ++i)
1355 const Eigen::Affine3d& tip_pose = robot_state_trajectory[i]->getGlobalLinkTransform(ee_parent_link);
1374 const robot_model::JointModelGroup* jmg,
1381 const robot_model::JointModelGroup* jmg,
1409 if (display_robot_msg.highlight_links.size() == 0)
1414 const std::vector<const moveit::core::LinkModel*>& link_names =
1415 robot_state.getRobotModel()->getLinkModelsWithCollisionGeometry();
1416 display_robot_msg.highlight_links.resize(link_names.size());
1419 const std_msgs::ColorRGBA& color_rgba =
getColor(color);
1422 for (std::size_t i = 0; i < link_names.size(); ++i)
1424 display_robot_msg.highlight_links[i].id = link_names[i]->getName();
1425 display_robot_msg.highlight_links[i].color = color_rgba;
1446 robot_state::robotStateToRobotStateMsg(robot_state, display_robot_msg.state);
1459 static const std::string VJOINT_NAME =
"virtual_joint";
1465 Eigen::Affine3d offset;
1477 const std::vector<const moveit::core::JointModel*>& joints =
robot_model_->getActiveJointModels();
1480 for (std::size_t i = 0; i < joints.size(); ++i)
1483 if (joints[i]->getVariableCount() > 1)
1490 double current_value = robot_state->getVariablePosition(joints[i]->
getName());
1493 bool out_of_bounds = !robot_state->satisfiesBounds(joints[i]);
1500 std::cout <<
" " << std::fixed << std::setprecision(5) << bound.
min_position_ <<
"\t";
1503 double step = delta / 20.0;
1505 bool marker_shown =
false;
1509 if (!marker_shown && current_value < value)
1512 marker_shown =
true;
1518 std::cout <<
" \t" << std::fixed << std::setprecision(5) << bound.
max_position_ <<
" \t" << joints[i]->getName()
1519 <<
" current: " << std::fixed << std::setprecision(5) << current_value << std::endl;
1546 static const std::string VJOINT_NAME =
"virtual_joint";
1549 if (!robot_state.
getRobotModel()->hasJointModel(VJOINT_NAME))
1552 const std::vector<std::string>& names = robot_state.
getRobotModel()->getJointModelNames();
1560 if (!robot_state.
getRobotModel()->getJointModel(VJOINT_NAME)->hasVariable(VJOINT_NAME +
"/trans_x"))
1564 <<
"' do not exist. Try making this vjoint " 1567 const std::vector<std::string>& var_names =
1568 robot_state.
getRobotModel()->getJointModel(VJOINT_NAME)->getVariableNames();
1569 std::copy(var_names.begin(), var_names.end(), std::ostream_iterator<std::string>(std::cout,
"\n"));
1578 static const std::string VJOINT_NAME =
"virtual_joint";
1583 ROS_WARN_STREAM_NAMED(
"moveit_visual_tools",
"Unable to apply virtual joint transform, hideRobot() functionality " 1594 Eigen::Quaterniond q(offset.rotation());
#define ROS_INFO_NAMED(name,...)
#define MOVEIT_CONSOLE_COLOR_RESET
#define ROS_DEBUG_STREAM_NAMED(name, args)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_ERROR_STREAM_NAMED(name, args)
#define ROS_WARN_NAMED(name,...)
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void getCollisionMarkersFromContacts(visualization_msgs::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con, const std_msgs::ColorRGBA &color, const ros::Duration &lifetime, const double radius=0.035)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
const std::string & getName() const
std::string getName(void *handle)
#define ROS_INFO_STREAM_NAMED(name, args)
std::size_t contact_count
void getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory &trajectory) const
#define ROS_DEBUG_NAMED(name,...)
#define ROS_FATAL_STREAM_NAMED(name, args)
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
void checkCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define MOVEIT_CONSOLE_COLOR_RED
const std::string & getPlanningFrame() const
const RobotModelConstPtr & getRobotModel() const
const robot_state::RobotState & getWayPoint(std::size_t index) const
std::size_t getWayPointCount() const
std::size_t max_contacts_per_pair
bool constructMsgFromShape(const Shape *shape, ShapeMsg &shape_msg)
Mesh * createMeshFromResource(const std::string &resource)
std::string getTopic() const
void setVariablePosition(const std::string &variable, double value)
ROSCPP_DECL void spinOnce()
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
#define ROS_WARN_STREAM_NAMED(name, args)