Move the .deb into your home folder. Open a terminal window, run the command sudo apt install ./ros-noetic-movel-seirios-msgs_0.0.0-0focalXXX64.deb to install.
You need to mount your own packages/nodes as a plugin to task_supervisor for Seirios to run it.
File to modify: ../config/task_supervisor/config/task_supervisor.yaml
Look for the plugins section in the config to add your own plugin. You can give any name and type. For type, give a number not used by previous plugins.
Then at the end of the file, create a new section with the same name you give for your plugin e.g. detecting. Then paste in the parameters.
detecting:watchdog_rate:2.0watchdog_timeout:0service_req:truelaunch_req:falseservice_start:"/external_process/trigger_detecting"#required if service_req is trueservice_start_msg:""#optional if there is any particular msg needs to sent or else empty string service_stop:"/external_process/stop_detecting"#required if service_req is trueservice_stop_msg:""#optional if there is any particular msg needs to sent or else empty string #launch_package: "yocs_velocity_smoother" #required if launch_req is true#launch_file: "standalone.launch" #required if launch_req is true#launch_nodes: "/nodelet_manager /velocity_smoother" #required if launch_req is truetopic_cancel_req:truetopic_process_cancel:"external_process/cancel_publish"
3. Launching your nodes with Seirios
There are different ways to launch your own codes. Choose one in the below subsection that best suits you.
3.1. Launch with your own code
Start & stop
You need to write a ROS service service_start with start_handler as the callback function to start your code.
And you need another ROS service service_stop with stop_handler to stop your code. Names must be service_start and service_stop.
You must use the movel_seirios_msgs package for msg and srv.
(For ROS C++ only) Add movel_seirios_msgs to package.xml and CMakeLists.txt.
Then in task_supervisor.yaml file. Change service_req: true and service_start and service_stop params to your own topics.
Stop with topic (optional)
IF you have your own script to stop the launch.
Write a subscriber topic_process_cancel to subscribe to the UI topic. Inside the handle_publish_cancel callback, include your own codes to stop.
Then change the params topic_cancel_req: true and topic_process_cancel to your own topic.
Getting status (optional)
IF you are launching your program from a launch file. Write a publisher client_status that publishes 2 if the program runs successfully or 3 if it fails.
Then change client_status: true.
3.2. Launch from the UI
Go to Custom Task UI, and choose Seirios Engine as your Execute Engine. Similarly, you need to give a task type number that is not used by other task supervisor plugins.
Then, you will need a custom service_start_msg and/or service_stop_msg to run or stop your external process.
Input a Payload in the JSON format e.g. {“service_start_msg”: “/eg/payload/start”, “service_stop_msg”:”/eg/payload/stop”} to customize the parameters.
Payload has to be parsable in JSON format so remember the “ ”s.
4. Sample Codes
For reference only.
#!/usr/bin/env python3import rospyfrom movel_seirios_msgs.srv import StringTrigger, StringTriggerResponse # like setboolfrom std_msgs.msg import Bool, UInt8classPytest:def__init__(self):print('starting test node') self.node = rospy.init_node('python_test') self.service_start = rospy.Service('/external_process/trigger_detecting', StringTrigger, self.start_handler) self.service_stop = rospy.Service('/external_process/stop_detecting', StringTrigger, self.stop_handler)# IGNORE dummy_publisher - just to simulate UI cancel topic self.dummy_publisher = rospy.Publisher('/cancel_publish', Bool, queue_size=1) self.topic_process_cancel = rospy.Subscriber('/cancel_publish', Bool, self.handle_publish_cancel) self.client_status = rospy.Publisher('/external_process/client_status', UInt8, queue_size=1) self.flag =Truedefstart_handler(self,req):print('inside start handler') start_msg =StringTriggerResponse() start_msg.success =True start_msg.message ='starting detect' self.flag =True self.publish_client_status()while(self.flag):print('executing something') rospy.sleep(1)return start_msg # return must be [success, message format]defstop_handler(self,req):print('inside stop handler') self.flag =Falseprint('stop handler called') stop_msg =StringTriggerResponse() stop_msg.success =False stop_msg.message ='stopping detect'return stop_msg# IGNORE if you are not using a topic to stop your codedefhandle_publish_cancel(self,req):print("inside publish cancel", req.data) cancel_trigger = req.dataif(cancel_trigger):print('executing cancel stuff')# replace print statement# IGNORE if you are not using launch filesdefpublish_client_status(self):print("publish client status called") cstatus =UInt8()#Dummy code#Decide how do you determine if your launch file is successful#And replace the if-else statementif (self.flag ==True): cstatus.data =2# if start_handler successfully called, task is successful and return 2else: cstatus.data =3# else task not successful, return 3 self.client_status.publish(cstatus)if__name__=='__main__': py_test =Pytest()#py_test.publish_cancel() rospy.spin()
#include<ros/ros.h>#include<std_msgs/Bool.h>#include<std_msgs/UInt8.h>#include<movel_seirios_msgs/StringTrigger.h>classCpptest {private: ros::ServiceServer service_start; ros::ServiceServer service_stop; ros::Publisher dummy_publisher; ros::Subscriber topic_process_cancel; ros::Publisher client_status;bool flag;public:Cpptest(ros::NodeHandle*nh) { service_start = nh->advertiseService("/external_package/triggering_detect_cpp", &Cpptest::start_handler, this);
service_stop =nh->advertiseService("/external_package/stopping_detect_cpp",&Cpptest::stop_handler,this); // Ignore dummy_publisher - just to simulate ui cancel button dummy_publisher =nh->advertise<std_msgs::Bool>("/cancel_publish_cpp",10); topic_process_cancel =nh->subscribe("/cancel_publish_cpp",1,&Cpptest::handle_publish_cancel,this); client_status =nh->advertise<std_msgs::UInt8>("/external_process/client_status_cpp",10); } bool start_handler(movel_seirios_msgs::StringTrigger::Request &req, movel_seirios_msgs::StringTrigger::Response &res) {
std::cout <<"inside start handler\n";res.success =true;res.message ="starting detect"; //std::cout << res << "\n"; flag =true;publish_client_status(); std::cout <<"start handler flag "<< flag <<"\n";returntrue; } bool stop_handler(movel_seirios_msgs::StringTrigger::Request &req, movel_seirios_msgs::StringTrigger::Response &res) {
std::cout <<"inside stop handler\n";res.success =false;res.message ="stopping detect"; //std::cout << res << "\n"; flag =false; std::cout <<"stop handler flag "<< flag <<"\n";returntrue; } // Ignore this method if not subscribing to stop topicvoidhandle_publish_cancel(const std_msgs::Bool& msg) { std::cout <<"inside handle publish cancel\n";bool cancel_trigger; cancel_trigger =msg.data; //std::cout << "published msg " << cancel_trigger << "\n";if(cancel_trigger){ std::cout <<"do canceling stuff. cancel_trigger: "<< cancel_trigger <<"\n"; } } // Ignore this method if not using launchvoidpublish_client_status() { std::cout <<"publish client status called\n"; std_msgs::UInt8 cstatus;if(flag) {cstatus.data =2; }else {cstatus.data =3; } std::cout <<"client status "<< cstatus <<"2 for success, 3 for fail \n";client_status.publish(cstatus); }};intmain(int argc,char** argv) { ros::init(argc, argv,"cpp_test"); ros::NodeHandle nh; Cpptest cpp_test(&nh); ros::spin();return0;}