Load scene config
This commit is contained in:
parent
e7aa81fed3
commit
d8ea9683db
@ -4,6 +4,10 @@ bt_sim:
|
||||
gripper_force: 10
|
||||
scene: random
|
||||
|
||||
hw:
|
||||
roi_calib_file: $(find active_grasp)/cfg/hw/T_base_tag.txt
|
||||
scene_file: $(find active_grasp)/cfg/hw/scene01.yaml
|
||||
|
||||
grasp_controller:
|
||||
base_frame_id: panda_link0
|
||||
ee_grasp_offset: [0.0, 0.0, -0.383, 0.924, 0.0, 0.0, 0.065] # offset to panda_link8
|
||||
|
4
cfg/hw/scene01.yaml
Normal file
4
cfg/hw/scene01.yaml
Normal file
@ -0,0 +1,4 @@
|
||||
target:
|
||||
min: [0.1, 0.1, 0.0]
|
||||
max: [0.2, 0.2, 0.1]
|
||||
q0: [0.0, -0.79, 0.0, -2.356, 0.0, 1.57, 0.79]
|
@ -1,6 +1,6 @@
|
||||
<?xml version="1.0" ?>
|
||||
<launch>
|
||||
<arg name="simulation" default="true" />
|
||||
<arg name="sim" default="true" />
|
||||
<arg name="launch_rviz" default="false" />
|
||||
|
||||
<!-- Load parameters -->
|
||||
@ -11,14 +11,14 @@
|
||||
<include file="$(find panda_moveit_config)/launch/move_group.launch" />
|
||||
|
||||
<!-- Simulated environment -->
|
||||
<group if="$(arg simulation)">
|
||||
<group if="$(arg sim)">
|
||||
<param name="robot_description" command="$(find xacro)/xacro $(find active_grasp)/assets/franka/panda_arm_hand.urdf.xacro" />
|
||||
<node pkg="active_grasp" type="bt_sim_node.py" name="bt_sim" output="screen" />
|
||||
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />
|
||||
</group>
|
||||
|
||||
<!-- Real environment -->
|
||||
<group unless="$(arg simulation)">
|
||||
<group unless="$(arg sim)">
|
||||
<node pkg="active_grasp" type="hw_node.py" name="hw" output="screen" />
|
||||
</group>
|
||||
|
||||
|
@ -1,24 +1,34 @@
|
||||
#!/usr/bin/env python3
|
||||
|
||||
from controller_manager_msgs.srv import *
|
||||
import numpy as np
|
||||
import rospy
|
||||
|
||||
from active_grasp.bbox import AABBox, to_bbox_msg
|
||||
from active_grasp.srv import *
|
||||
|
||||
|
||||
from robot_helpers.io import load_yaml
|
||||
from robot_helpers.ros.moveit import MoveItClient
|
||||
from robot_helpers.ros.panda import PandaGripperClient
|
||||
from robot_helpers.spatial import Transform
|
||||
|
||||
|
||||
class HwNode:
|
||||
def __init__(self):
|
||||
self.load_parameters()
|
||||
self.init_robot_connection()
|
||||
self.advertise_services()
|
||||
self.switch_controller = rospy.ServiceProxy(
|
||||
rospy.spin()
|
||||
|
||||
def load_parameters(self):
|
||||
cfg = rospy.get_param("hw")
|
||||
self.T_base_roi = Transform.from_matrix(np.loadtxt(cfg["roi_calib_file"]))
|
||||
self.scene_config = load_yaml(cfg["scene_file"])
|
||||
|
||||
def init_robot_connection(self):
|
||||
self.switch_to_joint_trajectory_controller = rospy.ServiceProxy(
|
||||
"controller_manager/switch_controller", SwitchController
|
||||
)
|
||||
|
||||
self.moveit = MoveItClient("panda_arm")
|
||||
rospy.spin()
|
||||
|
||||
def advertise_services(self):
|
||||
rospy.Service("seed", Seed, self.seed)
|
||||
@ -29,18 +39,24 @@ class HwNode:
|
||||
return SeedResponse()
|
||||
|
||||
def reset(self, req):
|
||||
# Move to the initial configuration
|
||||
self.switch_to_joint_trajectory_controller()
|
||||
self.moveit.goto(self.scene_config["q0"])
|
||||
|
||||
# Construct bounding box
|
||||
bbox_min = self.T_base_roi.apply(self.scene_config["target"]["min"])
|
||||
bbox_max = self.T_base_roi.apply(self.scene_config["target"]["max"])
|
||||
bbox = AABBox(bbox_min, bbox_max)
|
||||
|
||||
return ResetResponse(to_bbox_msg(bbox))
|
||||
|
||||
def switch_to_joint_trajectory_controller(self):
|
||||
req = SwitchControllerRequest()
|
||||
req.start_controllers = ["position_joint_trajectory_controller"]
|
||||
req.stop_controllers = ["cartesian_velocity_controller"]
|
||||
req.strictness = 1
|
||||
self.switch_controller(req)
|
||||
|
||||
# Move to the initial configuration
|
||||
self.moveit.goto([0.0, -0.79, 0.0, -2.356, 0.0, 1.57, 0.79])
|
||||
|
||||
# Detect target
|
||||
bbox = AABBox([0.4, -0.1, 0.0], [0.5, 0.1, 0.1])
|
||||
return ResetResponse(to_bbox_msg(bbox))
|
||||
|
||||
|
||||
def main():
|
||||
rospy.init_node("hw")
|
||||
|
@ -59,12 +59,14 @@ class GraspController:
|
||||
req = SwitchControllerRequest()
|
||||
req.start_controllers = ["cartesian_velocity_controller"]
|
||||
req.stop_controllers = ["position_joint_trajectory_controller"]
|
||||
req.strictness = 1
|
||||
self.switch_controller(req)
|
||||
|
||||
def switch_to_joint_trajectory_control(self):
|
||||
req = SwitchControllerRequest()
|
||||
req.start_controllers = ["position_joint_trajectory_controller"]
|
||||
req.stop_controllers = ["cartesian_velocity_controller"]
|
||||
req.strictness = 1
|
||||
self.switch_controller(req)
|
||||
|
||||
def init_camera_stream(self):
|
||||
|
Loading…
x
Reference in New Issue
Block a user