diff --git a/build.sh b/build.sh index 748846a..69676d7 100755 --- a/build.sh +++ b/build.sh @@ -1,4 +1,4 @@ #!/bin/bash pushd "$(dirname "$0")" || exit -colcon build --event-handlers console_cohesion+ --cmake-args -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -G Ninja +colcon build --event-handlers console_cohesion+ --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -G Ninja popd || exit diff --git a/gz_ros2_control b/gz_ros2_control deleted file mode 160000 index 55dd768..0000000 --- a/gz_ros2_control +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 55dd7680ff7234c825efa1dd0c104e5629448972 diff --git a/src/btree/src/Extensions.cpp b/src/btree/src/Extensions.cpp index f4827ab..d90a6d9 100644 --- a/src/btree/src/Extensions.cpp +++ b/src/btree/src/Extensions.cpp @@ -2,11 +2,10 @@ // Created by bastian on 28.02.22. // -#include "Area.h" -#include +#include "Extensions.hpp" namespace BT { - template<> + template<> [[nodiscard]] std::shared_ptr convertFromString(StringView str) { auto split = splitString(str, ','); if (split.size() != 2) { @@ -19,7 +18,7 @@ namespace BT { return pos; } - template<> + template<> [[nodiscard]] std::shared_ptr convertFromString(StringView str) { auto parts = splitString(str, '|'); if (parts.size() < 3) { @@ -35,7 +34,7 @@ namespace BT { return output; } - template<> + template<> [[nodiscard]] std::shared_ptr convertFromString(StringView str) { auto parts = splitString(str, ','); if (!(parts.size() == 3 || parts.size() == 7)) { @@ -61,7 +60,7 @@ namespace BT { return pose; } - template<> + template<> [[nodiscard]] std::shared_ptr convertFromString(StringView str) { auto parts = splitString(str, ','); if (parts.size() != 3) { @@ -76,7 +75,7 @@ namespace BT { return point; } - template<> + template<> [[nodiscard]] std::shared_ptr convertFromString(StringView str) { auto parts = splitString(str, ','); if (parts.size() != 4) { diff --git a/src/btree/src/Extensions.hpp b/src/btree/src/Extensions.hpp new file mode 100644 index 0000000..cdca2c2 --- /dev/null +++ b/src/btree/src/Extensions.hpp @@ -0,0 +1,27 @@ +// +// Created by bastian on 28.02.22. +// +#ifndef BUILD_EXTENSIONS_H +#define BUILD_EXTENSIONS_H + +#include "Area.h" +#include + +namespace BT { + template<> [[nodiscard]] + std::shared_ptr convertFromString(StringView str); + + template<> [[nodiscard]] + std::shared_ptr convertFromString(StringView str); + + template<> [[nodiscard]] + std::shared_ptr convertFromString(StringView str); + + template<> [[nodiscard]] + std::shared_ptr convertFromString(StringView str); + + template<> [[nodiscard]] + std::shared_ptr convertFromString(StringView str); +} + +#endif //BUILD_EXTENSIONS_H \ No newline at end of file diff --git a/src/btree/src/Tree.cpp b/src/btree/src/Tree.cpp index 918c7c4..0b04fbd 100644 --- a/src/btree/src/Tree.cpp +++ b/src/btree/src/Tree.cpp @@ -1,7 +1,10 @@ +#include "Extensions.hpp" #include "Area.h" #include #include #include +#include +#include #include #include #include @@ -20,9 +23,13 @@ #include #include +using namespace BT; + int main(int argc, char **argv) { rclcpp::init(argc, argv); rclcpp::NodeOptions node_options; + + convertFromString>("0,0,0"); auto mainNode = rclcpp::Node::make_shared("tree_general_node", node_options); @@ -51,12 +58,12 @@ int main(int argc, char **argv) { auto connection = std::make_shared(moveNode, "arm"); executor.add_node(moveNode); - factory.registerBuilder("RobotMove", [&connection](const std::string &name, const NodeConfiguration &config) { - return std::make_unique(name, config, &connection); + factory.registerBuilder("RobotMove", [connection](const std::string &name, const NodeConfiguration &config) { + return std::make_unique(name, config, connection); }); - factory.registerBuilder("SetRobotVelocity", [&connection](const std::string &name, const NodeConfiguration &config) { - return std::make_unique(name, config, &connection); + factory.registerBuilder("SetRobotVelocity", [connection](const std::string &name, const NodeConfiguration &config) { + return std::make_unique(name, config, connection); }); diff --git a/src/btree/src/nodes/ActorAnimation.cpp b/src/btree/src/nodes/ActorAnimation.cpp index eba6da3..305faa3 100644 --- a/src/btree/src/nodes/ActorAnimation.cpp +++ b/src/btree/src/nodes/ActorAnimation.cpp @@ -18,7 +18,7 @@ BT::PortsList ActorAnimation::providedPorts() { } BT::NodeStatus ActorAnimation::onStart() { - std::cout << "started animation" << std::endl; + std::cout << "started actor animation" << std::endl; ros_actor_action_server_msgs::action::Animation::Goal goal; @@ -37,8 +37,10 @@ BT::NodeStatus ActorAnimation::onStart() { send_goal_options.result_callback = [=](const ClientGoalHandle::WrappedResult & parameter) { mutex.lock(); if(parameter.code == ResultCode::SUCCEEDED){ + std::cout << "finished actor animation" << std::endl; result = BT::NodeStatus::SUCCESS; }else{ + std::cout << "failed actor animation" << std::endl; result = BT::NodeStatus::FAILURE; } mutex.unlock(); @@ -53,14 +55,12 @@ BT::NodeStatus ActorAnimation::onStart() { BT::NodeStatus ActorAnimation::onRunning() { mutex.lock(); auto status = result; - if(result != BT::NodeStatus::RUNNING){ - result = BT::NodeStatus::IDLE; - } mutex.unlock(); return status; } void ActorAnimation::onHalted() { - std::cout << "halted animation" << std::endl; + std::cout << "halted actor animation" << std::endl; client->async_cancel_all_goals(); + result = BT::NodeStatus::FAILURE; } diff --git a/src/btree/src/nodes/ActorMovement.cpp b/src/btree/src/nodes/ActorMovement.cpp index 3a0362a..fa1d8b1 100644 --- a/src/btree/src/nodes/ActorMovement.cpp +++ b/src/btree/src/nodes/ActorMovement.cpp @@ -2,6 +2,7 @@ // Created by bastian on 26.03.22. // +#include "../Extensions.hpp" #include "ActorMovement.h" #include #include @@ -22,7 +23,7 @@ BT::PortsList ActorMovement::providedPorts() { } BT::NodeStatus ActorMovement::onStart() { - std::cout << "started moving" << std::endl; + std::cout << "started actor movement" << std::endl; ros_actor_action_server_msgs::action::Movement::Goal goal; @@ -51,10 +52,10 @@ BT::NodeStatus ActorMovement::onStart() { send_goal_options.result_callback = [&](ClientGoalHandle::WrappedResult parameter) { mutex.lock(); if(parameter.code == ResultCode::SUCCEEDED){ - std::cout << "Success?" << std::endl; + std::cout << "finished actor movement" << std::endl; result = BT::NodeStatus::SUCCESS; }else{ - std::cout << "Failure?" << std::endl; + std::cout << "failed actor movement" << std::endl; result = BT::NodeStatus::FAILURE; } mutex.unlock(); @@ -81,15 +82,12 @@ BT::NodeStatus ActorMovement::onStart() { BT::NodeStatus ActorMovement::onRunning() { mutex.lock(); auto status = result; - if(result != BT::NodeStatus::RUNNING){ - result = BT::NodeStatus::IDLE; - } mutex.unlock(); return status; } void ActorMovement::onHalted() { - std::cout << "halted move" << std::endl; + std::cout << "halted actor movement" << std::endl; client->async_cancel_all_goals(); - result = BT::NodeStatus::IDLE; + result = BT::NodeStatus::FAILURE; } diff --git a/src/btree/src/nodes/GenerateXYPose.cpp b/src/btree/src/nodes/GenerateXYPose.cpp index 4ace1c4..51a156e 100644 --- a/src/btree/src/nodes/GenerateXYPose.cpp +++ b/src/btree/src/nodes/GenerateXYPose.cpp @@ -83,7 +83,6 @@ BT::NodeStatus BT::GenerateXYPose::tick() { randomPose->orientation.y = 0; randomPose->orientation.z = 0; - printf("Generated Target: %f %f\n", pos.x, pos.y); setOutput>("pose", randomPose); return NodeStatus::SUCCESS; } diff --git a/src/btree/src/nodes/InterruptableSequence.cpp b/src/btree/src/nodes/InterruptableSequence.cpp index 8d9dab8..84a6b7a 100644 --- a/src/btree/src/nodes/InterruptableSequence.cpp +++ b/src/btree/src/nodes/InterruptableSequence.cpp @@ -18,7 +18,7 @@ BT::NodeStatus BT::InterruptableSequence::tick() { setStatus(NodeStatus::RUNNING); if(result==NodeStatus::FAILURE){ - haltChildren(); + resetChildren(); position=0; return NodeStatus::FAILURE; } @@ -26,7 +26,7 @@ BT::NodeStatus BT::InterruptableSequence::tick() { if(result==NodeStatus::SUCCESS){ position++; if(position>=children_nodes_.size()){ - haltChildren(); + resetChildren(); position=0; return NodeStatus::SUCCESS; } diff --git a/src/btree/src/nodes/MoveConnection.cpp b/src/btree/src/nodes/MoveConnection.cpp index 36ebe1b..6b14da3 100644 --- a/src/btree/src/nodes/MoveConnection.cpp +++ b/src/btree/src/nodes/MoveConnection.cpp @@ -11,20 +11,19 @@ void MoveConnection::planAndExecute(const std::shared_ptr lastTarget = nullptr; std::function lastCallback = [](__attribute__((unused))bool finished) {}; diff --git a/src/btree/src/nodes/RobotMove.cpp b/src/btree/src/nodes/RobotMove.cpp index 0614ca7..6387e63 100644 --- a/src/btree/src/nodes/RobotMove.cpp +++ b/src/btree/src/nodes/RobotMove.cpp @@ -5,7 +5,7 @@ #include "RobotMove.h" BT::RobotMove::RobotMove(const std::string &name, const BT::NodeConfiguration &config, - std::shared_ptr *connection) + std::shared_ptr connection) : StatefulActionNode(name, config) { this->connection = connection; } @@ -20,7 +20,7 @@ BT::NodeStatus BT::RobotMove::onStart() { printf("X:%f Y:%f Z:%f\n",pose->position.x,pose->position.y,pose->position.z); printf("W:%f X:%f Y:%f Z:%f\n",pose->orientation.w,pose->orientation.x,pose->orientation.y,pose->orientation.z); asyncResult = NodeStatus::RUNNING; - connection->get()->planAndExecute(pose,[this](bool finished){ + connection->planAndExecute(pose,[this](bool finished){ if(finished){ printf("Finished move."); asyncResult = NodeStatus::SUCCESS; @@ -42,7 +42,7 @@ BT::NodeStatus BT::RobotMove::onRunning() { void BT::RobotMove::onHalted() { std::cout << "Halting RobotMove" << std::endl; - connection->get()->stop(); + connection->stop(); asyncResult=NodeStatus::FAILURE; } diff --git a/src/btree/src/nodes/RobotMove.h b/src/btree/src/nodes/RobotMove.h index c37846e..7ee0dbd 100644 --- a/src/btree/src/nodes/RobotMove.h +++ b/src/btree/src/nodes/RobotMove.h @@ -16,12 +16,12 @@ namespace BT { class RobotMove : public StatefulActionNode { private: - std::shared_ptr *connection; + std::shared_ptr connection; NodeStatus asyncResult = NodeStatus::FAILURE; public: RobotMove(const std::string &name, const BT::NodeConfiguration &config, - std::shared_ptr *connection); + std::shared_ptr connection); NodeStatus onStart() override; diff --git a/src/btree/src/nodes/SetRobotVelocity.cpp b/src/btree/src/nodes/SetRobotVelocity.cpp index fa4a9a2..b211b34 100644 --- a/src/btree/src/nodes/SetRobotVelocity.cpp +++ b/src/btree/src/nodes/SetRobotVelocity.cpp @@ -11,7 +11,7 @@ BT::NodeStatus BT::SetRobotVelocity::tick() { std::cout<<"No velocity given."<get()->setSpeedMultiplier(velocity); + connection->setSpeedMultiplier(velocity); return NodeStatus::SUCCESS; } @@ -21,7 +21,7 @@ BT::PortsList BT::SetRobotVelocity::providedPorts() { }; } -BT::SetRobotVelocity::SetRobotVelocity(const std::string &name, const BT::NodeConfiguration &config, std::shared_ptr *connection) : SyncActionNode( +BT::SetRobotVelocity::SetRobotVelocity(const std::string &name, const BT::NodeConfiguration &config, std::shared_ptr connection) : SyncActionNode( name, config) { this->connection = connection; } diff --git a/src/btree/src/nodes/SetRobotVelocity.h b/src/btree/src/nodes/SetRobotVelocity.h index 7324050..217db5d 100644 --- a/src/btree/src/nodes/SetRobotVelocity.h +++ b/src/btree/src/nodes/SetRobotVelocity.h @@ -11,11 +11,11 @@ namespace BT { class SetRobotVelocity: public SyncActionNode { private: - std::shared_ptr *connection{}; + std::shared_ptr connection; public: SetRobotVelocity(const std::string &name, const NodeConfiguration &config, - std::shared_ptr *connection); + std::shared_ptr connection); static PortsList providedPorts(); diff --git a/src/btree/src/nodes/WeightedRandomNode.cpp b/src/btree/src/nodes/WeightedRandomNode.cpp index 7cf0589..7aa9a05 100644 --- a/src/btree/src/nodes/WeightedRandomNode.cpp +++ b/src/btree/src/nodes/WeightedRandomNode.cpp @@ -16,7 +16,7 @@ void WeightedRandomNode::halt() { NodeStatus WeightedRandomNode::tick() { if (select_next) { - const size_t children_count = children_nodes_.size(); + size_t children_count = children_nodes_.size(); std::string weightString; @@ -53,14 +53,18 @@ NodeStatus WeightedRandomNode::tick() { } selected_child_index = i; + + std::cout<< "Selected child:" << selected_child_index <executeTick(); - + NodeStatus child_status = current_child_node->executeTick(); + if (child_status != NodeStatus::RUNNING) { select_next = true; + resetChildren(); } return child_status; diff --git a/src/btree/trees/actorTreeCoex.xml b/src/btree/trees/actorTreeCoex.xml index ad4cc9b..c386167 100644 --- a/src/btree/trees/actorTreeCoex.xml +++ b/src/btree/trees/actorTreeCoex.xml @@ -1,7 +1,7 @@ - + @@ -10,7 +10,7 @@ - + diff --git a/src/btree/trees/robotTreeCoex.xml b/src/btree/trees/robotTreeCoex.xml index 7c1319e..e3bb1f1 100644 --- a/src/btree/trees/robotTreeCoex.xml +++ b/src/btree/trees/robotTreeCoex.xml @@ -10,16 +10,41 @@ - - + + - - + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/src/gz_ros2_control b/src/gz_ros2_control index 55dd768..a295d33 160000 --- a/src/gz_ros2_control +++ b/src/gz_ros2_control @@ -1 +1 @@ -Subproject commit 55dd7680ff7234c825efa1dd0c104e5629448972 +Subproject commit a295d3319727b3e5ad1b0fa7dbfd34f3369655cf diff --git a/src/ign_actor_plugin/src/ActorSystem.cpp b/src/ign_actor_plugin/src/ActorSystem.cpp index f4f9195..a1a46e4 100644 --- a/src/ign_actor_plugin/src/ActorSystem.cpp +++ b/src/ign_actor_plugin/src/ActorSystem.cpp @@ -68,12 +68,8 @@ void ActorSystem::switchAnimation(EntityComponentManager &_ecm, char *animationN } double Angle(ignition::math::Quaterniond a,ignition::math::Quaterniond b){ - auto dot = fmin(abs(a.Dot(b)),1.0); - if(dot > 0.999999){ - return 0.0; - }else{ - return acos(dot) * 2; - } + auto dot = fmin(abs(a.Normalized().Dot(b.Normalized())),1.0); + return acos(dot); } void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ecm) { @@ -184,6 +180,8 @@ void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ec } movementDetails.rotateToEndDuration = Angle(movementDetails.targetDiff.Rot(),movementDetails.target.Rot()) / turnSpeed; + + igndbg << movementDetails.rotateToTargetDuration << " " <180 - $(find ign_actor_plugin)/animation/walk.dae + $(find ign_actor_plugin)/animation/standing_walk.dae 1.0 diff --git a/src/ros_actor_action_server/src/Server.cpp b/src/ros_actor_action_server/src/Server.cpp index f59f54e..ac981f2 100644 --- a/src/ros_actor_action_server/src/Server.cpp +++ b/src/ros_actor_action_server/src/Server.cpp @@ -99,10 +99,12 @@ int main(int argc, char **argv) { } if (newFeedback.state==IDLE) { if(currentFeedback.state==ANIMATION && currentAnimationGoalPtr!=nullptr){ + std::cout << "Finished Animation. " << std::endl; currentAnimationGoalPtr->succeed(std::make_shared()); currentAnimationGoalPtr = nullptr; } if(currentFeedback.state==MOVEMENT && currentMovementGoalPtr!=nullptr){ + std::cout << "Finished Movement. " << std::endl; currentMovementGoalPtr->succeed(std::make_shared()); currentMovementGoalPtr = nullptr; } @@ -120,14 +122,14 @@ int main(int argc, char **argv) { rosMutex.lock(); if (currentFeedback.state == IDLE) { - std::cout << "Accepting..." << std::endl; + std::cout << "Accepting Animation..." << std::endl; currentAction.animationSpeed = animationGoal->animation_speed; strcpy(currentAction.animationName, animationGoal->animation_name.data()); return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; } else { - std::cout << "Rejecting..." << std::endl; + std::cout << "Rejecting Animation..." << std::endl; rosMutex.unlock(); return rclcpp_action::GoalResponse::REJECT; } @@ -137,9 +139,11 @@ int main(int argc, char **argv) { return rclcpp_action::CancelResponse::REJECT; } else { rosMutex.lock(); + std::cout << "Cancelling Animation..." << std::endl; sendAction(actionQueue, &cancelAction); waitForState(¤tFeedback, IDLE); + std::cout << "Cancelled Animation..." << std::endl; rosMutex.unlock(); return rclcpp_action::CancelResponse::ACCEPT; @@ -161,7 +165,7 @@ int main(int argc, char **argv) { [¤tAction, ¤tFeedback](__attribute__((unused)) const rclcpp_action::GoalUUID goalUuid, const MovementGoalPtr &movementGoal) { rosMutex.lock(); if (currentFeedback.state == IDLE) { - std::cout << "Accepting..." << std::endl; + std::cout << "Accepting Movement..." << std::endl; currentAction.target = movementGoal->target; currentAction.animationSpeed = movementGoal->animation_distance; @@ -169,7 +173,7 @@ int main(int argc, char **argv) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; } else { - std::cout << "Rejecting..." << std::endl; + std::cout << "Rejecting Movement..." << std::endl; rosMutex.unlock(); return rclcpp_action::GoalResponse::REJECT; } @@ -179,9 +183,11 @@ int main(int argc, char **argv) { return rclcpp_action::CancelResponse::REJECT; } else { rosMutex.lock(); + std::cout << "Cancelling Movement..." << std::endl; sendAction(actionQueue, &cancelAction); waitForState(¤tFeedback, IDLE); + std::cout << "Cancelled Movement..." << std::endl; rosMutex.unlock(); return rclcpp_action::CancelResponse::ACCEPT; diff --git a/test.sh b/test.sh index afbf897..cc3478e 100755 --- a/test.sh +++ b/test.sh @@ -1,2 +1,2 @@ -ros2 action send_goal /ActorPlugin/animation ign_actor_plugin_msgs/action/Animation "{animation_name: 'walk', animation_speed: 1.0}" -ros2 action send_goal /ActorPlugin/movement ros_actor_action_server_msgs/action/Movement '{animation_name: "walk", animation_speed: 1.0, animation_distance: 1.5, target: {orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0}, position: {x: 2.0, y: 0.0, z: 0.0}}}' \ No newline at end of file +ros2 action send_goal /ActorPlugin/animation ign_actor_plugin_msgs/action/Animation "{animation_name: 'standing_walk', animation_speed: 1.0}" +ros2 action send_goal /ActorPlugin/movement ros_actor_action_server_msgs/action/Movement '{animation_name: "standing_walk", animation_speed: 1.0, animation_distance: 1.5, target: {orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0}, position: {x: 2.0, y: 0.0, z: 0.0}}}' \ No newline at end of file