Skip to content

Commit

Permalink
Respond to feedback
Browse files Browse the repository at this point in the history
Signed-off-by: Tyler Weaver <tyler@picknik.ai>
  • Loading branch information
tylerjw committed May 19, 2022
1 parent 78389a9 commit 632fc64
Show file tree
Hide file tree
Showing 3 changed files with 61 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -236,4 +236,4 @@ RViz enables you to save your configuration under ``File->Save Config``. You sho
Next Tutorial
+++++++++++++

:doc:`/doc/tutorials/your_first_project/your_first_project`
In :doc:`Your First MoveIt Project </doc/tutorials/your_first_project/your_first_project>`, you will create a C++ program using MoveIt to plan and execute moves.
51 changes: 51 additions & 0 deletions doc/tutorials/your_first_project/hello_moveit.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
#include <memory>

#include <rclcpp/rclcpp.hpp>
#include <moveit/move_group_interface/move_group_interface.h>

int main(int argc, char* argv[])
{
// Initialize ROS and create the Node
rclcpp::init(argc, argv);
auto const node = std::make_shared<rclcpp::Node>(
"hello_moveit", rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true));

// Create a ROS logger
auto const logger = rclcpp::get_logger("hello_moveit");

// Create the MoveIt MoveGroup Interface
using moveit::planning_interface::MoveGroupInterface;
auto move_group_interface = MoveGroupInterface(node, "panda_arm");

// Set a target Pose
auto const target_pose = [] {
geometry_msgs::msg::Pose msg;
msg.orientation.w = 1.0;
msg.position.x = 0.28;
msg.position.y = -0.2;
msg.position.z = 0.5;
return msg;
}();
move_group_interface.setPoseTarget(target_pose);

// Create a plan to that target pose
auto const [success, plan] = [&move_group_interface] {
moveit::planning_interface::MoveGroupInterface::Plan msg;
auto const ok = static_cast<bool>(move_group_interface.plan(msg));
return std::make_pair(ok, msg);
}();

// Execute the plan
if (success)
{
move_group_interface.execute(plan);
}
else
{
RCLCPP_ERROR(logger, "Planing failed!");
}

// Shutdown ROS
rclcpp::shutdown();
return 0;
}
11 changes: 9 additions & 2 deletions doc/tutorials/your_first_project/your_first_project.rst
Original file line number Diff line number Diff line change
Expand Up @@ -200,6 +200,8 @@ If it fails to find that within 10 seconds it prints this error and terminates t

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.
Note that this is the only mutable object that we create in this program.
Another thing to take note of is the second interface to the ``MoveGroupInterface`` object we are creating here: ``"panda_arm"``.
That is the group of joints as defined in the robot description that we are going to operate on with this ``MoveGroupInterface``.

.. code-block:: C++

Expand All @@ -208,6 +210,10 @@ Note that this is the only mutable object that we create in this program.

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).

One more thing to note about this next section is the use of lambdas for constructing the message type ``target_pose`` and planning.
This is a pattern you'll find in modern C++ codebases that enables writing in a more declarative style.
For more information about this pattern there is a couple of links at the end of this tutorial.

.. code-block:: C++

// Set a target Pose
Expand Down Expand Up @@ -242,8 +248,9 @@ Finally, we execute our plan if planning was successful, otherwise we log an err
Summary
-------

You created a ROS 2 package and wrote your first program using MoveIt.

* You created a ROS 2 package and wrote your first program using MoveIt.
* You learned about using the MoveGroupInterface to plan and execute moves.
* :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>`.

Further Reading
---------------
Expand Down

0 comments on commit 632fc64

Please sign in to comment.