| |
Actionlib API support
Description: Create remote tasks as Actionlib ClientKeywords: decision_making
Tutorial Level: BEGINNER
Contents
C++
Node : node.cpp
Entry point of node
#include <ros/ros.h>
#include "Tasks.hpp"
....
int main(int argc, char** argv){
ros::init(argc, argv, "Name_of_node");
Task1 task1;
Task2 task2;
ros::spin();
return 0;
}
Tasks: Tasks.hpp
#include <actionlib/server/simple_action_server.h> #include <robot_task/RobotTask.h> #include <robot_task/RobotTaskAction.h> #include <robot_task/StringOperations.h> using namespace std; using namespace robot_task;
example of persistent task (do something forever)
class Task1:public RobotTask{
public:
Task1(string name="/Name_Of_Task1"):
RobotTask(name) ...
{
...
}
...
TaskResult task(const string& name, const string& uid, Arguments& args){
//hear you can advertise your topics and services, subscribes to others topics, etc.
//for example
ros::ServiceServer my_service =
_node.advertiseService<MyNodeName::MyServiceRequest, MyNodeName::MyServiceResponse>(
"service_name",boost::bind(&Task1::FunciontNameForService,this,_1,_2)
);
...
while(true){
if (isPreempt()){
/* HERE PROCESS PREEMPTION OR INTERAPT */
return TaskResult::Preempted();
}
/* HERE PROCESS TASK */
...
/* SLEEP BETWEEN LOOP ITERATIONS */
sleep(1000);
}
return TaskResult::FAIL();
}
...
};
example of one action task (do something and finish with success or fail)
class Task2:public RobotTask{
public:
Task1(string name="/Name_Of_Task2"):
RobotTask(name) ...
{
...
}
...
TaskResult task(const string& name, const string& uid, Arguments& args){
//hear proc your arguments
string target("");
double distance(-1);
if( args.find("target")!=args.end() ){
target = args["target"];
}
if( args.find("distance")!=args.end() ){
std::stringstream tmp; tmp << (args["distance"]);
tmp >> distance;
}
...
if(...){
...
return TaskResult(SUCCESS, "OK. Task is done.");
}
if(...){
...
return TaskResult(FAIL, "Error. Task aborted because ...");
}
return TaskResult::FAIL();
}
...
};
Python
Manifest
<package> .... <depend package="robot_task"/> ... </package>
MyTask.py
import roslib; roslib.load_manifest('MyTaskProject')
import rospy
import actionlib
from RobotTaskPy import *
class MyTask(RobotTask):
def __init__(self, name):
print "Init",name
RobotTask.__init__(self, name)
def task(self, name, uid, parameters):
print "Start",name
r = rospy.Rate(1)
#parameters is a dictionary with task arguments
#{arg_name: arg_value, arg_name: arg_value, ...}
#while True:
for i in xrange(1, 10):
if self.isPreepted():
print "Preempt MyTask"
return RTResult_PREEPTED()
print '-- ',i,'Do something in MyTask'
r.sleep()
print "Finish MyTask"
#error_code = RobotTask_FAIL + 1
#return RTResult_ABORT(error_code,"Some Error detected: finished with error code "+str(error_code));
return RTResult_SUCCESSED("Finished in Success")
if __name__ == '__main__':
rospy.init_node('MyTaskNode')
MyTask("MyTask")
rospy.spin()






