diff --git a/src/btree_nodes/actorTree.xml b/src/btree_nodes/actorTree.xml
index 24c129b..5e80609 100644
--- a/src/btree_nodes/actorTree.xml
+++ b/src/btree_nodes/actorTree.xml
@@ -14,18 +14,25 @@
-
+
-
+
+
+ Name of animation to play
+
+
+ Name of animation to play
+ Pose to move to
+
state to set called to
diff --git a/src/btree_nodes/robotTree.xml b/src/btree_nodes/robotTree.xml
index b36ee65..418420c 100644
--- a/src/btree_nodes/robotTree.xml
+++ b/src/btree_nodes/robotTree.xml
@@ -28,6 +28,13 @@
+
+ Name of animation to play
+
+
+ Name of animation to play
+ Pose to move to
+
state to set called to
@@ -40,10 +47,6 @@
Bounds to check in
Position of object
-
- Current actor position
- Target to move actor to
-
initial position as Pose
offset as a Point
diff --git a/src/btree_nodes/src/Tree.cpp b/src/btree_nodes/src/Tree.cpp
index a0ecf55..bc9d306 100644
--- a/src/btree_nodes/src/Tree.cpp
+++ b/src/btree_nodes/src/Tree.cpp
@@ -1,4 +1,5 @@
#include "Area.h"
+#include
#include
#include
#include
@@ -19,16 +20,14 @@
#include
#include
-
-
int main(int argc, char **argv) {
rclcpp::init(argc, argv);
rclcpp::NodeOptions node_options;
node_options.automatically_declare_parameters_from_overrides(true);
auto mainNode = rclcpp::Node::make_shared("tree_general_node", node_options);
- auto blackboardVector = std::vector();
-
+ auto blackboard = Blackboard::create();
+ auto blackboardMutex = std::mutex();
rclcpp::executors::SingleThreadedExecutor executor;
@@ -108,16 +107,19 @@ int main(int argc, char **argv) {
NodeBuilder builderActorAnimation = [&actorAnimationNode](const std::string &name, const NodeConfiguration &config) {
return std::make_unique(name, config, actorAnimationNode, "/ActorPlugin/animation");
};
+ factory.registerBuilder("ActorAnimation",builderActorAnimation);
executor.add_node(actorAnimationNode);
auto actorMovementNode = rclcpp::Node::make_shared("actorMovementNode",node_options);
- NodeBuilder builderActorMovement = [&actorMovementNode, &blackboardVector](const std::string &name, const NodeConfiguration &config) {
- return std::make_unique(name, config, actorMovementNode, "/ActorPlugin/movement",[&blackboardVector](std::shared_ptr feedback){
- for (auto blackboard : blackboardVector){
- blackboard->set("actorPos", feedback);
- }
+ NodeBuilder builderActorMovement = [&actorMovementNode, &blackboard, &blackboardMutex](const std::string &name, const NodeConfiguration &config) {
+ return std::make_unique(name, config, actorMovementNode, "/ActorPlugin/movement",[&blackboard,&blackboardMutex](std::shared_ptr feedback){
+ blackboardMutex.lock();
+ blackboard->set("actorPos", std::make_shared(feedback->current));
+ blackboardMutex.unlock();
});
};
+ factory.registerBuilder("ActorMovement",builderActorMovement);
+ executor.add_node(actorMovementNode);
bool called = false;
auto IsCalled = [&called](__attribute__((unused)) TreeNode& parent_node) -> NodeStatus{
@@ -138,24 +140,19 @@ int main(int argc, char **argv) {
std::cout << "Creating tree." << std::endl;
- Tree actorTree = factory.createTreeFromFile("/home/ros/workspace/src/btree_nodes/actorTree.xml");
- Tree robotTree = factory.createTreeFromFile("/home/ros/workspace/src/btree_nodes/robotTree.xml");
-
- blackboardVector.push_back(actorTree.rootBlackboard());
- blackboardVector.push_back(robotTree.rootBlackboard());
+ Tree actorTree = factory.createTreeFromFile("/home/ros/workspace/src/btree_nodes/actorTree.xml",blackboard);
+ Tree robotTree = factory.createTreeFromFile("/home/ros/workspace/src/btree_nodes/robotTree.xml",blackboard);
auto init = std::make_shared();
init->position.x = 6.0;
init->position.y = 6.0;
- for (auto blackboard : blackboardVector){
- blackboard->set("safeArea",safeArea);
- blackboard->set("warningArea",warningArea);
- blackboard->set("unsafeArea",unsafeArea);
- blackboard->set("negativeYTable",negativeYTable);
- blackboard->set("positiveYTable",positiveYTable);
- blackboard->set("actorPos", init);
- }
+ blackboard->set("safeArea",safeArea);
+ blackboard->set("warningArea",warningArea);
+ blackboard->set("unsafeArea",unsafeArea);
+ blackboard->set("negativeYTable",negativeYTable);
+ blackboard->set("positiveYTable",positiveYTable);
+ blackboard->set("actorPos", init);
std::cout << "Starting subscriber." << std::endl;
@@ -166,13 +163,13 @@ int main(int argc, char **argv) {
std::cout << "Executor stopped." << std::endl;
}).detach();
- executor.add_node(actorMovementNode);
-
std::cout << "Looping." << std::endl;
while (rclcpp::ok()) {
+ blackboardMutex.lock();
+ actorTree.tickRoot();
robotTree.tickRoot();
- std::this_thread::sleep_for(std::chrono::milliseconds(20));
+ blackboardMutex.unlock();
}
std::cout << "End." << std::endl;
diff --git a/src/btree_nodes/src/nodes/ActorMovement.cpp b/src/btree_nodes/src/nodes/ActorMovement.cpp
index dc18a1f..d84873b 100644
--- a/src/btree_nodes/src/nodes/ActorMovement.cpp
+++ b/src/btree_nodes/src/nodes/ActorMovement.cpp
@@ -3,6 +3,7 @@
//
#include "ActorMovement.h"
+#include
ActorMovement::ActorMovement(const std::string &name, const BT::NodeConfiguration &config, std::shared_ptr node, const std::string &actionName, std::function)> positionCallback)
@@ -37,30 +38,40 @@ BT::NodeStatus ActorMovement::onStart() {
goal.animation_speed=1.0;
goal.target = *target;
-
-
auto send_goal_options = Client::SendGoalOptions();
- send_goal_options.feedback_callback = [=](__attribute__((unused)) std::shared_ptr> goal_handle, const std::shared_ptr feedback) {
+ send_goal_options.feedback_callback = [&](__attribute__((unused)) std::shared_ptr> goal_handle, std::shared_ptr feedback) {
positionCallback(feedback);
};
- send_goal_options.result_callback = [=](const ClientGoalHandle::WrappedResult & parameter) {
+ send_goal_options.result_callback = [&](ClientGoalHandle::WrappedResult parameter) {
mutex.lock();
if(parameter.code == ResultCode::SUCCEEDED){
+ std::cout << "Success?" << std::endl;
result = BT::NodeStatus::SUCCESS;
}else{
+ std::cout << "Failure?" << std::endl;
result = BT::NodeStatus::FAILURE;
}
mutex.unlock();
};
+ send_goal_options.goal_response_callback = [&](ClientGoalHandle::SharedPtr parameter){
+ if(!parameter){
+ std::cout << "ActorMovement rejected by server." << std::endl;
+ result = BT::NodeStatus::FAILURE;
+ }
+ };
client->async_send_goal(goal,send_goal_options);
-
+
+ result = BT::NodeStatus::RUNNING;
return BT::NodeStatus::RUNNING;
}
BT::NodeStatus ActorMovement::onRunning() {
mutex.lock();
auto status = result;
+ if(result != BT::NodeStatus::RUNNING){
+ result = BT::NodeStatus::IDLE;
+ }
mutex.unlock();
return status;
}
@@ -68,4 +79,5 @@ BT::NodeStatus ActorMovement::onRunning() {
void ActorMovement::onHalted() {
std::cout << "halted move" << std::endl;
client->async_cancel_all_goals();
+ result = BT::NodeStatus::IDLE;
}
diff --git a/src/btree_nodes/src/nodes/MoveConnection.cpp b/src/btree_nodes/src/nodes/MoveConnection.cpp
index dc1c0a2..e55e6c2 100644
--- a/src/btree_nodes/src/nodes/MoveConnection.cpp
+++ b/src/btree_nodes/src/nodes/MoveConnection.cpp
@@ -4,6 +4,8 @@
#include "MoveConnection.h"
+MoveConnection::MoveConnection(const std::shared_ptr &node, const std::string &planningGroup) : moveGroup(node,planningGroup) {}
+
void MoveConnection::planAndExecute(const std::shared_ptr &pose,
const std::function &callback) {
std::cout<<"planAndExecute."< &node, const std::string &planningGroup) : moveGroup(node,planningGroup) {
-
-}
-
void MoveConnection::stop() {
std::cout<<"Stopping MoveConnection"<
using namespace ros_actor_message_queue_msgs;
static const char* feedbackName;
static const char* actionName;
+static std::mutex feedbackMutex;
+static std::mutex rosMutex;
+
+static std::condition_variable stateCondition;
+
+static ActionMessage cancelAction;
+
void sendAction(mqd_t queue, ActionMessage *message) {
std::cout << "Sending action..." << std::endl;
mq_send(queue, (const char *)message, sizeof(ActionMessage), 0);
std::cout << "Sent action" << std::endl;
}
+void waitForState(FeedbackMessage *currentFeedback,ActorPluginState state){
+ std::unique_lock lock(feedbackMutex);
+ stateCondition.wait(lock,[¤tFeedback,state]{return currentFeedback->state==state;});
+
+ return;
+}
+
int main(int argc, char **argv) {
+ cancelAction.state = IDLE;
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("ActorPlugin", "ActorPlugin");
@@ -64,90 +79,89 @@ int main(int argc, char **argv) {
FeedbackMessage currentFeedback;
ActionMessage currentAction;
- std::mutex mutex;
- currentAction.state = IDLE;
-
- std::thread([feedbackQueue, ¤tAnimationGoalPtr, ¤tMovementGoalPtr, ¤tFeedback, ¤tAction, &mutex] {
+ std::thread([feedbackQueue, ¤tAnimationGoalPtr, ¤tMovementGoalPtr, ¤tFeedback, ¤tAction] {
while (true) {
FeedbackMessage newFeedback;
if(mq_receive(feedbackQueue, (char *)&newFeedback, sizeof(ros_actor_message_queue_msgs::FeedbackMessage), nullptr)==-1){
perror(nullptr);
}
- mutex.lock();
- if (newFeedback.state != currentFeedback.state) {
- currentAction.state = newFeedback.state;
+ feedbackMutex.lock();
+ if(newFeedback.state==ANIMATION && currentAnimationGoalPtr!=nullptr){
+ auto feedback = std::make_shared();
+ feedback->progress = newFeedback.progress;
+ currentAnimationGoalPtr->publish_feedback(feedback);
}
- if(currentAction.state==ANIMATION && currentAnimationGoalPtr!=nullptr){
- if(newFeedback.progress<1){
- auto feedback = std::make_shared();
- feedback->progress = newFeedback.progress;
- currentAnimationGoalPtr->publish_feedback(feedback);
- }else{
+ if(newFeedback.state==MOVEMENT && currentMovementGoalPtr!=nullptr){
+ auto feedback = std::make_shared();
+ feedback->current = newFeedback.current;
+ currentMovementGoalPtr->publish_feedback(feedback);
+ }
+ if (newFeedback.state==IDLE) {
+ if(currentFeedback.state==ANIMATION && currentAnimationGoalPtr!=nullptr){
currentAnimationGoalPtr->succeed(std::make_shared());
currentAnimationGoalPtr = nullptr;
}
- }
- if(currentAction.state==MOVEMENT && currentMovementGoalPtr!=nullptr){
- if(newFeedback.progress<1){
- auto feedback = std::make_shared();
- feedback->current = newFeedback.current;
- currentMovementGoalPtr->publish_feedback(feedback);
- }else{
+ if(currentFeedback.state==MOVEMENT && currentMovementGoalPtr!=nullptr){
currentMovementGoalPtr->succeed(std::make_shared());
currentMovementGoalPtr = nullptr;
}
}
currentFeedback = newFeedback;
- mutex.unlock();
+ feedbackMutex.unlock();
+ stateCondition.notify_all();
}
}).detach();
auto animationServer = rclcpp_action::create_server(
node, "animation",
- [¤tAction, &mutex](__attribute__((unused)) const rclcpp_action::GoalUUID goalUuid, const AnimationGoalPtr &animationGoal) {
+ [¤tAction, ¤tFeedback](__attribute__((unused)) const rclcpp_action::GoalUUID goalUuid, const AnimationGoalPtr &animationGoal) {
// igndbg << "goal" << shared_mmap->currentState << std::endl;
- mutex.lock();
+ rosMutex.lock();
- if (currentAction.state == IDLE) {
+ if (currentFeedback.state == IDLE) {
std::cout << "Accepting..." << std::endl;
+
strcpy(currentAction.animationName, animationGoal->animation_name.data());
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
} else {
std::cout << "Rejecting..." << std::endl;
- mutex.unlock();
+ rosMutex.unlock();
return rclcpp_action::GoalResponse::REJECT;
}
},
- [actionQueue, ¤tAction, &mutex](__attribute__((unused)) const AnimationServerGoalPtr &animationGoalPtr) {
- if (currentAction.state == IDLE) {
+ [actionQueue, ¤tFeedback](__attribute__((unused)) const AnimationServerGoalPtr &animationGoalPtr) {
+ if (currentFeedback.state == IDLE) {
return rclcpp_action::CancelResponse::REJECT;
} else {
- mutex.lock();
-
- currentAction.state = IDLE;
- sendAction(actionQueue, ¤tAction);
-
- mutex.unlock();
+ rosMutex.lock();
+ sendAction(actionQueue, &cancelAction);
+
+ waitForState(¤tFeedback, IDLE);
+ rosMutex.unlock();
return rclcpp_action::CancelResponse::ACCEPT;
}
},
- [actionQueue, ¤tAction, ¤tAnimationGoalPtr, &mutex](const AnimationServerGoalPtr &animationGoalPtr) {
+ [actionQueue, ¤tAction, ¤tAnimationGoalPtr, ¤tFeedback](const AnimationServerGoalPtr &animationGoalPtr) {
+ feedbackMutex.lock();
currentAnimationGoalPtr = animationGoalPtr;
+ feedbackMutex.unlock();
currentAction.state = ANIMATION;
sendAction(actionQueue, ¤tAction);
- mutex.unlock();
+ waitForState(¤tFeedback, ANIMATION);
+ rosMutex.unlock();
});
auto movementServer = rclcpp_action::create_server(
node, "movement",
- [¤tAction, &mutex](__attribute__((unused)) const rclcpp_action::GoalUUID goalUuid, const MovementGoalPtr &movementGoal) {
- mutex.lock();
- if (currentAction.state == IDLE) {
+ [¤tAction, ¤tFeedback](__attribute__((unused)) const rclcpp_action::GoalUUID goalUuid, const MovementGoalPtr &movementGoal) {
+ rosMutex.lock();
+ if (currentFeedback.state == IDLE) {
std::cout << "Accepting..." << std::endl;
+
currentAction.target = movementGoal->target;
currentAction.animationDistance = movementGoal->animation_distance;
strcpy(currentAction.animationName, movementGoal->animation_name.data());
@@ -155,34 +169,35 @@ int main(int argc, char **argv) {
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
} else {
std::cout << "Rejecting..." << std::endl;
- mutex.unlock();
+ rosMutex.unlock();
return rclcpp_action::GoalResponse::REJECT;
}
},
- [actionQueue, ¤tAction, &mutex](__attribute__((unused)) const MovementServerGoalPtr &movementGoalPtr) {
- if (currentAction.state == IDLE) {
+ [actionQueue, ¤tFeedback](__attribute__((unused)) const MovementServerGoalPtr &movementGoalPtr) {
+ if (currentFeedback.state == IDLE) {
return rclcpp_action::CancelResponse::REJECT;
} else {
- mutex.lock();
-
- currentAction.state = IDLE;
- sendAction(actionQueue, ¤tAction);
-
- mutex.unlock();
+ rosMutex.lock();
+ sendAction(actionQueue, &cancelAction);
+
+ waitForState(¤tFeedback, IDLE);
+ rosMutex.unlock();
+
return rclcpp_action::CancelResponse::ACCEPT;
}
},
- [actionQueue, ¤tAction, ¤tMovementGoalPtr, &mutex](const MovementServerGoalPtr &movementGoalPtr) {
+ [actionQueue, ¤tAction, ¤tFeedback, ¤tMovementGoalPtr](const MovementServerGoalPtr &movementGoalPtr) {
+ feedbackMutex.lock();
currentMovementGoalPtr = movementGoalPtr;
+ feedbackMutex.unlock();
currentAction.state = MOVEMENT;
sendAction(actionQueue, ¤tAction);
-
- mutex.unlock();
+
+ waitForState(¤tFeedback, MOVEMENT);
+ rosMutex.unlock();
});
while(rclcpp::ok()){
rclcpp::spin(node);
}
-
-
}
\ No newline at end of file