modify rm lib
This commit is contained in:
@@ -71,7 +71,7 @@ ament_target_dependencies(brain_node
|
||||
target_link_libraries(brain_node
|
||||
Boost::thread
|
||||
yaml-cpp
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/lib/libapi_cpp.so
|
||||
/usr/local/lib/libapi_cpp.so
|
||||
)
|
||||
|
||||
install(TARGETS brain_node
|
||||
@@ -172,7 +172,7 @@ if(BUILD_TESTING)
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/include
|
||||
)
|
||||
target_link_libraries(test_cerebellum_node Boost::thread)
|
||||
target_link_libraries(test_cerebellum_node yaml-cpp ${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/lib/libapi_cpp.so)
|
||||
target_link_libraries(test_cerebellum_node yaml-cpp /usr/local/lib/libapi_cpp.so)
|
||||
endif()
|
||||
|
||||
ament_add_gtest(test_cerebrum_node
|
||||
@@ -202,7 +202,7 @@ if(BUILD_TESTING)
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/include
|
||||
)
|
||||
target_link_libraries(test_cerebrum_node Boost::thread)
|
||||
target_link_libraries(test_cerebrum_node yaml-cpp ${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/lib/libapi_cpp.so)
|
||||
target_link_libraries(test_cerebrum_node yaml-cpp /usr/local/lib/libapi_cpp.so)
|
||||
endif()
|
||||
|
||||
ament_add_gtest(test_sm_cerebellum
|
||||
@@ -225,7 +225,7 @@ if(BUILD_TESTING)
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/include
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/include
|
||||
)
|
||||
target_link_libraries(test_sm_cerebellum ${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/lib/libapi_cpp.so)
|
||||
target_link_libraries(test_sm_cerebellum /usr/local/lib/libapi_cpp.so)
|
||||
endif()
|
||||
|
||||
# ExecuteBtAction end-to-end single skill test
|
||||
@@ -254,7 +254,7 @@ if(BUILD_TESTING)
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/include
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/include
|
||||
)
|
||||
target_link_libraries(test_execute_bt_action Boost::thread yaml-cpp ${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/lib/libapi_cpp.so)
|
||||
target_link_libraries(test_execute_bt_action Boost::thread yaml-cpp /usr/local/lib/libapi_cpp.so)
|
||||
endif()
|
||||
|
||||
# Extended ExecuteBtAction scenario tests (multi-skill, failure, RUN interpolation, timeout, stats, cancel)
|
||||
@@ -283,7 +283,7 @@ if(BUILD_TESTING)
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/include
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/include
|
||||
)
|
||||
target_link_libraries(test_execute_bt_action_extended Boost::thread yaml-cpp ${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/lib/libapi_cpp.so)
|
||||
target_link_libraries(test_execute_bt_action_extended Boost::thread yaml-cpp /usr/local/lib/libapi_cpp.so)
|
||||
endif()
|
||||
|
||||
# Additional isolated ExecuteBtAction scenario tests
|
||||
@@ -302,7 +302,7 @@ if(BUILD_TESTING)
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/include
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/include
|
||||
)
|
||||
target_link_libraries(${test_name} Boost::thread yaml-cpp ${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/lib/libapi_cpp.so)
|
||||
target_link_libraries(${test_name} Boost::thread yaml-cpp /usr/local/lib/libapi_cpp.so)
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
@@ -320,7 +320,7 @@ if(BUILD_TESTING)
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/include
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/include
|
||||
)
|
||||
target_link_libraries(test_cerebrum_utils Boost::thread yaml-cpp ${CMAKE_CURRENT_SOURCE_DIR}/../thirdparty/rm_arm/lib/libapi_cpp.so)
|
||||
target_link_libraries(test_cerebrum_utils Boost::thread yaml-cpp /usr/local/lib/libapi_cpp.so)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
<BehaviorTree ID="MainTree">
|
||||
<Sequence name="root">
|
||||
<!-- Retry vision + hand until GripperControl_H succeeds -->
|
||||
<RetryUntilSuccessful name="retry_vision_hand" num_attempts="20">
|
||||
<RetryUntilSuccessful name="retry_vision_hand" num_attempts="3">
|
||||
<Sequence>
|
||||
<!-- <GripperCmd_H name="gripper_open" /> -->
|
||||
<VisionObjectRecognition_H name="VisionObjectRecognition_H" />
|
||||
|
||||
@@ -95,7 +95,7 @@ private:
|
||||
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr stats_pub_;
|
||||
std::unordered_map<std::string, geometry_msgs::msg::PoseStamped> target_pose_;
|
||||
std::vector<std::string> target_frames_{"apple", "bottle"};
|
||||
std::string target_frame_{"apple"};
|
||||
std::string target_frame_{"bottle"};
|
||||
int64_t command_id_{0};
|
||||
int64_t command_id_left_arm_ {0};
|
||||
int64_t command_id_right_arm_{0};
|
||||
|
||||
@@ -516,6 +516,8 @@ void CerebellumHooks::ConfigureServiceHooks(CerebellumNode * node)
|
||||
ConfigureMapSaveHooks(node);
|
||||
}
|
||||
|
||||
#define ENABLE_CAL_GRASP_POSE
|
||||
|
||||
void CerebellumHooks::ConfigureVisionObjectRecognitionHooks(CerebellumNode * node)
|
||||
{
|
||||
using VisionSrv = interfaces::srv::VisionObjectRecognition;
|
||||
@@ -527,7 +529,7 @@ void CerebellumHooks::ConfigureVisionObjectRecognitionHooks(CerebellumNode * nod
|
||||
node->target_pose_[tf].header.frame_id = "RightLink6";
|
||||
node->target_pose_[tf].pose = obj.pose;
|
||||
// node->target_pose_[tf].pose.position.x -= obj.grab_width / 2;
|
||||
// node->target_pose_[tf].pose.position.z -= 0.175;
|
||||
node->target_pose_[tf].pose.position.z -= 0.175;
|
||||
node->grab_width_ = obj.grab_width;
|
||||
// RCLCPP_INFO(node->get_logger(), "target_frame_: %s, grab_width_: %f, updated target_pose",
|
||||
// tf.c_str(), node->grab_width_);
|
||||
@@ -598,7 +600,7 @@ void CerebellumHooks::ConfigureVisionObjectRecognitionHooks(CerebellumNode * nod
|
||||
for (double angle : best_angles) {
|
||||
for (const auto& palm : palm_facings) {
|
||||
auto result = brain::GraspPoseCalculator::calculate(target_pos,
|
||||
target_quat, "side", angle, palm, 0.06, 0.175, node->arm_target_frame_);
|
||||
target_quat, "side", angle, palm, 0.06, 0.0, node->arm_target_frame_);
|
||||
|
||||
geometry_msgs::msg::Pose pre_grasp_msg;
|
||||
pre_grasp_msg.position.x = result.pre_grasp_pose.position.x();
|
||||
|
||||
Reference in New Issue
Block a user