Enhance grasping task handling and behavior tree configurations
- Improved `get_grasp_pose_callback` with regex for grasp pose matching and added fallback mechanisms for `pregrasp_pose` and `postgrasp_pose`. - Introduced `_create_pose_msg` and `_create_pose_msg_from_name` helper functions for dynamic transform-to-pose conversion. - Updated `GetGraspPose.srv` to include `pregrasp_pose` and `postgrasp_pose` in the service response structure. - Enhanced TF listener integration in `assembly_config_service.py` for dynamic pose retrieval and parameter management. - Added `rbs_utils_interfaces` dependency in `CMakeLists.txt` and introduced new `GetGraspPose` node for behavior tree integration. - Replaced `MoveGripper` with `GripperCommand` to improve gripper state transitions. - Refactored `MoveToPose` and `GetWorkspace` nodes for enhanced logging and parameter handling. - Updated `workspace_movement.xml` and `grasp_object.xml` with improved actions and configurations.
This commit is contained in:
parent
2fd4f3e480
commit
5c2c67567d
9 changed files with 327 additions and 67 deletions
|
@ -11,27 +11,37 @@ class MoveToPose : public RosActionNode<MoveitSendPoseAction> {
|
|||
public:
|
||||
MoveToPose(const std::string &name, const NodeConfig &conf,
|
||||
const RosNodeParams ¶ms)
|
||||
: RosActionNode<MoveitSendPoseAction>(name, conf, params) {}
|
||||
: RosActionNode<MoveitSendPoseAction>(name, conf, params) {
|
||||
|
||||
RCLCPP_INFO(this->logger(), "Starting MoveToPose");
|
||||
}
|
||||
|
||||
static BT::PortsList providedPorts() {
|
||||
return providedBasicPorts(
|
||||
{BT::InputPort<std::string>("robot_name"),
|
||||
BT::InputPort<std::shared_ptr<geometry_msgs::msg::Pose>>("pose")});
|
||||
BT::InputPort<std::shared_ptr<geometry_msgs::msg::Pose>>("pose"),
|
||||
BT::InputPort<double>("duration")});
|
||||
}
|
||||
|
||||
bool setGoal(RosActionNode::Goal &goal) override {
|
||||
RCLCPP_INFO(this->logger(), "Starting send request");
|
||||
getInput("robot_name", goal.robot_name);
|
||||
getInput("pose", goal.target_pose);
|
||||
goal.duration = 2.0;
|
||||
getInput("pose", m_target_pose);
|
||||
getInput("duration", goal.duration);
|
||||
goal.target_pose = *m_target_pose;
|
||||
return true;
|
||||
}
|
||||
|
||||
NodeStatus onResultReceived(const WrappedResult &wr) override {
|
||||
|
||||
RCLCPP_INFO(this->logger(), "Starting get response");
|
||||
if (!wr.result->success) {
|
||||
return NodeStatus::FAILURE;
|
||||
}
|
||||
return NodeStatus::SUCCESS;
|
||||
}
|
||||
private:
|
||||
std::shared_ptr<geometry_msgs::msg::Pose> m_target_pose;
|
||||
};
|
||||
|
||||
CreateRosNodePlugin(MoveToPose, "MoveToPose");
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue