diff --git a/src/ign_actor_plugin/src/ActorSystem.cpp b/src/ign_actor_plugin/src/ActorSystem.cpp index e9e2f60..b47b623 100644 --- a/src/ign_actor_plugin/src/ActorSystem.cpp +++ b/src/ign_actor_plugin/src/ActorSystem.cpp @@ -21,6 +21,7 @@ #include #include #include +#include IGNITION_ADD_PLUGIN( ignition::gazebo::ActorSystem, @@ -244,7 +245,7 @@ void ActorSystem::PreUpdate(const UpdateInfo &_info, EntityComponentManager &_ec } -void ActorSystem::client(const std::string& topic){ +void ActorSystem::rclcppServer(const std::string& topic){ rclcpp::init(0, {}); auto node = rclcpp::Node::make_shared("moveService", topic); @@ -258,109 +259,122 @@ void ActorSystem::client(const std::string& topic){ node, "animation", [this](const rclcpp_action::GoalUUID goalUuid, const AnimationGoalPtr &animationGoal) { + igndbg << "goal" << shared_mmap->currentState << std::endl; if (shared_mmap->currentState == ActorSystemState::IDLE) { pthread_mutex_lock(&shared_mmap->mutex); - //animationTarget = *animationGoal; + igndbg << "goal l" << shared_mmap->currentState << std::endl; + strcpy(shared_mmap->animation_name,animationGoal->animation_name.data()); + pthread_mutex_unlock(&shared_mmap->mutex); - return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; + return rclcpp_action::GoalResponse::ACCEPT_AND_DEFER; }else{ return rclcpp_action::GoalResponse::REJECT; } }, - [this,¤tAnimationGoalPtr](const AnimationServerGoalPtr& animationGoalPtr) { - currentAnimationGoalPtr = nullptr; + [this](const AnimationServerGoalPtr& animationGoalPtr) { + igndbg << "cancel" << shared_mmap->currentState << std::endl; if (shared_mmap->currentState == ActorSystemState::IDLE) { return rclcpp_action::CancelResponse::REJECT; }else{ pthread_mutex_lock(&shared_mmap->mutex); + shared_mmap->currentState = ActorSystemState::IDLE; pthread_mutex_unlock(&shared_mmap->mutex); + return rclcpp_action::CancelResponse::ACCEPT; } }, [this,¤tAnimationGoalPtr](const AnimationServerGoalPtr& animationGoalPtr) { + igndbg << "accepted" << shared_mmap->currentState << std::endl; pthread_mutex_lock(&shared_mmap->mutex); + igndbg << "accepted l" << shared_mmap->currentState << std::endl; + + igndbg << "got animation handle" << std::endl; currentAnimationGoalPtr = animationGoalPtr; + shared_mmap->currentState = ActorSystemState::ANIMATION; + currentAnimationGoalPtr->execute(); + pthread_mutex_unlock(&shared_mmap->mutex); + } ); - auto movementServer = rclcpp_action::create_server( node, "movement", [this](const rclcpp_action::GoalUUID goalUuid, const MovementGoalPtr &movementGoal ){ - if (shared_mmap->currentState == ActorSystemState::IDLE) { pthread_mutex_lock(&shared_mmap->mutex); - //movementTarget = *movementGoal; + shared_mmap->target_position = math::Vector3d( movementGoal->target_position[0], movementGoal->target_position[1], movementGoal->target_position[2]); shared_mmap->animation_distance = movementGoal->animation_distance; strcpy(shared_mmap->animation_name,movementGoal->animation_name.data()); + pthread_mutex_unlock(&shared_mmap->mutex); return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }else{ return rclcpp_action::GoalResponse::REJECT; } }, - [this,¤tMovementGoalPtr](const MovementServerGoalPtr& movementGoalPtr ){ - currentMovementGoalPtr = nullptr; + [this](const MovementServerGoalPtr& movementGoalPtr ){ if (shared_mmap->currentState == ActorSystemState::IDLE) { return rclcpp_action::CancelResponse::REJECT; }else{ pthread_mutex_lock(&shared_mmap->mutex); + shared_mmap->currentState = ActorSystemState::IDLE; + pthread_mutex_unlock(&shared_mmap->mutex); return rclcpp_action::CancelResponse::ACCEPT; } }, [this,¤tMovementGoalPtr](const MovementServerGoalPtr& movementGoalPtr ){ pthread_mutex_lock(&shared_mmap->mutex); + + igndbg << "got movement handle" << std::endl; currentMovementGoalPtr = movementGoalPtr; shared_mmap->currentState = ActorSystemState::MOVEMENT; + pthread_mutex_unlock(&shared_mmap->mutex); } ); #pragma clang diagnostic pop - std::thread t([this,¤tAnimationGoalPtr,¤tMovementGoalPtr]() { float progress; while(true) { read(feedback_pipe[0], &progress, sizeof(float)); - pthread_mutex_lock(&shared_mmap->mutex); + igndbg << progress << std::endl; - if(currentAnimationGoalPtr!=nullptr){ - auto feedback = std::make_shared(); - feedback->set__progress(progress); - currentAnimationGoalPtr->publish_feedback(feedback); - } - if(currentMovementGoalPtr!=nullptr){ - auto feedback = std::make_shared(); - feedback->set__progress(progress); - currentMovementGoalPtr->publish_feedback(feedback); - } - - if(progress == 1.0){ + if(progress >= 1.0f){ if(currentAnimationGoalPtr!=nullptr){ + currentAnimationGoalPtr->succeed(std::make_shared()); } if(currentMovementGoalPtr!=nullptr){ currentMovementGoalPtr->succeed(std::make_shared()); } - currentMovementGoalPtr = nullptr; - currentAnimationGoalPtr = nullptr; + }else{ + if(currentAnimationGoalPtr!=nullptr){ + auto feedback = std::make_shared(); + feedback->set__progress(progress); + currentAnimationGoalPtr->publish_feedback(feedback); + } + if(currentMovementGoalPtr!=nullptr){ + auto feedback = std::make_shared(); + feedback->set__progress(progress); + currentMovementGoalPtr->publish_feedback(feedback); + } } - pthread_mutex_unlock(&shared_mmap->mutex); + usleep(500); } }); - t.detach(); igndbg << "Spinning node..." << std::endl; @@ -423,7 +437,7 @@ void ActorSystem::Configure(const Entity &_entity, const std::shared_ptr