Skip to content

Commit

Permalink
Merge branch 'main' of https://github.com/mrceki/air_robot_arm into main
Browse files Browse the repository at this point in the history
  • Loading branch information
mrceki committed Mar 2, 2023
2 parents 5ac5ec1 + 65608fe commit 1c32376
Show file tree
Hide file tree
Showing 43 changed files with 1,061 additions and 98 deletions.
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -46,3 +46,5 @@ rosrun air_moveit_config add_sphere
```
roslaunch air_moveit_config air_mtc.launch
```
## Tips
The workspace may not be created when you clone the ADS repository.
51 changes: 51 additions & 0 deletions air_moveit_config/scripts/generate_pose.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
#! /usr/bin/env python3
# -*- coding: utf-8 -*-

from moveit.task_constructor import core, stages
from geometry_msgs.msg import PoseStamped
from moveit_commander.roscpp_initializer import roscpp_initialize
import time

roscpp_initialize("mtc_tutorial_compute_ik")

# Specify the planning group
group = "air"

# Create a task
task = core.Task()

# Get the current robot state
currentState = stages.CurrentState("current state")
task.add(currentState)

# Create a planner instance that is used to connect
# the current state to the grasp approach pose
pipelinePlanner = core.PipelinePlanner()
pipelinePlanner.planner = "RRTConnectkConfigDefault"
planners = [(group, pipelinePlanner)]

# Connect the two stages
connect = stages.Connect("connect1", planners)
connect.properties.configureInitFrom(core.Stage.PropertyInitializerSource.PARENT)
task.add(connect)

# [initAndConfigGeneratePose]
# create an example pose wrt. the origin of the
# panda arm link8
pose = PoseStamped()
pose.header.frame_id = "qbhand_base_link"

# Calculate the inverse kinematics for the current robot state
generatePose = stages.GeneratePose("generate pose")

# spwan a pose whenever there is a solution of the monitored stage
generatePose.setMonitoredStage(task["current state"])
generatePose.pose = pose

# Add the stage to the task hierarchy
task.add(generatePose)
# [initAndConfigGeneratePose]

if task.plan():
task.publish(task.solutions[0])
time.sleep(1)
134 changes: 134 additions & 0 deletions air_moveit_config/scripts/pickplace.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,134 @@
#! /usr/bin/env python3
# -*- coding: utf-8 -*-

from moveit_commander.roscpp_initializer import roscpp_initialize
from moveit.task_constructor import core, stages
from moveit_commander import PlanningSceneInterface
from geometry_msgs.msg import PoseStamped, TwistStamped
import time
import rospy


roscpp_initialize("pickplace")
rospy.loginfo("Z<OERJGHSDFKJSDFJKASDJKLFASJKLDFJKLASDFJKLKASJDFJKLASDLF")
# [pickAndPlaceTut1]
# Specify robot parameters
arm = "air"
eef = "gripper"
# [pickAndPlaceTut1]

# [pickAndPlaceTut2]
# Specify object parameters
object_name = "grasp_object"
object_radius = 0.02

# Start with a clear planning scene
psi = PlanningSceneInterface(synchronous=True)
psi.remove_world_object()

# [initCollisionObject]
# Grasp object properties
objectPose = PoseStamped()
objectPose.header.frame_id = "world"
objectPose.pose.orientation.w = 1.0
objectPose.pose.position.x = 0.55
objectPose.pose.position.y = -0.25
objectPose.pose.position.z = 0.82
# [initCollisionObject]

# Add the grasp object to the planning scene
psi.add_cylinder(object_name, objectPose, height=0.2, radius=0.01)
# [pickAndPlaceTut2]

# [pickAndPlaceTut3]
# Create a task
task = core.Task("PandaPickPipelineExample")
task.enableIntrospection()
# [pickAndPlaceTut3]

# [pickAndPlaceTut4]
# Start with the current state
task.add(stages.CurrentState("current"))

# [initAndConfigConnect]
# Create a planner instance that is used to connect
# the current state to the grasp approach pose
pipeline = core.PipelinePlanner()
pipeline.planner = "RRTConnect"
planners = [(arm, pipeline)]

# Connect the two stages
task.add(stages.Connect("connect1", planners))
# [initAndConfigConnect]
# [pickAndPlaceTut4]

# [initAndConfigGenerateGraspPose]
# The grasp generator spawns a set of possible grasp poses around the object
grasp_generator = stages.GenerateGraspPose("Generate Grasp Pose")
grasp_generator.angle_delta = 0.3
grasp_generator.pregrasp = "open"
grasp_generator.grasp = "closed"
grasp_generator.setMonitoredStage(task["current"]) # Generate solutions for all initial states
# [initAndConfigGenerateGraspPose]
# [pickAndPlaceTut5]

# [pickAndPlaceTut6]
# [initAndConfigSimpleGrasp]
# SimpleGrasp container encapsulates IK calculation of arm pose as well as finger closing
simpleGrasp = stages.SimpleGrasp(grasp_generator, "Grasp")
# Set frame for IK calculation in the center between the fingers
ik_frame = PoseStamped()
ik_frame.header.frame_id = "qbhand_base_link"
ik_frame.pose.position.y = 0.04
ik_frame.pose.position.z = 0.13
ik_frame.pose.orientation.w= 1
ik_frame.pose.orientation.x=-0.5646338
ik_frame.pose.orientation.y=-0.5646338
ik_frame.pose.orientation.z=0.5646338
simpleGrasp.setIKFrame(ik_frame)
# [initAndConfigSimpleGrasp]
# [pickAndPlaceTut6]

# [pickAndPlaceTut7]
# [initAndConfigPick]
# Pick container comprises approaching, grasping (using SimpleGrasp stage), and lifting of object
pick = stages.Pick(simpleGrasp, "Pick")
pick.eef = eef
pick.object = object_name

# Twist to approach the object
approach = TwistStamped()
approach.header.frame_id = "world"
approach.twist.linear.z = -1.0
pick.setApproachMotion(approach, 0.00, 0.25) # (approach, 0.03, 0.1)

# Twist to lift the object
lift = TwistStamped()
lift.header.frame_id = "qbhand_base_link"
lift.twist.linear.z = - 1.0
pick.setLiftMotion(lift, 0.00, 0.25) # (lift, 0.03, 0.1)
# [pickAndPlaceTut7]

# [pickAndPlaceTut8]
# Add the pick stage to the task's stage hierarchy
task.add(pick)
# [initAndConfigPick]
# [pickAndPlaceTut8]

# [pickAndPlaceTut9]
# Connect the Pick stage with the following Place stage

if task.plan():
try:
task.publish(task.solutions[0])
except:
print("Can't publish task")


# avoid ClassLoader warning
del pipeline
del planners
# [pickAndPlaceTut13]

# Prevent the program from exiting, giving you the opportunity to inspect solutions in rviz
time.sleep(120)
Loading

0 comments on commit 1c32376

Please sign in to comment.