Go to the documentation of this file.
17 #ifndef ROSACTIONSERVER_H
18 #define ROSACTIONSERVER_H
24 #include <rosee_msg/ROSEECommandAction.h>
26 #define DEFAULT_ERROR_NORM 0.01
38 rosee_msg::ROSEEActionControl
getGoal();
57 void sendFeedback(
double completation_percentage, std::string currentAction) ;
59 void abortGoal(std::string errorMsg =
"");
79 #endif // ROSACTIONSERVER_H
RosActionServer(std::string topicForAction, ros::NodeHandle *nh)
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
void sendFeedback(double completation_percentage, std::string currentAction)
send Feedback to the client who has requested the goal.
void goalReceivedCallback()
void abortGoal(std::string errorMsg="")
rosee_msg::ROSEEActionControl getGoal()
std::string topicForAction
void preemptReceivedCallback()
rosee_msg::ROSEEActionControl actionControlMsg
double getWantedNormError() const
in message there is a field where norm error of joint position can be set If it is not present in the...
end-effector
Author(s): Luca Muratore
, Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:26