moveit_visual_tools_demo.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, University of Colorado, Boulder
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Univ of CO, Boulder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Dave Coleman
00036    Desc:   Demo implementation of moveit_visual_tools
00037            To use, add a Rviz Marker Display subscribed to topic /moveit_visual_tools
00038 */
00039 
00040 // ROS
00041 #include <ros/ros.h>
00042 
00043 // For visualizing things in rviz
00044 #include <moveit_visual_tools/moveit_visual_tools.h>
00045 
00046 // MoveIt
00047 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00048 
00049 // C++
00050 #include <string>
00051 
00052 namespace rvt = rviz_visual_tools;
00053 
00054 namespace moveit_visual_tools
00055 {
00056 static const std::string PLANNING_GROUP_NAME = "arm";  // RRBot Specific
00057 static const std::string THIS_PACKAGE = "moveit_visual_tools";
00058 
00059 class VisualToolsDemo
00060 {
00061 public:
00065   VisualToolsDemo()
00066   {
00067     visual_tools_.reset(new moveit_visual_tools::MoveItVisualTools("world", "/moveit_visual_tools"));
00068     visual_tools_->loadPlanningSceneMonitor();
00069     visual_tools_->loadMarkerPub(true);
00070     visual_tools_->loadRobotStatePub("display_robot_state");
00071     visual_tools_->setManualSceneUpdating();
00072 
00073     robot_state_ = visual_tools_->getSharedRobotState();
00074     jmg_ = robot_state_->getJointModelGroup(PLANNING_GROUP_NAME);
00075 
00076     // Allow time to publish messages
00077     ros::spinOnce();
00078     ros::Duration(0.1).sleep();
00079 
00080     // Clear collision objects and markers
00081     visual_tools_->deleteAllMarkers();
00082     visual_tools_->removeAllCollisionObjects();
00083     visual_tools_->triggerPlanningSceneUpdate();
00084     ros::Duration(0.1).sleep();
00085 
00086     // Show message
00087     Eigen::Affine3d text_pose = Eigen::Affine3d::Identity();
00088     text_pose.translation().z() = 4;
00089     visual_tools_->publishText(text_pose, "MoveIt! Visual Tools", rvt::WHITE, rvt::XLARGE, /*static_id*/ false);
00090 
00091     runRobotStateTests();
00092 
00093     runDeskTest();
00094 
00095     runCollisionObjectTests();
00096   }
00097 
00098   void publishLabelHelper(const Eigen::Affine3d& pose, const std::string& label)
00099   {
00100     Eigen::Affine3d pose_copy = pose;
00101     pose_copy.translation().x() -= 0.2;
00102     visual_tools_->publishText(pose_copy, label, rvt::WHITE, rvt::LARGE, false);
00103   }
00104 
00105   void runRobotStateTests()
00106   {
00107     // Show 5 random robot states
00108     for (std::size_t i = 0; i < 5; ++i)
00109     {
00110       robot_state_->setToRandomPositions(jmg_);
00111       visual_tools_->publishRobotState(robot_state_, rvt::DEFAULT);
00112       ros::Duration(0.1).sleep();
00113     }
00114 
00115     // Show 5 robot state in different colors
00116     for (std::size_t i = 0; i < 5; ++i)
00117     {
00118       robot_state_->setToRandomPositions(jmg_);
00119       visual_tools_->publishRobotState(robot_state_, visual_tools_->getRandColor());
00120       ros::Duration(0.1).sleep();
00121     }
00122 
00123     // Hide the robot
00124     visual_tools_->hideRobot();
00125     ros::Duration(0.1).sleep();
00126 
00127     // Show the robot
00128     visual_tools_->publishRobotState(robot_state_, rvt::DEFAULT);
00129     ros::Duration(0.1).sleep();
00130   }
00131 
00132   void runDeskTest()
00133   {
00134     double common_angle = M_PI * 1.1;
00135     double x_offset = -3.0;
00136 
00137     // --------------------------------------------------------------------
00138     ROS_INFO_STREAM_NAMED("visual_tools", "Moving robot");
00139     Eigen::Affine3d robot_pose = Eigen::Affine3d::Identity();
00140     robot_pose = robot_pose * Eigen::AngleAxisd(common_angle, Eigen::Vector3d::UnitZ());
00141     robot_pose.translation().x() = x_offset;
00142     visual_tools_->applyVirtualJointTransform(*robot_state_, robot_pose);
00143     visual_tools_->publishRobotState(robot_state_, rvt::DEFAULT);
00144 
00145     // --------------------------------------------------------------------
00146     ROS_INFO_STREAM_NAMED("visual_tools", "Publishing Collision Floor");
00147     visual_tools_->publishCollisionFloor(-0.5, "Floor", rvt::GREY);
00148 
00149     // --------------------------------------------------------------------
00150     ROS_INFO_STREAM_NAMED("visual_tools", "Publishing Collision Wall");
00151     double wall_x = x_offset - 1.0;
00152     double wall_y = -1.0;
00153     double wall_width = 6.0;
00154     double wall_height = 4;
00155     visual_tools_->publishCollisionWall(wall_x, wall_y, common_angle, wall_width, wall_height, "Wall", rvt::GREEN);
00156 
00157     // --------------------------------------------------------------------
00158     ROS_INFO_STREAM_NAMED("visual_tools", "Publishing Collision Table");
00159     double table_x = x_offset + 1.0;
00160     double table_y = 0;
00161     double table_width = 3;
00162     double table_height = 1;
00163     double table_depth = 1;
00164     visual_tools_->publishCollisionTable(table_x, table_y, common_angle, table_width, table_height, table_depth,
00165                                          "Table", rvt::BLUE);
00166 
00167     // Send ROS messages
00168     visual_tools_->triggerPlanningSceneUpdate();
00169 
00170     // Show 5 random robot states
00171     for (std::size_t i = 0; i < 5; ++i)
00172     {
00173       robot_state_->setToRandomPositions(jmg_);
00174       visual_tools_->publishRobotState(robot_state_, rvt::DEFAULT);
00175       ros::Duration(0.1).sleep();
00176     }
00177   }
00178 
00179   void runCollisionObjectTests()
00180   {
00181     // Create pose
00182     Eigen::Affine3d pose1 = Eigen::Affine3d::Identity();
00183     Eigen::Affine3d pose2 = Eigen::Affine3d::Identity();
00184     // geometry_msgs::Pose pose1;
00185     // geometry_msgs::Pose pose2;
00186 
00187     double space_between_rows = 0.2;
00188     double y = 0;
00189     double step;
00190 
00191     // --------------------------------------------------------------------
00192     ROS_INFO_STREAM_NAMED("visual_tools", "Publishing Collision Mesh");
00193     std::string file_path = "file://" + ros::package::getPath(THIS_PACKAGE);
00194     if (file_path == "file://")
00195       ROS_FATAL_STREAM_NAMED("visual_tools", "Unable to get " << THIS_PACKAGE << " package path ");
00196     file_path.append("/resources/demo_mesh.stl");
00197     step = 0.4;
00198     for (double i = 0; i <= 1.0; i += 0.1)
00199     {
00200       visual_tools_->publishCollisionMesh(visual_tools_->convertPose(pose1),
00201                                           "Mesh_" + boost::lexical_cast<std::string>(i), file_path,
00202                                           visual_tools_->getRandColor());
00203       if (!i)
00204         publishLabelHelper(pose1, "Mesh");
00205       pose1.translation().x() += step;
00206     }
00207 
00208     // --------------------------------------------------------------------
00209     ROS_INFO_STREAM_NAMED("visual_tools", "Publishing Collision Block");
00210     pose1 = Eigen::Affine3d::Identity();
00211     y += space_between_rows * 2.0;
00212     pose1.translation().y() = y;
00213     for (double i = 0; i <= 1.0; i += 0.1)
00214     {
00215       double size = 0.1 * (i + 0.5);
00216       visual_tools_->publishCollisionBlock(visual_tools_->convertPose(pose1),
00217                                            "Block_" + boost::lexical_cast<std::string>(i), size,
00218                                            visual_tools_->getRandColor());
00219 
00220       if (!i)
00221         publishLabelHelper(pose1, "Block");
00222       pose1.translation().x() += step;
00223     }
00224 
00225     // --------------------------------------------------------------------
00226     ROS_INFO_STREAM_NAMED("visual_tools", "Publishing Collision Rectanglular Cuboid");
00227     double cuboid_min_size = 0.05;
00228     double cuboid_max_size = 0.2;
00229     pose1 = Eigen::Affine3d::Identity();
00230     pose2 = Eigen::Affine3d::Identity();
00231     y += space_between_rows * 2.0;
00232     pose1.translation().y() = y;
00233     pose2.translation().y() = y;
00234     for (double i = 0; i <= 1.0; i += 0.1)
00235     {
00236       pose2 = pose1;
00237       pose2.translation().x() += i * cuboid_max_size + cuboid_min_size;
00238       pose2.translation().y() += (i * cuboid_max_size + cuboid_min_size) / 2.0;
00239       pose2.translation().z() += i * cuboid_max_size + cuboid_min_size;
00240       visual_tools_->publishCollisionCuboid(pose1.translation(), pose2.translation(),
00241                                             "Rectangle_" + boost::lexical_cast<std::string>(i),
00242                                             visual_tools_->getRandColor());
00243       if (!i)
00244         publishLabelHelper(pose1, "Cuboid");
00245       pose1.translation().x() += step;
00246     }
00247 
00248     // --------------------------------------------------------------------
00249     ROS_INFO_STREAM_NAMED("visual_tools", "Publishing Collision Cylinder");
00250     double cylinder_min_size = 0.01;
00251     double cylinder_max_size = 0.3;
00252     pose1 = Eigen::Affine3d::Identity();
00253     pose2 = Eigen::Affine3d::Identity();
00254     y += space_between_rows * 2.0;
00255     pose1.translation().y() = y;
00256     pose2.translation().y() = y;
00257     for (double i = 0; i <= 1.0; i += 0.1)
00258     {
00259       double radius = 0.1;
00260       pose2 = pose1;
00261       pose2.translation().x() += i * cylinder_max_size + cylinder_min_size;
00262       // pose2.translation().y() += i * cylinder_max_size + cylinder_min_size;
00263       // pose2.translation().z() += i * cylinder_max_size + cylinder_min_size;
00264       visual_tools_->publishCollisionCylinder(pose1.translation(), pose2.translation(),
00265                                               "Cylinder_" + boost::lexical_cast<std::string>(i), radius,
00266                                               visual_tools_->getRandColor());
00267 
00268       if (!i)
00269         publishLabelHelper(pose1, "Cylinder");
00270       pose1.translation().x() += step;
00271 
00272       pose1 = pose1 * Eigen::AngleAxisd(step * 2 * M_PI, Eigen::Vector3d::UnitZ());
00273     }
00274 
00275     // TODO(davetcoleman): publishCollisionGraph
00276     // TODO(davetcoleman): publishContactPoint
00277     // TODO(davetcoleman): trajectory stuff
00278     // TODO(davetcoleman): gripper stuff
00279 
00280     // Send ROS messages
00281     visual_tools_->triggerPlanningSceneUpdate();
00282   }
00283 
00284 private:
00285   // A shared node handle
00286   ros::NodeHandle nh_;
00287 
00288   // For visualizing things in rviz
00289   moveit_visual_tools::MoveItVisualToolsPtr visual_tools_;
00290 
00291   // MoveIt Components
00292   planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
00293 
00294   const moveit::core::JointModelGroup* jmg_;
00295 
00296   moveit::core::RobotStatePtr robot_state_;
00297 };  // end class
00298 
00299 }  // namespace moveit_visual_tools
00300 
00301 int main(int argc, char** argv)
00302 {
00303   ros::init(argc, argv, "visual_tools_demo");
00304   ROS_INFO_STREAM("Visual Tools Demo");
00305 
00306   // Allow the action server to recieve and send ros messages
00307   ros::AsyncSpinner spinner(1);
00308   spinner.start();
00309 
00310   moveit_visual_tools::VisualToolsDemo demoer;
00311 
00312   ROS_INFO_STREAM("Shutting down.");
00313 
00314   return 0;
00315 }


moveit_visual_tools
Author(s): Dave Coleman
autogenerated on Fri Jun 17 2016 04:11:05