diff --git a/src/ros_actor_action_server/src/Server.cpp b/src/ros_actor_action_server/src/Server.cpp index 07a76ba..9bf53e5 100644 --- a/src/ros_actor_action_server/src/Server.cpp +++ b/src/ros_actor_action_server/src/Server.cpp @@ -4,13 +4,12 @@ #include "Server.hpp" -#include - -#include -#include using namespace ros_actor_message_queue_msgs; +static const char* feedbackName; +static const char* actionName; + void sendAction(mqd_t queue, ActionMessage *message) { std::cout << "Sending action..." << std::endl; mq_send(queue, (const char *)message, sizeof(ActionMessage), 0); @@ -86,7 +85,7 @@ int main(int argc, char **argv) { currentAnimationGoalPtr->publish_feedback(feedback); }else{ currentAnimationGoalPtr->succeed(std::make_shared()); - currentAnimationGoalPtr == nullptr; + currentAnimationGoalPtr = nullptr; } } if(currentAction.state==MOVEMENT && currentMovementGoalPtr!=nullptr){ @@ -96,7 +95,7 @@ int main(int argc, char **argv) { currentMovementGoalPtr->publish_feedback(feedback); }else{ currentMovementGoalPtr->succeed(std::make_shared()); - currentMovementGoalPtr == nullptr; + currentMovementGoalPtr = nullptr; } } currentFeedback = newFeedback; @@ -106,7 +105,7 @@ int main(int argc, char **argv) { auto animationServer = rclcpp_action::create_server( node, "animation", - [¤tAction, &mutex](const rclcpp_action::GoalUUID goalUuid, const AnimationGoalPtr &animationGoal) { + [¤tAction, &mutex](__attribute__((unused)) const rclcpp_action::GoalUUID goalUuid, const AnimationGoalPtr &animationGoal) { // igndbg << "goal" << shared_mmap->currentState << std::endl; mutex.lock(); @@ -121,7 +120,7 @@ int main(int argc, char **argv) { return rclcpp_action::GoalResponse::REJECT; } }, - [actionQueue, ¤tAction, &mutex](const AnimationServerGoalPtr &animationGoalPtr) { + [actionQueue, ¤tAction, &mutex](__attribute__((unused)) const AnimationServerGoalPtr &animationGoalPtr) { if (currentAction.state == IDLE) { return rclcpp_action::CancelResponse::REJECT; } else { @@ -145,7 +144,7 @@ int main(int argc, char **argv) { auto movementServer = rclcpp_action::create_server( node, "movement", - [¤tAction, &mutex](const rclcpp_action::GoalUUID goalUuid, const MovementGoalPtr &movementGoal) { + [¤tAction, &mutex](__attribute__((unused)) const rclcpp_action::GoalUUID goalUuid, const MovementGoalPtr &movementGoal) { mutex.lock(); if (currentAction.state == IDLE) { std::cout << "Accepting..." << std::endl; @@ -160,7 +159,7 @@ int main(int argc, char **argv) { return rclcpp_action::GoalResponse::REJECT; } }, - [actionQueue, ¤tAction, &mutex](const MovementServerGoalPtr &movementGoalPtr) { + [actionQueue, ¤tAction, &mutex](__attribute__((unused)) const MovementServerGoalPtr &movementGoalPtr) { if (currentAction.state == IDLE) { return rclcpp_action::CancelResponse::REJECT; } else { @@ -184,4 +183,6 @@ int main(int argc, char **argv) { while(rclcpp::ok()){ rclcpp::spin(node); } + + } \ No newline at end of file diff --git a/src/ros_actor_action_server/src/Server.hpp b/src/ros_actor_action_server/src/Server.hpp index 4f8295b..969fe34 100644 --- a/src/ros_actor_action_server/src/Server.hpp +++ b/src/ros_actor_action_server/src/Server.hpp @@ -5,7 +5,10 @@ #ifndef BUILD_SERVER_H #define BUILD_SERVER_H +#include #include +#include +#include #include #include #include @@ -15,18 +18,14 @@ #include using namespace ros_actor_action_server_msgs; -using rclcpp_action::ServerGoalHandle; - -static char *feedbackName; -static char *actionName; #define AnimationActionServer rclcpp_action::Server #define MovementActionServer rclcpp_action::Server #define AnimationGoalPtr std::shared_ptr -#define AnimationServerGoalPtr std::shared_ptr> +#define AnimationServerGoalPtr std::shared_ptr> #define MovementGoalPtr std::shared_ptr -#define MovementServerGoalPtr std::shared_ptr> +#define MovementServerGoalPtr std::shared_ptr> #endif //BUILD_SERVER_H