Fixed compiler warnings
This commit is contained in:
parent
156af3db6b
commit
b654b06945
@ -4,13 +4,12 @@
|
||||
|
||||
#include "Server.hpp"
|
||||
|
||||
#include <mqueue.h>
|
||||
|
||||
#include <cstdio>
|
||||
#include <rclcpp/logger.hpp>
|
||||
|
||||
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<ros_actor_action_server_msgs::action::Animation_Result>());
|
||||
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<ros_actor_action_server_msgs::action::Movement_Result>());
|
||||
currentMovementGoalPtr == nullptr;
|
||||
currentMovementGoalPtr = nullptr;
|
||||
}
|
||||
}
|
||||
currentFeedback = newFeedback;
|
||||
@ -106,7 +105,7 @@ int main(int argc, char **argv) {
|
||||
|
||||
auto animationServer = rclcpp_action::create_server<action::Animation>(
|
||||
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<action::Movement>(
|
||||
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);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
@ -5,7 +5,10 @@
|
||||
#ifndef BUILD_SERVER_H
|
||||
#define BUILD_SERVER_H
|
||||
|
||||
#include <cstdio>
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <rclcpp/utilities.hpp>
|
||||
#include <rclcpp/logger.hpp>
|
||||
#include <rclcpp_action/rclcpp_action.hpp>
|
||||
#include <ros_actor_action_server_msgs/action/animation.hpp>
|
||||
#include <ros_actor_action_server_msgs/action/movement.hpp>
|
||||
@ -15,18 +18,14 @@
|
||||
#include <mqueue.h>
|
||||
|
||||
using namespace ros_actor_action_server_msgs;
|
||||
using rclcpp_action::ServerGoalHandle;
|
||||
|
||||
static char *feedbackName;
|
||||
static char *actionName;
|
||||
|
||||
#define AnimationActionServer rclcpp_action::Server<action::Animation>
|
||||
#define MovementActionServer rclcpp_action::Server<action::Movement>
|
||||
|
||||
#define AnimationGoalPtr std::shared_ptr<const action::Animation::Goal>
|
||||
#define AnimationServerGoalPtr std::shared_ptr<ServerGoalHandle<action::Animation>>
|
||||
#define AnimationServerGoalPtr std::shared_ptr<rclcpp_action::ServerGoalHandle<action::Animation>>
|
||||
|
||||
#define MovementGoalPtr std::shared_ptr<const action::Movement::Goal>
|
||||
#define MovementServerGoalPtr std::shared_ptr<ServerGoalHandle<action::Movement>>
|
||||
#define MovementServerGoalPtr std::shared_ptr<rclcpp_action::ServerGoalHandle<action::Movement>>
|
||||
|
||||
#endif //BUILD_SERVER_H
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user