!

Note: This tutorial assumes that you have completed the previous tutorials: http://wiki.ros.org/descartes/Tutorials/Getting%20Started%20with%20Descartes.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Robot Welding With Descartes

Description: Through a robot welding example the tutorial explains how to visualize trajectory points, add collision objects to the planning scene and shows why you should use enough trajectory points for a path.

Keywords: Descartes, descartes, path planner, MoveIt planning scene, rviz Marker

Tutorial Level: INTERMEDIATE

Overview

In this tutorial, we start with the code from the previous tutorial and gradually add extra functionality and use a different robot.

Installation

To install the code necessary to run this tutorial, we first need to create a workspace. In this example we call the workspace catkin_ws but you can call it however you want. Open a command terminal and enter the following commands to create the workspace:

mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
catkin_init_workspace

While still in the ~/catkin_ws/src folder, run the following commands to install the necessary files:

git clone https://github.com/JeroenDM/descartes.git
git clone https://github.com/ros-industrial/kuka_experimental.git
git clone https://github.com/JeroenDM/descartes_tutorials.git

The first command installs a custom version of the Descartes package. This custom has an extra necessary commit to enable collision detection. This functionality is not yet correctly implemented in the most recent indigo version of Descartes. The commit can be found here: https://github.com/ros-industrial-consortium/descartes/pull/187/commits/eb394d5af12c207b8bc9b0952b6e78ad04f6119b

If you do not install this custom version, and instead install the current Indigo version of Descartes, the collision detection will not work. (This has to do with the MoveIt! planning scene not being updated correctly.)

The second command installs a package from which we will use the robot model. The third command installs the necessary tutorial files.

We now need to check and update the dependencies. First go back to the root folder of the workspace, then update the dependencies:

cd ~/catkin_ws
rosdep install -r -y --from-paths src --ignore-src

Finally, while still in the root folder, build the workspace:

catkin_make

First Run

To be able to run the tutorials, we first need to source the workspace:

cd ~/catkin_ws/devel
source setup.bash

(!) This sourcing needs to be done in every command terminal in which you run any file from this workspace. (!) Because this is a tedious job, it might be interesting to add this line to your .bashrc file:

source /home/*your_username*/catkin_ws/devel/setup.bash

This way, the workspace is automatically sourced whenever you open a command terminal. It is recommended if you plan to run the tutorial multiple times, but not necessary.

After sourcing, we should be able to run several launch files from the catkin_ws/src/descartes_tutorials/descartes_tutorials/launch folder.

First run the kuka_sim.launch file:

roslaunch descartes_tutorials kuka_sim.launch

This should open up RViz, with the robot in its home position. After running the previous command, we can now run the tutorial2.launch file, which will add multiple collision objects, visualize the trajectory, plan it, and finally execute the path it on the simulated robot. With the previous terminal still running, open a new terminal (if necessary, source the workspace!) and enter the following commands:

roslaunch descartes_tutorials tutorial2.launch

The robot should execute the path once.

Source Code

In this part we will briefly describe the code used in the tutorial2.cpp file. We will explain the way that trajectory point visualization was implemented, and how the collision detection can be enabled or disabled. The tutorial2.cpp file consists of the following code:

   1 // Core ros functionality like ros::init and spin
   2 #include <ros/ros.h>
   3 // ROS Trajectory Action server definition
   4 #include <control_msgs/FollowJointTrajectoryAction.h>
   5 // Means by which we communicate with above action-server
   6 #include <actionlib/client/simple_action_client.h>
   7 
   8 // Includes the descartes robot model we will be using
   9 #include <descartes_moveit/ikfast_moveit_state_adapter.h>
  10 // Includes the descartes trajectory type we will be using
  11 #include <descartes_trajectory/axial_symmetric_pt.h>
  12 #include <descartes_trajectory/cart_trajectory_pt.h>
  13 // Includes the planner we will be using
  14 #include <descartes_planner/dense_planner.h>
  15 
  16 #include <tutorial_utilities/path_generation.h>
  17 #include <tutorial_utilities/collision_object_utils.h>
  18 #include <tutorial_utilities/visualization.h>
  19 
  20 // Include the visualisation message that will be used to
  21 // visualize the trajectory points in RViz
  22 #include <visualization_msgs/MarkerArray.h>
  23 
  24 typedef std::vector<descartes_core::TrajectoryPtPtr> TrajectoryVec;
  25 typedef TrajectoryVec::const_iterator TrajectoryIter;
  26 
  27 /**
  28  * Generates an completely defined (zero-tolerance) cartesian point from a pose
  29  */
  30 descartes_core::TrajectoryPtPtr makeCartesianPoint(const Eigen::Affine3d &pose);
  31 /**
  32  * Generates a cartesian point with free rotation about the Z axis of the EFF frame
  33  */
  34 descartes_core::TrajectoryPtPtr makeTolerancedCartesianPoint(const Eigen::Affine3d &pose);
  35 descartes_core::TrajectoryPtPtr makeTolerancedCartesianPoint(Eigen::Affine3d pose,
  36                                                              double rxTolerance, double ryTolerance, double rzTolerance);
  37 
  38 /**
  39  * Translates a descartes trajectory to a ROS joint trajectory
  40  */
  41 trajectory_msgs::JointTrajectory
  42 toROSJointTrajectory(const TrajectoryVec &trajectory, const descartes_core::RobotModel &model,
  43                      const std::vector<std::string> &joint_names, double time_delay);
  44 
  45 /**
  46  * Sends a ROS trajectory to the robot controller
  47  */
  48 bool executeTrajectory(const trajectory_msgs::JointTrajectory &trajectory);
  49 
  50 /**
  51  * Waits for a subscriber to subscribe to a publisher
  52  */
  53 bool waitForSubscribers(ros::Publisher &pub, ros::Duration timeout);
  54 
  55 /**
  56  * Add the welding object (l-profile) to the planning scene.
  57  * This is put in a function to keep the tutorial more readable.
  58  */
  59 void addWeldingObject(moveit_msgs::PlanningScene &planningScene);
  60 
  61 /**
  62  * Add the welding table to the planning scene.
  63  * This is put in a function to keep the tutorial more readable.
  64  */
  65 void addTable(moveit_msgs::PlanningScene &planningScene);
  66 
  67 /**********************
  68   ** MAIN LOOP
  69 **********************/
  70 int main(int argc, char **argv)
  71 {
  72   // Initialize ROS
  73   ros::init(argc, argv, "descartes_tutorial");
  74   ros::NodeHandle nh;
  75 
  76   // Required for communication with moveit components
  77   ros::AsyncSpinner spinner(1);
  78   spinner.start();
  79 
  80   ros::Rate loop_rate(10);
  81 
  82   // 0. Add objects to planning scene
  83   moveit_msgs::PlanningScene planning_scene;
  84 
  85   addTable(planning_scene);
  86   addWeldingObject(planning_scene);
  87 
  88   ros::Publisher scene_diff_publisher;
  89   scene_diff_publisher = nh.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
  90 
  91   planning_scene.is_diff = true;
  92 
  93   ROS_INFO("Waiting for planning_scene subscriber.");
  94   if (waitForSubscribers(scene_diff_publisher, ros::Duration(2.0)))
  95   {
  96     scene_diff_publisher.publish(planning_scene);
  97     ros::spinOnce();
  98     loop_rate.sleep();
  99     ROS_INFO("Object added to the world.");
 100   }
 101   else
 102   {
 103     ROS_ERROR("No subscribers connected, collision object not added");
 104   }
 105 
 106   // 1. Define sequence of points
 107   double x, y, z, rx, ry, rz;
 108   x = 2.0 - 0.025;
 109   y = 0.0;
 110   z = 0.008 + 0.025;
 111   rx = 0.0;
 112   ry = (M_PI / 2) + M_PI / 4;
 113   rz = 0.0;
 114   TrajectoryVec points;
 115   int N_points = 9;
 116 
 117   std::vector<Eigen::Affine3d> poses;
 118   Eigen::Affine3d startPose;
 119   Eigen::Affine3d endPose;
 120   startPose = descartes_core::utils::toFrame(x, y, z, rx, ry, rz, descartes_core::utils::EulerConventions::XYZ);
 121   endPose = descartes_core::utils::toFrame(x, y + 0.4, z, rx, ry, rz, descartes_core::utils::EulerConventions::XYZ);
 122   poses = tutorial_utilities::line(startPose, endPose, N_points);
 123 
 124   for (unsigned int i = 0; i < N_points; ++i)
 125   {
 126     descartes_core::TrajectoryPtPtr pt = makeTolerancedCartesianPoint(poses[i], 0.0, 0.4, M_PI);
 127     points.push_back(pt);
 128   }
 129 
 130   // Visualize the trajectory points in RViz
 131   // Transform the generated poses into a markerArray message that can be visualized by RViz
 132   visualization_msgs::MarkerArray ma;
 133   ma = tutorial_utilities::createMarkerArray(poses);
 134   // Start the publisher for the Rviz Markers
 135   ros::Publisher vis_pub = nh.advertise<visualization_msgs::MarkerArray>("visualization_marker_array", 1);
 136 
 137   // Wait for subscriber and publish the markerArray once the subscriber is found.
 138   ROS_INFO("Waiting for marker subscribers.");
 139   if (waitForSubscribers(vis_pub, ros::Duration(2.0)))
 140   {
 141     ROS_INFO("Subscriber found, publishing markers.");
 142     vis_pub.publish(ma);
 143     ros::spinOnce();
 144     loop_rate.sleep();
 145   }
 146   else
 147   {
 148     ROS_ERROR("No subscribers connected, markers not published");
 149   }
 150 
 151   // 2. Create a robot model and initialize it
 152   descartes_core::RobotModelPtr model(new descartes_moveit::IkFastMoveitStateAdapter);
 153 
 154   //Enable collision checking
 155   model->setCheckCollisions(true);
 156 
 157   // Name of description on parameter server. Typically just "robot_description".
 158   const std::string robot_description = "robot_description";
 159 
 160   // name of the kinematic group you defined when running MoveitSetupAssistant
 161   const std::string group_name = "manipulator";
 162 
 163   // Name of frame in which you are expressing poses. Typically "world_frame" or "base_link".
 164   const std::string world_frame = "base_link";
 165 
 166   // tool center point frame (name of link associated with tool)
 167   // this is also updated in the launch file of the robot
 168   const std::string tcp_frame = "tool_tip";
 169 
 170   if (!model->initialize(robot_description, group_name, world_frame, tcp_frame))
 171   {
 172     ROS_INFO("Could not initialize robot model");
 173     return -1;
 174   }
 175 
 176   // 3. Create a planner and initialize it with our robot model
 177   descartes_planner::DensePlanner planner;
 178   planner.initialize(model);
 179 
 180   // 4. Feed the trajectory to the planner
 181   if (!planner.planPath(points))
 182   {
 183     ROS_ERROR("Could not solve for a valid path");
 184     return -2;
 185   }
 186 
 187   TrajectoryVec result;
 188   if (!planner.getPath(result))
 189   {
 190     ROS_ERROR("Could not retrieve path");
 191     return -3;
 192   }
 193 
 194   // 5. Translate the result into a type that ROS understands
 195   // Get Joint Names
 196   std::vector<std::string> names;
 197   nh.getParam("controller_joint_names", names);
 198   // Generate a ROS joint trajectory with the result path, robot model, given joint names,
 199   // a certain time delta between each trajectory point
 200   trajectory_msgs::JointTrajectory joint_solution = toROSJointTrajectory(result, *model, names, 1.0);
 201 
 202   // 6. Send the ROS trajectory to the robot for execution
 203   if (!executeTrajectory(joint_solution))
 204   {
 205     ROS_ERROR("Could not execute trajectory!");
 206     return -4;
 207   }
 208 
 209   // Wait till user kills the process (Control-C)
 210   ROS_INFO("Done!");
 211   return 0;
 212 }
 213 
 214 descartes_core::TrajectoryPtPtr makeCartesianPoint(const Eigen::Affine3d &pose)
 215 {
 216   using namespace descartes_core;
 217   using namespace descartes_trajectory;
 218 
 219   return TrajectoryPtPtr(new CartTrajectoryPt(TolerancedFrame(pose)));
 220 }
 221 
 222 descartes_core::TrajectoryPtPtr makeTolerancedCartesianPoint(const Eigen::Affine3d &pose)
 223 {
 224   using namespace descartes_core;
 225   using namespace descartes_trajectory;
 226   return TrajectoryPtPtr(new AxialSymmetricPt(pose, M_PI / 2.0 - 0.0001, AxialSymmetricPt::Z_AXIS));
 227 }
 228 
 229 descartes_core::TrajectoryPtPtr makeTolerancedCartesianPoint(Eigen::Affine3d pose,
 230                                                              double rxTolerance, double ryTolerance, double rzTolerance)
 231 {
 232   using namespace descartes_core;
 233   using namespace descartes_trajectory;
 234 
 235   double rotStepSize = 0.1; //M_PI/180;
 236 
 237   Eigen::Vector3d translations;
 238   translations = pose.translation();
 239   Eigen::Vector3d eulerXYZ;
 240   eulerXYZ = pose.rotation().eulerAngles(0, 1, 2);
 241 
 242   PositionTolerance p;
 243   p = ToleranceBase::zeroTolerance<PositionTolerance>(translations(0), translations(1), translations(2));
 244   OrientationTolerance o;
 245   o = ToleranceBase::createSymmetric<OrientationTolerance>(eulerXYZ(0), eulerXYZ(1), eulerXYZ(2), rxTolerance, ryTolerance, rzTolerance);
 246   return TrajectoryPtPtr(new CartTrajectoryPt(TolerancedFrame(pose, p, o), 0.0, rotStepSize));
 247 }
 248 
 249 trajectory_msgs::JointTrajectory
 250 toROSJointTrajectory(const TrajectoryVec &trajectory,
 251                      const descartes_core::RobotModel &model,
 252                      const std::vector<std::string> &joint_names,
 253                      double time_delay)
 254 {
 255   // Fill out information about our trajectory
 256   trajectory_msgs::JointTrajectory result;
 257   result.header.stamp = ros::Time::now();
 258   result.header.frame_id = "world_frame";
 259   result.joint_names = joint_names;
 260 
 261   // For keeping track of time-so-far in the trajectory
 262   double time_offset = 0.0;
 263   // Loop through the trajectory
 264   for (TrajectoryIter it = trajectory.begin(); it != trajectory.end(); ++it)
 265   {
 266     // Find nominal joint solution at this point
 267     std::vector<double> joints;
 268     it->get()->getNominalJointPose(std::vector<double>(), model, joints);
 269 
 270     // Fill out a ROS trajectory point
 271     trajectory_msgs::JointTrajectoryPoint pt;
 272     pt.positions = joints;
 273     // velocity, acceleration, and effort are given dummy values
 274     // we'll let the controller figure them out
 275     pt.velocities.resize(joints.size(), 0.0);
 276     pt.accelerations.resize(joints.size(), 0.0);
 277     pt.effort.resize(joints.size(), 0.0);
 278     // set the time into the trajectory
 279     pt.time_from_start = ros::Duration(time_offset);
 280     // increment time
 281     time_offset += time_delay;
 282 
 283     result.points.push_back(pt);
 284   }
 285 
 286   return result;
 287 }
 288 
 289 bool executeTrajectory(const trajectory_msgs::JointTrajectory &trajectory)
 290 {
 291   // Create a Follow Joint Trajectory Action Client
 292   actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> ac("joint_trajectory_action", true);
 293   if (!ac.waitForServer(ros::Duration(2.0)))
 294   {
 295     ROS_ERROR("Could not connect to action server");
 296     return false;
 297   }
 298 
 299   control_msgs::FollowJointTrajectoryGoal goal;
 300   goal.trajectory = trajectory;
 301   goal.goal_time_tolerance = ros::Duration(1.0);
 302 
 303   ac.sendGoal(goal);
 304 
 305   if (ac.waitForResult(goal.trajectory.points[goal.trajectory.points.size() - 1].time_from_start + ros::Duration(5)))
 306   {
 307     ROS_INFO("Action server reported successful execution");
 308     return true;
 309   }
 310   else
 311   {
 312     ROS_WARN("Action server could not execute trajectory");
 313     return false;
 314   }
 315 }
 316 
 317 bool waitForSubscribers(ros::Publisher &pub, ros::Duration timeout)
 318 {
 319   if (pub.getNumSubscribers() > 0)
 320     return true;
 321   ros::Time start = ros::Time::now();
 322   ros::Rate waitTime(0.5);
 323   while (ros::Time::now() - start < timeout)
 324   {
 325     waitTime.sleep();
 326     if (pub.getNumSubscribers() > 0)
 327       break;
 328   }
 329   return pub.getNumSubscribers() > 0;
 330 }
 331 
 332 void addWeldingObject(moveit_msgs::PlanningScene &scene)
 333 {
 334   Eigen::Vector3d scale(0.001, 0.001, 0.001);
 335   Eigen::Affine3d pose;
 336   pose = descartes_core::utils::toFrame(2.0, 0.0, 0.012, 0.0, 0.0, M_PI_2, descartes_core::utils::EulerConventions::XYZ);
 337   //ros::package::getPath('descartes_tutorials')
 338   scene.world.collision_objects.push_back(
 339       tutorial_utilities::makeCollisionObject("package://descartes_tutorials/meshes/profile.stl", scale, "Profile", pose));
 340   scene.object_colors.push_back(tutorial_utilities::makeObjectColor("Profile", 0.5, 0.5, 0.5, 1.0));
 341 }
 342 
 343 void addTable(moveit_msgs::PlanningScene &scene)
 344 {
 345   Eigen::Vector3d scale(1.0, 1.0, 1.0);
 346   Eigen::Affine3d pose;
 347   pose = descartes_core::utils::toFrame(1.5, -0.6, 0.0, 0.0, 0.0, 0.0, descartes_core::utils::EulerConventions::XYZ);
 348   scene.world.collision_objects.push_back(
 349       tutorial_utilities::makeCollisionObject("package://descartes_tutorials/meshes/table.stl", scale, "Table", pose));
 350   scene.object_colors.push_back(tutorial_utilities::makeObjectColor("Table", 0.2, 0.2, 0.2, 1.0));
 351 }

Discussion

Compared to the previous tutorial, a few include lines have been added:

   1 #include <tutorial_utilities/path_generation.h>
   2 #include <tutorial_utilities/collision_object_utils.h>
   3 #include <tutorial_utilities/visualization.h>
   4 
   5 // Include the visualisation message that will be used to
   6 // visualize the trajectory points in RViz
   7 #include <visualization_msgs/MarkerArray.h>
   8 

The first three lines include different libraries we will be using in the tutorial. To keep the main program more readable, it was decided to put many help-functions in a separate package. The three different files included here contain functions helping with the definition of trajectory points, defining collision objects, and visualizing trajectory points.

The final include is necessary to send the necessary Marker Array message to RViz, which is used to visualize things in RViz.

Then a couple of function declarations follow. The function definitions can be found at the end of the program. Compared to the previous tutorial, a few extra functions have been added:

   1 descartes_core::TrajectoryPtPtr makeTolerancedCartesianPoint(Eigen::Affine3d pose,
   2                        double rxTolerance, double ryTolerance, double rzTolerance);
   3 
   4 /**
   5  * Waits for a subscriber to subscribe to a publisher
   6  */
   7 bool waitForSubscribers(ros::Publisher &pub, ros::Duration timeout);
   8 
   9 /**
  10  * Add the welding object (l-profile) to the planning scene.
  11  * This is put in a function to keep the tutorial more readable.
  12  */
  13 void addWeldingObject(moveit_msgs::PlanningScene &planningScene);
  14 
  15 /**
  16  * Add the welding table to the planning scene.
  17  * This is put in a function to keep the tutorial more readable.
  18  */
  19 void addTable(moveit_msgs::PlanningScene &planningScene);

The first function is a second declaration of the makeTolerancedCartesianPoint() function. This declaration takes more parameters, allowing the user to define tolerances around multiple axes.

The waitForSubscribers() function takes a publisher and a time in seconds. The function waits for at least the defined time duration for a subscriber to subscribe to the given publisher. This can help to make sure that messages arrive at the desired destination.

The addWeldingObject() and addTable() functions both help to add collision objects to the simulation.

We then enter the main() functions. The first new part is the adding of collision objects:

   1 // 0. Add objects to planning scene
   2   moveit_msgs::PlanningScene planning_scene;
   3 
   4   addTable(planning_scene);
   5   addWeldingObject(planning_scene);
   6 
   7   ros::Publisher scene_diff_publisher;
   8   scene_diff_publisher = nh.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
   9 
  10   planning_scene.is_diff = true;
  11 
  12   ROS_INFO("Waiting for planning_scene subscriber.");
  13   if (waitForSubscribers(scene_diff_publisher, ros::Duration(2.0)))
  14   {
  15     scene_diff_publisher.publish(planning_scene);
  16     ros::spinOnce();
  17     loop_rate.sleep();
  18     ROS_INFO("Object added to the world.");
  19   }
  20   else
  21   {
  22     ROS_ERROR("No subscribers connected, collision object not added");
  23   }

In this section of code we declare a new planning scene, and then add both the table and the work piece to the scene, using the help functions. The planning_scene is then published on the "planning_scene" topic. Using the waitForSubscriber() function we wait for the planning_scene to be read, for a maximum of 2 seconds. When the new planning scene is read, the objects should appear in RViz.

As an example we will briefly take a look at the addTable() function definition at the end of the document:

   1 void addTable(moveit_msgs::PlanningScene &scene)
   2 {
   3   Eigen::Vector3d scale(1.0, 1.0, 1.0);
   4   Eigen::Affine3d pose;
   5   pose = descartes_core::utils::toFrame(1.5, -0.6, 0.0, 0.0, 0.0, 0.0, descartes_core::utils::EulerConventions::XYZ);
   6   scene.world.collision_objects.push_back(
   7       tutorial_utilities::makeCollisionObject("package://descartes_tutorials/meshes/table.stl", scale, "Table", pose));
   8   scene.object_colors.push_back(tutorial_utilities::makeObjectColor("Table", 0.2, 0.2, 0.2, 1.0));
   9 }

First the scale of the object is defined using a vector. Because the mesh we will be using here is already scaled correctly, we set this scale to 1. Next we define a pose, using Cartesian XYZ translations and XYZ Euler-rotations, using the toFrame() function. This pose will define the origin of the collision object, with it you can control the position and the rotation of the object.

We then actually create the object using the makeCollisionObject() from the tutorial utilities. This object is then added to the list of objects in the planning scene's world with scene.world.collision_objects.push_back(). The final lines are used to give the collision object a non-standard color.

We then move on to the definition of the trajectory points, together with their visualization:

   1 // 1. Define sequence of points
   2   double x, y, z, rx, ry, rz;
   3   x = 2.0 - 0.025;
   4   y = 0.0;
   5   z = 0.008 + 0.025;
   6   rx = 0.0;
   7   ry = (M_PI / 2) + M_PI / 4;
   8   rz = 0.0;
   9   TrajectoryVec points;
  10   int N_points = 9;
  11 
  12   std::vector<Eigen::Affine3d> poses;
  13   Eigen::Affine3d startPose;
  14   Eigen::Affine3d endPose;
  15   startPose = descartes_core::utils::toFrame(x, y, z, rx, ry, rz, descartes_core::utils::EulerConventions::XYZ);
  16   endPose = descartes_core::utils::toFrame(x, y + 0.4, z, rx, ry, rz, descartes_core::utils::EulerConventions::XYZ);
  17   poses = tutorial_utilities::line(startPose, endPose, N_points);
  18 
  19   for (unsigned int i = 0; i < N_points; ++i)
  20   {
  21     descartes_core::TrajectoryPtPtr pt = makeTolerancedCartesianPoint(poses[i], 0.0, 0.4, M_PI);
  22     points.push_back(pt);
  23   }

In this section of code we start of with the declaration of a series of double variables, used to define the first trajectory point. We define the XYZ position, and the XYZ Euler-rotations for the frame. We then use these variables to define both the starting pose and the end pose of the movement. This is done using the toFrame() function. Now that we have both the start and the end frame, we use the tutorial_utilities::line() function to create more poses following the straight line in space between the position of the start pose and the end pose. In this example 9 frames are generated.

In the for loop, we then use each of these generated poses, to generate a toleranced cartesian trajectory point. The trajectory points are added to the points list. To generate the trajectory points, we use makeTolerancedCartesianPoint(poses[i], 0.0, 0.4, M_PI). The three numbers following the pose are the allowed rotational tolerance sizes around the X, Y, and Z axis. In this case we allow a symmetric rotational tolerance of 0.4 radians around the Y axis, and a symmetric rotational tolerance of PI radians around the Z axis.

We then move on to the visualization of the trajectory points generated in the previous piece of code:

   1   // Visualize the trajectory points in RViz
   2   // Transform the generated poses into a markerArray message that can be visualized by RViz
   3   visualization_msgs::MarkerArray ma;
   4   ma = tutorial_utilities::createMarkerArray(poses);
   5   // Start the publisher for the Rviz Markers
   6   ros::Publisher vis_pub = nh.advertise<visualization_msgs::MarkerArray>("visualization_marker_array", 1);
   7 
   8   // Wait for subscriber and publish the markerArray once the subscriber is found.
   9   ROS_INFO("Waiting for marker subscribers.");
  10   if (waitForSubscribers(vis_pub, ros::Duration(2.0)))
  11   {
  12     ROS_INFO("Subscriber found, publishing markers.");
  13     vis_pub.publish(ma);
  14     ros::spinOnce();
  15     loop_rate.sleep();
  16   }
  17   else
  18   {
  19     ROS_ERROR("No subscribers connected, markers not published");
  20   }

Using the createMarkerArray(poses) function, we transform the list of poses into a so-called Marker Array. As its name explains, the marker array contains an array of markers, that can be sent to RViz, on a certain topic that it listens to. RViz will then visualize every marker in the marker array. The marker array is then published, using the same method as in the publishing of the planning scene.

The third step is creating a robot model and initializing it correctly. In this tutorial there are two differences compared to the previous one:

   1 // 2. Create a robot model and initialize it
   2   descartes_core::RobotModelPtr model(new descartes_moveit::IkFastMoveitStateAdapter);
   3 
   4   //Enable collision checking
   5   model->setCheckCollisions(true);

The first line, where the robot model is created, a new descartes_moveit::IkFastMoveitStateAdapter is created. We need to use this specific object, because in this case we will use the IKfast solver to calculate the inverse kinematic solutions. This is different than the KDL solver, which is used in the previous tutorial. The IKfast solver seems to be faster, generates more solutions, and is more accurate.

After the model is declared, we turn on the collision detection.

The remaining code is explained in the first tutorial.

Wiki: descartes/Tutorials/Robot Welding With Descartes (last edited 2017-06-21 10:05:39 by BartMoyaers)