Skip to content

Commit

Permalink
Update the displayed tutorial robot (#720)
Browse files Browse the repository at this point in the history
* Update Quickstart Guide

* Update your first c++ project

* Update Visualizing in rviz

* Update Planning Around Objects tutorial

* missed a couple updates

* pre-commit

* Needs to be demo.launch.py

* add kinova 7dof moveit config dependency

* update unit test

* pre-commit again

* update test pose

* update trajectory_execution param
  • Loading branch information
abake48 authored Jul 27, 2023
1 parent a7a1b89 commit f226955
Show file tree
Hide file tree
Showing 48 changed files with 1,855 additions and 36 deletions.
Binary file modified _static/videos/rviz_joints_nullspace.webm
Binary file not shown.
125 changes: 125 additions & 0 deletions doc/tutorials/planning_around_objects/hello_moveit_kinova.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,125 @@
#include <moveit/move_group_interface/move_group_interface.h>
#include <moveit/planning_scene_interface/planning_scene_interface.h>
#include <moveit_visual_tools/moveit_visual_tools.h>

#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <thread>

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");

// We spin up a SingleThreadedExecutor for the current state monitor to get
// information about the robot's state.
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
auto spinner = std::thread([&executor]() { executor.spin(); });

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

// Construct and initialize MoveItVisualTools
auto moveit_visual_tools =
moveit_visual_tools::MoveItVisualTools{ node, "base_link", rviz_visual_tools::RVIZ_MARKER_TOPIC,
move_group_interface.getRobotModel() };
moveit_visual_tools.deleteAllMarkers();
moveit_visual_tools.loadRemoteControl();

// Create a closure for updating the text in rviz
auto const draw_title = [&moveit_visual_tools](auto text) {
auto const text_pose = [] {
auto msg = Eigen::Isometry3d::Identity();
msg.translation().z() = 1.0;
return msg;
}();
moveit_visual_tools.publishText(text_pose, text, rviz_visual_tools::WHITE, rviz_visual_tools::XLARGE);
};
auto const prompt = [&moveit_visual_tools](auto text) { moveit_visual_tools.prompt(text); };
auto const draw_trajectory_tool_path =
[&moveit_visual_tools, jmg = move_group_interface.getRobotModel()->getJointModelGroup("manipulator")](
auto const trajectory) { moveit_visual_tools.publishTrajectoryLine(trajectory, jmg); };

// Set a target Pose with updated values !!!
auto const target_pose = [] {
geometry_msgs::msg::Pose msg;
msg.orientation.y = 0.8;
msg.orientation.w = 0.6;
msg.position.x = 0.1;
msg.position.y = 0.4;
msg.position.z = 0.4;
return msg;
}();
move_group_interface.setPoseTarget(target_pose);

// Create collision object for the robot to avoid
auto const collision_object = [frame_id = move_group_interface.getPlanningFrame()] {
moveit_msgs::msg::CollisionObject collision_object;
collision_object.header.frame_id = frame_id;
collision_object.id = "box1";
shape_msgs::msg::SolidPrimitive primitive;

// Define the size of the box in meters
primitive.type = primitive.BOX;
primitive.dimensions.resize(3);
primitive.dimensions[primitive.BOX_X] = 0.5;
primitive.dimensions[primitive.BOX_Y] = 0.1;
primitive.dimensions[primitive.BOX_Z] = 0.5;

// Define the pose of the box (relative to the frame_id)
geometry_msgs::msg::Pose box_pose;
box_pose.orientation.w = 1.0;
box_pose.position.x = 0.2;
box_pose.position.y = 0.2;
box_pose.position.z = 0.25;

collision_object.primitives.push_back(primitive);
collision_object.primitive_poses.push_back(box_pose);
collision_object.operation = collision_object.ADD;

return collision_object;
}();

// Add the collision object to the scene
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
planning_scene_interface.applyCollisionObject(collision_object);

// Create a plan to that target pose
prompt("Press 'next' in the RvizVisualToolsGui window to plan");
draw_title("Planning");
moveit_visual_tools.trigger();
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)
{
draw_trajectory_tool_path(plan.trajectory);
moveit_visual_tools.trigger();
prompt("Press 'next' in the RvizVisualToolsGui window to execute");
draw_title("Executing");
moveit_visual_tools.trigger();
move_group_interface.execute(plan);
}
else
{
draw_title("Planning Failed!");
moveit_visual_tools.trigger();
RCLCPP_ERROR(logger, "Planning failed!");
}

// Shutdown ROS
rclcpp::shutdown();
spinner.join();
return 0;
}
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
Expand Up @@ -100,15 +100,15 @@ This code block should directly follow the code block that creates the collision

Just as we did in the last tutorial, start RViz using the ``demo.launch.py`` script and run our program. If you're using one of the Docker tutorial containers, you can specify a different RViz configuration that already has the RvizVisualToolsGui panel added using: ::

ros2 launch moveit2_tutorials demo.launch.py rviz_config:=panda_hello_moveit.rviz
ros2 launch moveit2_tutorials demo.launch.py rviz_config:=kinova_hello_moveit.rviz

.. image:: planning_around_object.png

Summary
-------

- You extended the program you wrote with MoveIt to plan around an object in the scene.
- :codedir:`Here is a copy of the full hello_moveit.cpp source<tutorials/planning_around_objects/hello_moveit.cpp>`.
- :codedir:`Here is a copy of the full hello_moveit.cpp source<tutorials/planning_around_objects/hello_moveit_kinova.cpp>`.

Further Reading
---------------
Expand Down
29 changes: 18 additions & 11 deletions doc/tutorials/quickstart_in_rviz/launch/demo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ def generate_launch_description():
declared_arguments.append(
DeclareLaunchArgument(
"rviz_config",
default_value="panda_moveit_config_demo.rviz",
default_value="kinova_moveit_config_demo.rviz",
description="RViz configuration file",
)
)
Expand All @@ -28,15 +28,24 @@ def generate_launch_description():

def launch_setup(context, *args, **kwargs):

launch_arguments = {
"robot_ip": "xxx.yyy.zzz.www",
"use_fake_hardware": "true",
"gripper": "robotiq_2f_85",
"dof": "7",
}

moveit_config = (
MoveItConfigsBuilder("moveit_resources_panda")
.robot_description(file_path="config/panda.urdf.xacro")
.trajectory_execution(file_path="config/gripper_moveit_controllers.yaml")
MoveItConfigsBuilder(
"gen3", package_name="kinova_gen3_7dof_robotiq_2f_85_moveit_config"
)
.robot_description(mappings=launch_arguments)
.trajectory_execution(file_path="config/moveit_controllers.yaml")
.planning_scene_monitor(
publish_robot_description=True, publish_robot_description_semantic=True
)
.planning_pipelines(
pipelines=["ompl", "chomp", "pilz_industrial_motion_planner"]
pipelines=["ompl", "stomp", "pilz_industrial_motion_planner"]
)
.to_moveit_configs()
)
Expand Down Expand Up @@ -76,7 +85,7 @@ def launch_setup(context, *args, **kwargs):
executable="static_transform_publisher",
name="static_transform_publisher",
output="log",
arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "world", "panda_link0"],
arguments=["0.0", "0.0", "0.0", "0.0", "0.0", "0.0", "world", "base_link"],
)

# Publish TF
Expand All @@ -90,7 +99,7 @@ def launch_setup(context, *args, **kwargs):

# ros2_control using FakeSystem as hardware
ros2_controllers_path = os.path.join(
get_package_share_directory("moveit_resources_panda_moveit_config"),
get_package_share_directory("kinova_gen3_7dof_robotiq_2f_85_moveit_config"),
"config",
"ros2_controllers.yaml",
)
Expand All @@ -106,8 +115,6 @@ def launch_setup(context, *args, **kwargs):
executable="spawner",
arguments=[
"joint_state_broadcaster",
"--controller-manager-timeout",
"300",
"--controller-manager",
"/controller_manager",
],
Expand All @@ -116,13 +123,13 @@ def launch_setup(context, *args, **kwargs):
arm_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["panda_arm_controller", "-c", "/controller_manager"],
arguments=["joint_trajectory_controller", "-c", "/controller_manager"],
)

hand_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["panda_hand_controller", "-c", "/controller_manager"],
arguments=["robotiq_gripper_controller", "-c", "/controller_manager"],
)
nodes_to_start = [
rviz_node,
Expand Down
Loading

0 comments on commit f226955

Please sign in to comment.