Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ROSEE::RosActionServer Class Reference

#include <RosActionServer.h>

Public Member Functions

void abortGoal (std::string errorMsg="")
 
rosee_msg::ROSEEActionControl getGoal ()
 
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 message sent (thus it is 0) the DEFAULT_ERROR_NORM is used More...
 
bool hasGoal () const
 
bool hasNewGoal () const
 
 RosActionServer (std::string topicForAction, ros::NodeHandle *nh)
 
void sendComplete ()
 
void sendFeedback (double completation_percentage, std::string currentAction)
 send Feedback to the client who has requested the goal. More...
 
 ~RosActionServer ()
 

Protected Member Functions

void goalReceivedCallback ()
 
void preemptReceivedCallback ()
 

Protected Attributes

actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
 
rosee_msg::ROSEEActionControl actionControlMsg
 
bool goalInExecution
 
bool newGoal
 
ros::NodeHandlenh
 
std::string topicForAction
 
double wantedNormError
 

Detailed Description

Todo:
write docs

Definition at line 32 of file RosActionServer.h.

Constructor & Destructor Documentation

◆ RosActionServer()

ROSEE::RosActionServer::RosActionServer ( std::string  topicForAction,
ros::NodeHandle nh 
)

Definition at line 19 of file RosActionServer.cpp.

◆ ~RosActionServer()

ROSEE::RosActionServer::~RosActionServer ( )
inline

Definition at line 36 of file RosActionServer.h.

Member Function Documentation

◆ abortGoal()

void ROSEE::RosActionServer::abortGoal ( std::string  errorMsg = "")

Definition at line 83 of file RosActionServer.cpp.

◆ getGoal()

rosee_msg::ROSEEActionControl ROSEE::RosActionServer::getGoal ( )

Definition at line 46 of file RosActionServer.cpp.

◆ getWantedNormError()

double ROSEE::RosActionServer::getWantedNormError ( ) const

in message there is a field where norm error of joint position can be set If it is not present in the message sent (thus it is 0) the DEFAULT_ERROR_NORM is used

Definition at line 42 of file RosActionServer.cpp.

◆ goalReceivedCallback()

void ROSEE::RosActionServer::goalReceivedCallback ( )
protected

Definition at line 58 of file RosActionServer.cpp.

◆ hasGoal()

bool ROSEE::RosActionServer::hasGoal ( ) const

Definition at line 34 of file RosActionServer.cpp.

◆ hasNewGoal()

bool ROSEE::RosActionServer::hasNewGoal ( ) const

Definition at line 38 of file RosActionServer.cpp.

◆ preemptReceivedCallback()

void ROSEE::RosActionServer::preemptReceivedCallback ( )
protected

Definition at line 72 of file RosActionServer.cpp.

◆ sendComplete()

void ROSEE::RosActionServer::sendComplete ( )

Definition at line 111 of file RosActionServer.cpp.

◆ sendFeedback()

void ROSEE::RosActionServer::sendFeedback ( double  completation_percentage,
std::string  currentAction 
)

send Feedback to the client who has requested the goal.

Parameters
completation_percentagethe percentae that tells how much we have completed the action requested
currentActioncurrent action that is running. If it is empty, it is taken the name of the action from member actionControlMsg . You should passed not empty string when dealing with timed action (passing the inner action of the timed one)

Definition at line 95 of file RosActionServer.cpp.

Member Data Documentation

◆ _actionServer

actionlib::SimpleActionServer<rosee_msg::ROSEECommandAction> ROSEE::RosActionServer::_actionServer
protected

Definition at line 65 of file RosActionServer.h.

◆ actionControlMsg

rosee_msg::ROSEEActionControl ROSEE::RosActionServer::actionControlMsg
protected

Definition at line 66 of file RosActionServer.h.

◆ goalInExecution

bool ROSEE::RosActionServer::goalInExecution
protected

Definition at line 67 of file RosActionServer.h.

◆ newGoal

bool ROSEE::RosActionServer::newGoal
protected

Definition at line 68 of file RosActionServer.h.

◆ nh

ros::NodeHandle* ROSEE::RosActionServer::nh
protected

Definition at line 63 of file RosActionServer.h.

◆ topicForAction

std::string ROSEE::RosActionServer::topicForAction
protected

Definition at line 64 of file RosActionServer.h.

◆ wantedNormError

double ROSEE::RosActionServer::wantedNormError
protected

Definition at line 69 of file RosActionServer.h.


The documentation for this class was generated from the following files:


end-effector
Author(s): Luca Muratore , Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:27