Motion planner (MoveIt) and Task planner (Plansys) integration

This commit is contained in:
Roman Andrianov 2023-04-30 11:46:52 +00:00 committed by Igor Brylyov
parent 0a735b87c9
commit 000ddb4831
43 changed files with 1402 additions and 379 deletions

View file

@ -0,0 +1,67 @@
#include <string>
#include <behavior_tree/BtService.hpp>
#include <rclcpp/rclcpp.hpp>
#include "rbs_skill_interfaces/srv/assemble_state.hpp"
using AssembleStateSrv = rbs_skill_interfaces::srv::AssembleState;
class AssembleState : public BtService<AssembleStateSrv>
{
public:
AssembleState(const std::string & name, const BT::NodeConfiguration &config)
: BtService<AssembleStateSrv>(name, config)
{
RCLCPP_INFO_STREAM(_node->get_logger(), "Start node.");
}
AssembleStateSrv::Request::SharedPtr populate_request()
{
auto request = std::make_shared<AssembleStateSrv::Request>();
auto state_kind = getInput<std::string>("StateKind").value();
request->req_kind = -1;
if (state_kind == "INITIALIZE")
request->req_kind = 0;
else if (state_kind == "VALIDATE")
request->req_kind = 1;
else if (state_kind == "COMPLETE")
request->req_kind = 2;
auto assemble_name = getInput<std::string>("AssembleName").value();
auto part_name = getInput<std::string>("PartName").value();
auto workspace = getInput<std::string>("WorkspaceName").value();
request->assemble_name = assemble_name;
request->part_name = part_name;
request->workspace = workspace;
return request;
}
BT::NodeStatus handle_response(AssembleStateSrv::Response::SharedPtr response)
{
// TODO: return bad status on validate process return false state
return (response->call_status = true)? BT::NodeStatus::SUCCESS: BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return providedBasicPorts({
BT::InputPort<std::string>("StateKind"),
BT::InputPort<std::string>("AssembleName"),
BT::InputPort<std::string>("PartName"),
BT::InputPort<std::string>("WorkspaceName")
});
}
private:
std::map<std::string, int> assemble_states_;
};
#include "behaviortree_cpp_v3/bt_factory.h"
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<AssembleState>("AssembleState");
}

View file

@ -0,0 +1,51 @@
#include <string>
#include <behavior_tree/BtService.hpp>
#include <rclcpp/rclcpp.hpp>
#include <component_interfaces/srv/detect_object.hpp>
using DetectObjectSrv = component_interfaces::srv::DetectObject;
class DetectObject: public BtService<DetectObjectSrv>
{
public:
DetectObject(const std::string &name, const BT::NodeConfiguration &config)
: BtService<DetectObjectSrv>(name, config)
{
RCLCPP_INFO_STREAM(_node->get_logger(), "Start node.");
}
DetectObjectSrv::Request::SharedPtr populate_request()
{
auto request = std::make_shared<DetectObjectSrv::Request>();
auto req_kind = getInput<std::string>("ReqKind").value();
if (req_kind == "DETECT")
request->req_kind = 0;
else if (req_kind == "FOLLOW")
request->req_kind = 1;
else
request->req_kind = 2;
request->object_name = getInput<std::string>("ObjectName").value();
return request;
}
BT::NodeStatus handle_response(DetectObjectSrv::Response::SharedPtr response)
{
return response->call_status? BT::NodeStatus::SUCCESS: BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return providedBasicPorts({
BT::InputPort<std::string>("ReqKind"),
BT::InputPort<std::string>("ObjectName"),
});
}
};
#include "behaviortree_cpp_v3/bt_factory.h"
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<DetectObject>("DetectObject");
}