Skip to content

Commit

Permalink
Merge pull request #363 from reidchristopher/ros2-demo1-instructions
Browse files Browse the repository at this point in the history
ROS2 Demo1 instructions
  • Loading branch information
jdlangs committed Oct 11, 2021
2 parents 149b62e + bdc149d commit 9682270
Show file tree
Hide file tree
Showing 32 changed files with 421 additions and 435 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@
Hints:
- You can manipulate the "world_to_tcp_tf" transform through the "setOrigin" and "setRotation".
- Look into the "create_manipulation_poses" function and observe how each pick pose is created.
- Look into the "createManipulationPoses" function and observe how each pick pose is created.
*/

std::vector<geometry_msgs::msg::Pose>
pick_and_place_application::PickAndPlaceApp::computePickToolPoses(geometry_msgs::msg::Pose& box_pose)
{
// RCLCPP_ERROR_STREAM(node->get_logger(), "create_pick_moves is not implemented yet. Aborting."); exit(1);
// RCLCPP_ERROR_STREAM(node->get_logger(), "computePickToolPoses is not implemented yet. Aborting."); exit(1);

// transforms relative to world
tf2::Transform tcp_at_box_tf; // transform of tcp at box pick location relative to world
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,12 @@
Hints:
- You can manipulate the "world_to_tcp_tf" transform through the "setOrigin" and "setRotation".
- Use the "create_manipulation_poses" function to create the tcp poses between each place move
- Use the "createManipulationPoses" function to create the tcp poses between each place move
*/

std::vector<geometry_msgs::msg::Pose> pick_and_place_application::PickAndPlaceApp::computePlaceToolPoses()
{
// RCLCPP_ERROR_STREAM(node->get_logger(), "create_place_moves is not implemented yet. Aborting."); exit(1);
// RCLCPP_ERROR_STREAM(node->get_logger(), "computePlaceToolPoses is not implemented yet. Aborting."); exit(1);

// task variables
tf2::Transform tcp_at_box_tf, tcp_to_wrist_tf;
Expand All @@ -26,7 +26,7 @@ std::vector<geometry_msgs::msg::Pose> pick_and_place_application::PickAndPlaceAp
* Hints:
* - Use the "setOrigin" method to set the position of "tcp_at_box_tf"
* using cfg.BOX_PLACE_TF.
* - cfg.BOX_PLACE_TF is a tf::Transform object so it provides a getOrigin() method.
* - cfg.BOX_PLACE_TF is a tf2::Transform object so it provides a getOrigin() method.
*/
tcp_at_box_tf.setOrigin(cfg.BOX_PLACE_TF.getOrigin());

Expand All @@ -35,7 +35,7 @@ std::vector<geometry_msgs::msg::Pose> pick_and_place_application::PickAndPlaceAp
* - Reorient the tool so that the tcp points towards the box.
* Hints:
* - Use the "setRotation" to set the orientation of "tcp_at_box_tf".
* - The quaternion value "tf::Quaternion(0.707, 0.707, 0, 0)" will point
* - The quaternion value "tf2::Quaternion(0.707, 0.707, 0, 0)" will point
* the tcp's direction towards the box.
*/
tcp_at_box_tf.setRotation(cfg.BOX_PLACE_TF.getRotation() * tf2::Quaternion(0.707, 0.707, 0, 0));
Expand All @@ -44,7 +44,7 @@ std::vector<geometry_msgs::msg::Pose> pick_and_place_application::PickAndPlaceAp
* Goal:
* - Create place poses for tcp. *
* Hints:
* - Use the "create_manipulation_poses" and save results to "tcp_place_poses".
* - Use the "createManipulationPoses" and save results to "tcp_place_poses".
* - The RETREAT_DISTANCE and APPROACH_DISTANCE values were populated from a configuration yaml file passed to the executable in the launch file.
*/
tcp_place_poses = createManipulationPoses(cfg.RETREAT_DISTANCE, cfg.APPROACH_DISTANCE, tcp_at_box_tf);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ geometry_msgs::msg::Pose pick_and_place_application::PickAndPlaceApp::detectBox(
using RequestType = pick_and_place_msgs::srv::GetTargetPose::Request;
using ResponseType = pick_and_place_msgs::srv::GetTargetPose::Response;

// RCLCPP_ERROR_STREAM(node->get_logger(),"detect_box_pick is not implemented yet. Aborting."); exit(1);
// RCLCPP_ERROR_STREAM(node->get_logger(),"detectBox is not implemented yet. Aborting."); exit(1);

// creating shape for recognition
shape_msgs::msg::SolidPrimitive shape;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ using moveit::planning_interface::MoveItErrorCode;

void pick_and_place_application::PickAndPlaceApp::moveToWaitPosition()
{
// RCLCPP_ERROR(node->get_logger(),"move_to_wait_position is not implemented yet. Aborting."); exit(1);
// RCLCPP_ERROR(node->get_logger(),"moveToWaitPosition is not implemented yet. Aborting."); exit(1);

if (!moveit_cpp->getPlanningSceneMonitor()->requestPlanningSceneState())
{
Expand All @@ -29,13 +29,13 @@ void pick_and_place_application::PickAndPlaceApp::moveToWaitPosition()
plan_parameters.planning_time = 20.0f;
plan_parameters.planning_attempts = 4;

/* // task variables
/*
Fill Code:
* Goal:
* - Set robot wait target
* Hints:
* - Use the "setNamedTarget" method in the "move_group_ptr" object.
* - Use the "setGoal" method in the "planning_component" object.
* - The "WAIT_POSE_NAME" variable is a member of the "cfg" object.
*/
planning_component.setGoal(cfg.WAIT_POSE_NAME);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
void pick_and_place_application::PickAndPlaceApp::doBoxPickup(std::vector<geometry_msgs::msg::Pose>& pick_poses,
const geometry_msgs::msg::Pose& box_pose)
{
// RCLCPP_ERROR_STREAM(node->get_logger(),"pickup_box is not implemented yet. Aborting."); exit(1);
// RCLCPP_ERROR_STREAM(node->get_logger(),"doBoxPickup is not implemented yet. Aborting."); exit(1);

// task variables
bool success;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
void pick_and_place_application::PickAndPlaceApp::doBoxPlace(std::vector<geometry_msgs::msg::Pose>& place_poses,
const geometry_msgs::msg::Pose& box_pose)
{
// RCLCPP_ERROR_STREAM(node->get_logger(),"place_box is not implemented yet. Aborting."); exit(1);
// RCLCPP_ERROR_STREAM(node->get_logger(),"doBoxPlace is not implemented yet. Aborting."); exit(1);

// task variables
bool success;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ void pick_and_place_application::PickAndPlaceApp::actuateGripper(bool do_grasp)
{
using GraspGoalType = pick_and_place_msgs::action::ExecuteGraspMove::Goal;
using GraspGoalHandle = rclcpp_action::ClientGoalHandle<pick_and_place_msgs::action::ExecuteGraspMove>;
// RCLCPP_ERROR_STREAM(node->get_logger(),"set_gripper is not implemented yet. Aborting."); exit(1);
// RCLCPP_ERROR_STREAM(node->get_logger(),"actuateGripper is not implemented yet. Aborting."); exit(1);

// task variables
GraspGoalType grasp_goal;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,6 @@ repositories:
perception_pcl:
type: git
url: https://github.com/ros-perception/perception_pcl.git
version: ros2
version: foxy-devel


Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@
Hints:
- You can manipulate the "world_to_tcp_tf" transform through the "setOrigin" and "setRotation".
- Look into the "create_manipulation_poses" function and observe how each pick pose is created.
- Look into the "createManipulationPoses" function and observe how each pick pose is created.
*/

std::vector<geometry_msgs::msg::Pose>
pick_and_place_application::PickAndPlaceApp::computePickToolPoses(geometry_msgs::msg::Pose& box_pose)
{
RCLCPP_ERROR_STREAM(node->get_logger(), "create_pick_moves is not implemented yet. Aborting."); exit(1);
RCLCPP_ERROR_STREAM(node->get_logger(), "computePickToolPoses is not implemented yet. Aborting."); exit(1);

// transforms relative to world
tf2::Transform tcp_at_box_tf; // transform of tcp at box pick location relative to world
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,12 @@
Hints:
- You can manipulate the "world_to_tcp_tf" transform through the "setOrigin" and "setRotation".
- Use the "create_manipulation_poses" function to create the tcp poses between each place move
- Use the "createManipulationPoses" function to create the tcp poses between each place move
*/

std::vector<geometry_msgs::msg::Pose> pick_and_place_application::PickAndPlaceApp::computePlaceToolPoses()
{
RCLCPP_ERROR_STREAM(node->get_logger(), "create_place_moves is not implemented yet. Aborting."); exit(1);
RCLCPP_ERROR_STREAM(node->get_logger(), "computePlaceToolPoses is not implemented yet. Aborting."); exit(1);

// task variables
tf2::Transform tcp_at_box_tf, tcp_to_wrist_tf;
Expand All @@ -26,7 +26,7 @@ std::vector<geometry_msgs::msg::Pose> pick_and_place_application::PickAndPlaceAp
* Hints:
* - Use the "setOrigin" method to set the position of "tcp_at_box_tf"
* using cfg.BOX_PLACE_TF.
* - cfg.BOX_PLACE_TF is a tf::Transform object so it provides a getOrigin() method.
* - cfg.BOX_PLACE_TF is a tf2::Transform object so it provides a getOrigin() method.
*/
// UNCOMMENT AND COMPLETE: tcp_at_box_tf.setOrigin(...);

Expand All @@ -35,7 +35,7 @@ std::vector<geometry_msgs::msg::Pose> pick_and_place_application::PickAndPlaceAp
* - Reorient the tool so that the tcp points towards the box.
* Hints:
* - Use the "setRotation" to set the orientation of "tcp_at_box_tf".
* - The quaternion value "tf::Quaternion(0.707, 0.707, 0, 0)" will point
* - The quaternion value "tf2::Quaternion(0.707, 0.707, 0, 0)" will point
* the tcp's direction towards the box.
*/
// UNCOMMENT AND COMPLETE: tcp_at_box_tf.setRotation(cfg.BOX_PLACE_TF.getRotation() * ...);
Expand All @@ -44,7 +44,7 @@ std::vector<geometry_msgs::msg::Pose> pick_and_place_application::PickAndPlaceAp
* Goal:
* - Create place poses for tcp. *
* Hints:
* - Use the "create_manipulation_poses" and save results to "tcp_place_poses".
* - Use the "createManipulationPoses" and save results to "tcp_place_poses".
* - The RETREAT_DISTANCE and APPROACH_DISTANCE values were populated from a configuration yaml file passed to the executable in the launch file.
*/
// UNCOMMENT AND COMPLETE: tcp_place_poses = createManipulationPoses(..., ..., tcp_at_box_tf);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ geometry_msgs::msg::Pose pick_and_place_application::PickAndPlaceApp::detectBox(
using RequestType = pick_and_place_msgs::srv::GetTargetPose::Request;
using ResponseType = pick_and_place_msgs::srv::GetTargetPose::Response;

RCLCPP_ERROR_STREAM(node->get_logger(),"detect_box_pick is not implemented yet. Aborting."); exit(1);
RCLCPP_ERROR_STREAM(node->get_logger(),"detectBox is not implemented yet. Aborting."); exit(1);

// creating shape for recognition
shape_msgs::msg::SolidPrimitive shape;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ using moveit::planning_interface::MoveItErrorCode;

void pick_and_place_application::PickAndPlaceApp::moveToWaitPosition()
{
RCLCPP_ERROR(node->get_logger(),"move_to_wait_position is not implemented yet. Aborting."); exit(1);
RCLCPP_ERROR(node->get_logger(),"moveToWaitPosition is not implemented yet. Aborting."); exit(1);

if (!moveit_cpp->getPlanningSceneMonitor()->requestPlanningSceneState())
{
Expand All @@ -35,7 +35,7 @@ void pick_and_place_application::PickAndPlaceApp::moveToWaitPosition()
* Goal:
* - Set robot wait target
* Hints:
* - Use the "setNamedTarget" method in the "move_group_ptr" object.
* - Use the "setGoal" method in the "planning_component" object.
* - The "WAIT_POSE_NAME" variable is a member of the "cfg" object.
*/
// UNCOMMENT AND COMPLETE: planning_component.setGoal(...);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
void pick_and_place_application::PickAndPlaceApp::doBoxPickup(std::vector<geometry_msgs::msg::Pose>& pick_poses,
const geometry_msgs::msg::Pose& box_pose)
{
RCLCPP_ERROR_STREAM(node->get_logger(),"pickup_box is not implemented yet. Aborting."); exit(1);
RCLCPP_ERROR_STREAM(node->get_logger(),"doBoxPickup is not implemented yet. Aborting."); exit(1);

// task variables
bool success;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
void pick_and_place_application::PickAndPlaceApp::doBoxPlace(std::vector<geometry_msgs::msg::Pose>& place_poses,
const geometry_msgs::msg::Pose& box_pose)
{
RCLCPP_ERROR_STREAM(node->get_logger(),"place_box is not implemented yet. Aborting."); exit(1);
RCLCPP_ERROR_STREAM(node->get_logger(),"doBoxPlace is not implemented yet. Aborting."); exit(1);

// task variables
bool success;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ void pick_and_place_application::PickAndPlaceApp::actuateGripper(bool do_grasp)
using GraspGoalType = pick_and_place_msgs::action::ExecuteGraspMove::Goal;
using GraspGoalHandle = rclcpp_action::ClientGoalHandle<pick_and_place_msgs::action::ExecuteGraspMove>;

RCLCPP_ERROR_STREAM(node->get_logger(),"set_gripper is not implemented yet. Aborting."); exit(1);
RCLCPP_ERROR_STREAM(node->get_logger(),"actuateGripper is not implemented yet. Aborting."); exit(1);

// task variables
GraspGoalType grasp_goal;
Expand Down
File renamed without changes.
86 changes: 86 additions & 0 deletions gh_pages/_source/demo1/1-Inspect-the-package.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
Inspect the ``pick_and_place_application`` Package
==================================================

In this exercise, we will get familiar with all the files that you will be
interacting with throughout the next exercises.


Acquire the Workspace
------------------------------------

.. code-block:: shell
cp -r ~/industrial_training/exercises/Perception-Driven_Manipulation/ros2/template_ws \
~/perception_driven_ws
Locate and navigate into the package
------------------------------------

.. code-block:: shell
cd ~/perception_driven_ws/src/pick_and_place_application/
Look into the ``launch`` directory
----------------------------------

* ``application_setup.launch.py``

* Brings up the entire ROS system (MoveIt!, Rviz, perception nodes, ROS-I drivers, robot I/O peripherals)

* ``application_run.launch.py``

* Runs your pick and place node.


Look into the ``config`` directory
----------------------------------

* ``pick_and_place_parameters.yaml``

* List of parameters read by the pick and place node.

* ``rviz_config.rviz``

* Rviz configuration file for display properties.

* ``target_recognition_parameters.yaml``

* Parameters used by the target recognition service for detecting the box from the sensor data.

* ``fake_obstacles_cloud_descriptions.yaml``

* Parameters used to generate simulated sensor data (simulated sensor mode only).


Look into the ``src`` directory
-------------------------------

* ``nodes/``

* ``pick_and_place_node.cpp``

* Main application thread. Contains all necessary headers and function calls.

* ``tasks/``

* ``create_motion_plan.cpp``
* ``create_pick_moves.cpp``
* ``create_place_moves.cpp``
* ``detect_box_pick.cpp``
* ``initialize.cpp``
* ``move_to_wait_position.cpp``
* ``pickup_box.cpp``
* ``place_box.cpp``
* ``reset_world.cpp``
* ``set_attached_object.cpp``
* ``set_gripper.cpp``

.. note:: The ``tasks`` directory contains source files with incomplete function definitions. You will fill with code where needed in order to complete the exercise.

* ``utilities/``

* ``pick_and_place_utilities.cpp``

* Contains support functions that will help you complete the exercise.

0 comments on commit 9682270

Please sign in to comment.