optimize parameters
This commit is contained in:
@@ -53,7 +53,7 @@
|
||||
|
||||
frame_time_stamp: 0
|
||||
|
||||
data_array: [0, 0, 0, 0, 0, 0, 60, -22, -90, 0, -68, 90]
|
||||
data_array: [0, 0, 0, 0, 0, 0, 14.29, -34.07, -122.53, -76.89, 84.40, 112.89]
|
||||
|
||||
'
|
||||
- name: s1_left_arm_pre_cam_take_photo
|
||||
@@ -67,7 +67,7 @@
|
||||
|
||||
frame_time_stamp: 0
|
||||
|
||||
data_array: [120, 22, 90, 0, 68, 90, 0, 0, 0, 0, 0, 0]
|
||||
data_array: [165.80, 34.07, 122.53, 76.89, -84.40, 67.20, 0, 0, 0, 0, 0, 0]
|
||||
|
||||
'
|
||||
- name: s2_right_arm_cam_take_photo
|
||||
|
||||
@@ -655,16 +655,16 @@ void CerebellumHooks::ConfigureVisionObjectRecognitionHooks(CerebellumNode * nod
|
||||
geometry_msgs::msg::PoseStamped target_pose = node->target_pose_[node->target_frame_];
|
||||
target_pose.header.frame_id = "base_link_rightarm";
|
||||
|
||||
if (target_pose.pose.position.z > 0.10f) { //right arm
|
||||
if (target_pose.pose.position.z >= 0.05f) { //right arm
|
||||
target_arm = "right_arm";
|
||||
target_pose.pose.position.x += 0.10f;
|
||||
target_pose.pose.position.y = 0.32f;
|
||||
target_pose.pose.position.x += 0.12f;
|
||||
target_pose.pose.position.y = 0.33f;
|
||||
target_pose.pose.orientation.x = -0.7071;
|
||||
target_pose.pose.orientation.y = 0.0000;
|
||||
target_pose.pose.orientation.z = -0.0000;
|
||||
target_pose.pose.orientation.w = 0.7071;
|
||||
|
||||
} else if (target_pose.pose.position.z < -0.10f) { //left arm
|
||||
} else if (target_pose.pose.position.z <= -0.10f) { //left arm
|
||||
//transfer to left arm base
|
||||
target_arm = "left_arm";
|
||||
geometry_msgs::msg::PoseStamped left_arm_pose;
|
||||
@@ -675,8 +675,8 @@ void CerebellumHooks::ConfigureVisionObjectRecognitionHooks(CerebellumNode * nod
|
||||
return false;
|
||||
}
|
||||
target_pose.pose = left_arm_pose.pose;
|
||||
target_pose.pose.position.x += 0.10f;
|
||||
target_pose.pose.position.y = -0.32f;
|
||||
target_pose.pose.position.x += 0.12f;
|
||||
target_pose.pose.position.y = -0.33f;
|
||||
target_pose.pose.orientation.x = 0.7071;
|
||||
target_pose.pose.orientation.y = 0.0000;
|
||||
target_pose.pose.orientation.z = -0.0000;
|
||||
@@ -778,7 +778,7 @@ void CerebellumHooks::ConfigureVisionObjectRecognitionHooks(CerebellumNode * nod
|
||||
for (double angle : best_angles) {
|
||||
for (const auto& palm : palm_facings) {
|
||||
brain::GraspResult result = brain::GraspPoseCalculator::calculate(target_pos,
|
||||
target_quat, "side", angle, palm, 0.10, 0.20, node->arm_target_frame_);
|
||||
target_quat, "side", angle, palm, 0.03, 0.20, node->arm_target_frame_);
|
||||
|
||||
#ifdef DEBUG_GRASP_POSE_CALCULATION
|
||||
RCLCPP_INFO(node->get_logger(), "[%s] angle %f, palm %s, pre_grasp_pose[%.4f, %.4f, %.4f, %.4f, %.4f, %.4f, %.4f]",
|
||||
|
||||
Reference in New Issue
Block a user