|
| 1 | +Your First C++ MoveIt Project |
| 2 | +============================= |
| 3 | + |
| 4 | +This tutorial will quickly get you writing your first ROS project with MoveIt. |
| 5 | + |
| 6 | +Prerequisites |
| 7 | +------------- |
| 8 | + |
| 9 | +If you haven't already done so, make sure you've completed the steps in :doc:`Getting Started </doc/tutorials/getting_started/getting_started>`. |
| 10 | + |
| 11 | +This tutorial assumes you understand the basics of ROS 2. |
| 12 | +To prepare yourself for this please complete the `Official ROS 2 Tutorials <https://docs.ros.org/en/{DISTRO}/Tutorials.html>`_ up until "Writing a simple publisher and Subscriber (C++)". |
| 13 | + |
| 14 | +Steps |
| 15 | +----- |
| 16 | + |
| 17 | +1 Create a package |
| 18 | +^^^^^^^^^^^^^^^^^^ |
| 19 | + |
| 20 | +Open a terminal and `source your ROS 2 installation <https://docs.ros.org/en/{DISTRO}/Tutorials/Configuring-ROS2-Environment.html>`_ so that ``ros2`` commands will work. |
| 21 | + |
| 22 | +Navigate to your ``ws_moveit2`` directory you created in the :doc:`Getting Started Tutorial </doc/tutorials/getting_started/getting_started>`. |
| 23 | + |
| 24 | +Change directory into the ``src`` directory, as that is where we put our source code. |
| 25 | + |
| 26 | +Create a new package with the ROS 2 command line tools: |
| 27 | + |
| 28 | +.. code-block:: bash |
| 29 | +
|
| 30 | + ros2 pkg create \ |
| 31 | + --build-type ament_cmake \ |
| 32 | + --dependencies moveit_ros_planning_interface rclcpp \ |
| 33 | + --node-name hello_moveit hello_moveit |
| 34 | +
|
| 35 | +The output of this will show that it created some files in a new directory. |
| 36 | + |
| 37 | +Note that we added ``moveit_ros_planning_interface`` and ``rclcpp`` as dependencies. |
| 38 | +This will create the necessary changes in the ``package.xml`` and ``CMakeLists.txt`` files so that we can depend on these two packages. |
| 39 | + |
| 40 | +Open the new source file created for you at ``ws_moveit2/src/hello_moveit/src/hello_moveit.cpp`` in your favorite editor. |
| 41 | + |
| 42 | +2 Create a ROS Node and Executor |
| 43 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 44 | + |
| 45 | +This first block of code is a bit of boilerplate but you should be used to seeing this from the ROS 2 tutorials. |
| 46 | + |
| 47 | +.. code-block:: C++ |
| 48 | + |
| 49 | + #include <memory> |
| 50 | + |
| 51 | + #include <rclcpp/rclcpp.hpp> |
| 52 | + #include <moveit/move_group_interface/move_group_interface.h> |
| 53 | + |
| 54 | + int main(int argc, char * argv[]) |
| 55 | + { |
| 56 | + // Initialize ROS and create the Node |
| 57 | + rclcpp::init(argc, argv); |
| 58 | + auto const node = std::make_shared<rclcpp::Node>( |
| 59 | + "hello_moveit", |
| 60 | + rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true) |
| 61 | + ); |
| 62 | + |
| 63 | + // Create a ROS logger |
| 64 | + auto const logger = rclcpp::get_logger("hello_moveit"); |
| 65 | + |
| 66 | + // Next step goes here |
| 67 | + |
| 68 | + // Shutdown ROS |
| 69 | + rclcpp::shutdown(); |
| 70 | + return 0; |
| 71 | + } |
| 72 | + |
| 73 | +2.1 Build and Run |
| 74 | +~~~~~~~~~~~~~~~~~ |
| 75 | + |
| 76 | +We will build and run the program to see that everything is right before we move on. |
| 77 | + |
| 78 | +Change directory back to the workspace directory ``ws_moveit2`` and run this command: |
| 79 | + |
| 80 | +.. code-block:: bash |
| 81 | +
|
| 82 | + colcon build --mixin debug |
| 83 | +
|
| 84 | +After this succeeds, **open a new terminal**, then source the workspace environment script in that new terminal so that we can run our program. |
| 85 | + |
| 86 | +.. code-block:: bash |
| 87 | +
|
| 88 | + cd ~/ws_moveit2 |
| 89 | + source install/setup.bash |
| 90 | +
|
| 91 | +Run your program and see the output. |
| 92 | + |
| 93 | +.. code-block:: bash |
| 94 | +
|
| 95 | + ros2 run hello_moveit hello_moveit |
| 96 | +
|
| 97 | +The program should run and exit without error. |
| 98 | + |
| 99 | +2.2 Examine the code |
| 100 | +~~~~~~~~~~~~~~~~~~~~ |
| 101 | + |
| 102 | +The headers included at the top are just some standard C++ headers and the header for ROS and MoveIt that we will use later. |
| 103 | + |
| 104 | +After that, we have the normal call to initialize rclcpp, and then we create our Node. |
| 105 | + |
| 106 | +.. code-block:: C++ |
| 107 | + |
| 108 | + auto const node = std::make_shared<rclcpp::Node>( |
| 109 | + "hello_moveit", |
| 110 | + rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true) |
| 111 | + ); |
| 112 | + |
| 113 | +The first argument is a string that ROS will use to make a unique node. |
| 114 | +The second is needed for MoveIt because of how we use ROS Parameters. |
| 115 | + |
| 116 | +Lastly, we have the code to shutdown ROS. |
| 117 | + |
| 118 | +3 Plan and Execute using MoveGroupInterface |
| 119 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 120 | + |
| 121 | +In place of the comment that says "Next step goes here," add this code: |
| 122 | + |
| 123 | +.. code-block:: C++ |
| 124 | + |
| 125 | + // Create the MoveIt MoveGroup Interface |
| 126 | + using moveit::planning_interface::MoveGroupInterface; |
| 127 | + auto move_group_interface = MoveGroupInterface(node, "panda_arm"); |
| 128 | + |
| 129 | + // Set a target Pose |
| 130 | + auto const target_pose = []{ |
| 131 | + geometry_msgs::msg::Pose msg; |
| 132 | + msg.orientation.w = 1.0; |
| 133 | + msg.position.x = 0.28; |
| 134 | + msg.position.y = -0.2; |
| 135 | + msg.position.z = 0.5; |
| 136 | + return msg; |
| 137 | + }(); |
| 138 | + move_group_interface.setPoseTarget(target_pose); |
| 139 | + |
| 140 | + // Create a plan to that target pose |
| 141 | + auto const [success, plan] = [&move_group_interface]{ |
| 142 | + moveit::planning_interface::MoveGroupInterface::Plan msg; |
| 143 | + auto const ok = static_cast<bool>(move_group_interface.plan(msg)); |
| 144 | + return std::make_pair(ok, msg); |
| 145 | + }(); |
| 146 | + |
| 147 | + // Execute the plan |
| 148 | + if(success) { |
| 149 | + move_group_interface.execute(plan); |
| 150 | + } else { |
| 151 | + RCLCPP_ERROR(logger, "Planing failed!"); |
| 152 | + } |
| 153 | + |
| 154 | +3.1 Build and Run |
| 155 | +~~~~~~~~~~~~~~~~~ |
| 156 | + |
| 157 | +Just like before, we need to build the code before we can run it. |
| 158 | + |
| 159 | +In the workspace directory, ``ws_moveit2``, run this command: |
| 160 | + |
| 161 | +.. code-block:: bash |
| 162 | +
|
| 163 | + colcon build --mixin debug |
| 164 | +
|
| 165 | +After this succeeds, we need to re-use the demo launch file from the previous tutorial to start RViz and the MoveGroup node. |
| 166 | +In a separate terminal, source the workspace and then execute this: |
| 167 | + |
| 168 | +.. code-block:: bash |
| 169 | +
|
| 170 | + ros2 launch moveit2_tutorials demo.launch.py |
| 171 | +
|
| 172 | +Then in the ``Displays`` window under ``MotionPlanning/Planning Request``, uncheck the box ``Query Goal State``. |
| 173 | + |
| 174 | +.. image:: rviz_1.png |
| 175 | + :width: 300px |
| 176 | + |
| 177 | +In a third terminal, source the workspace and run your program. |
| 178 | + |
| 179 | +.. code-block:: bash |
| 180 | +
|
| 181 | + ros2 run hello_moveit hello_moveit |
| 182 | +
|
| 183 | +This should cause the robot in RViz to move and end up in this pose: |
| 184 | + |
| 185 | +.. image:: rviz_2.png |
| 186 | + :width: 300px |
| 187 | + |
| 188 | +Note that if you ran the node ``hello_moveit`` without launching the demo launch file first, it will wait for 10 seconds and then print this error and exit. |
| 189 | + |
| 190 | +.. code-block:: bash |
| 191 | +
|
| 192 | + [ERROR] [1644181704.350825487] [hello_moveit]: Could not find parameter robot_description and did not receive robot_description via std_msgs::msg::String subscription within 10.000000 seconds. |
| 193 | +
|
| 194 | +This is because the ``demo.launch.py`` launch is starting the ``MoveGroup`` node that provides the robot description. |
| 195 | +When ``MoveGroupInterface`` is constructed, it looks for a node publishing a topic with the robot description. |
| 196 | +If it fails to find that within 10 seconds, it prints this error and terminates the program. |
| 197 | + |
| 198 | +3.2 Examine the code |
| 199 | +~~~~~~~~~~~~~~~~~~~~ |
| 200 | + |
| 201 | +The first thing we do is create the MoveGroupInterface. This object will be used to interact with move_group, which allows us to plan and execute trajectories. |
| 202 | +Note that this is the only mutable object that we create in this program. |
| 203 | +Another thing to take note of is the second interface to the ``MoveGroupInterface`` object we are creating here: ``"panda_arm"``. |
| 204 | +That is the group of joints as defined in the robot description that we are going to operate on with this ``MoveGroupInterface``. |
| 205 | + |
| 206 | +.. code-block:: C++ |
| 207 | + |
| 208 | + using moveit::planning_interface::MoveGroupInterface; |
| 209 | + auto move_group_interface = MoveGroupInterface(node, "panda_arm"); |
| 210 | + |
| 211 | +Then, we set our target pose and plan. Note that only the target pose is set (via ``setPoseTarget``. The starting pose is implicitly the position published by joint state publisher, which could be changed using the ``MoveGroupInterface::setStartState*`` family of functions (but is not in this tutorial). |
| 212 | + |
| 213 | +One more thing to note about this next section is the use of lambdas for constructing the message type ``target_pose`` and planning. |
| 214 | +This is a pattern you'll find in modern C++ codebases that enables writing in a more declarative style. |
| 215 | +For more information about this pattern there is a couple of links at the end of this tutorial. |
| 216 | + |
| 217 | +.. code-block:: C++ |
| 218 | + |
| 219 | + // Set a target Pose |
| 220 | + auto const target_pose = []{ |
| 221 | + geometry_msgs::msg::Pose msg; |
| 222 | + msg.orientation.w = 1.0; |
| 223 | + msg.position.x = 0.28; |
| 224 | + msg.position.y = -0.2; |
| 225 | + msg.position.z = 0.5; |
| 226 | + return msg; |
| 227 | + }(); |
| 228 | + move_group_interface.setPoseTarget(target_pose); |
| 229 | + |
| 230 | + // Create a plan to that target pose |
| 231 | + auto const [success, plan] = [&move_group_interface]{ |
| 232 | + moveit::planning_interface::MoveGroupInterface::Plan msg; |
| 233 | + auto const ok = static_cast<bool>(move_group_interface.plan(msg)); |
| 234 | + return std::make_pair(ok, msg); |
| 235 | + }(); |
| 236 | + |
| 237 | +Finally, we execute our plan if planning was successful, otherwise we log an error: |
| 238 | + |
| 239 | +.. code-block:: C++ |
| 240 | + |
| 241 | + // Execute the plan |
| 242 | + if(success) { |
| 243 | + move_group_interface.execute(plan); |
| 244 | + } else { |
| 245 | + RCLCPP_ERROR(logger, "Planning failed!"); |
| 246 | + } |
| 247 | + |
| 248 | +Summary |
| 249 | +------- |
| 250 | + |
| 251 | +* You created a ROS 2 package and wrote your first program using MoveIt. |
| 252 | +* You learned about using the MoveGroupInterface to plan and execute moves. |
| 253 | +* :codedir:`Here is a copy of the full hello_moveit.cpp source at the end of this tutorial<tutorials/your_first_project/hello_moveit.cpp>`. |
| 254 | + |
| 255 | +Further Reading |
| 256 | +--------------- |
| 257 | + |
| 258 | +- We used lambdas to be able to initialize objects as constants. This is known as a technique called IIFE. `Read more about this pattern from C++ Stories <https://www.cppstories.com/2016/11/iife-for-complex-initialization/>`_. |
| 259 | +- We also declared everything we could as const. `Read more about the usefulness of const here <https://www.cppstories.com/2016/12/please-declare-your-variables-as-const/>`_. |
| 260 | + |
| 261 | +Next Step |
| 262 | +--------- |
| 263 | + |
| 264 | +TODO |
0 commit comments