External Process Handler
external_process_handler is a package for clients to run their own tasks into Seirios.

How to setup your tasks with External Process Handler

Pre-setup: Make sure your Seirios is setup and working.
This guide shows you how to integrate your own programs as a plugin into Seirios using external_process_handlerpackage.
You will need:
  1. 1.
    Seirios
  2. 2.
    Your own codes

0. Installing Movel Seirios Message

Check your ROS version.
  • For Ubuntu 20.04, ROS Noetic users:
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.
  • Else:
Git clone this repo here: https://gitlab.com/movelai_public/movel_seirios_msgs/-/tree/master/srv into your catkin workspace.
Run catkin_make this repo to compile so that it will be usable.

1. Codes to add into your own program

You need functions to interface with external_program_handler execute your launch and stop codes.
Your program must have something that can tell Seirios to start your program and stop your program. For starting, it can be done with a ROS service or a launch file. For stopping, it can be done with a ROS service or subscribing to a topic.
Sample codes provided are in python and c++.
Make sure you're copying the correct type of code. Do not copy c++ codes into a python program, vice versa.

1.1. Starting & stopping a program with ROS Service

Starting
Inside your program, add a service. Name it as service_start. Write a handler start_handler as a callback to handle your launch codes.
Stopping
Initialize another service as service_stop. Similarly, write a callback stop_handler to handle your codes to stop the program.
You MUST use the Seirios package movel_seirios_msgsforservice_startandservice_stop.To use the package, add the import statements below. You must also include the additional configurations if you are using C++.
Python
C++
1
from movel_seirios_msgs.srv import StringTrigger, StringTriggerResponse # like setbool
Copied!
1
#include <movel_seirios_msgs/StringTrigger.h>
Copied!
Additional configurations for C++
For C++ programs, you must also add movel_seirios_msgs package as a dependency in package.xml in your own package.
1
<depend>movel_seirios_msgs</depend>
Copied!
In CMakeLists.txt in your own package, add movel_seirios_msgs under find_package.
1
find_package(catkin REQUIRED COMPONENTS
2
roscpp
3
rospy
4
std_msgs
5
movel_seirios_msgs
6
)
Copied!

1.2. Stopping a program with a topic

Refer to this section if you stop your program via publishing a stop topic from the UI. Else, ignore it.
Write a subscriber topic_process_cancelto subscribe to the UI topic. Inside the handle_publish_cancelcallback, include your stopping codes.
Make sure topic_process_cancel is subscribing to the correct UI topic.
1.3. Publishing client status
Refer to this section if you are launching your program from a launch file. Else, ignore it.
Purpose of this is to check if your program is running successfully after launching your program from launch file.
Write a publisher client_status that publishes 2 if the program runs successfully or 3 if the program fails.

2. Sample Code

You may refer to the sample codes on how to start and stop your program using external process handler.
The codes in the callback functions are just filler codes to test external_process_handler. Replace them with your own starting and stopping codes.
Python
C++
1
#!/usr/bin/env python
2
import rospy
3
from movel_seirios_msgs.srv import StringTrigger, StringTriggerResponse # like setbool
4
from std_msgs.msg import Bool, UInt8
5
6
7
class Pytest:
8
9
def __init__(self):
10
print('starting test node')
11
self.node = rospy.init_node('python_test')
12
13
self.service_start = rospy.Service('/external_process/trigger_detecting', StringTrigger, self.start_handler)
14
self.service_stop = rospy.Service('/external_process/stop_detecting', StringTrigger, self.stop_handler)
15
16
# IGNORE dummy_publisher - just to simulate UI cancel topic
17
self.dummy_publisher = rospy.Publisher('/cancel_publish', Bool, queue_size=1)
18
19
self.topic_process_cancel = rospy.Subscriber('/cancel_publish', Bool, self.handle_publish_cancel)
20
self.client_status = rospy.Publisher('/external_process/client_status', UInt8, queue_size=1)
21
22
self.flag = True
23
24
def start_handler(self, req):
25
print('inside start handler')
26
27
start_msg = StringTriggerResponse()
28
start_msg.success = True
29
start_msg.message = 'starting detect'
30
31
self.flag = True
32
self.publish_client_status()
33
34
while(self.flag):
35
print('executing something')
36
rospy.sleep(1)
37
38
39
return start_msg # return must be [success, message format]
40
41
def stop_handler(self, req):
42
print('inside stop handler')
43
44
self.flag = False
45
print('stop handler called')
46
stop_msg = StringTriggerResponse()
47
stop_msg.success = False
48
stop_msg.message = 'stopping detect'
49
50
return stop_msg
51
52
# IGNORE if you are not using a topic to stop your code
53
def handle_publish_cancel(self, req):
54
print("inside publish cancel", req.data)
55
56
cancel_trigger = req.data
57
if(cancel_trigger):
58
print('executing cancel stuff') # replace print statement
59
60
61
# IGNORE if you are not using launch files
62
def publish_client_status(self):
63
print("publish client status called")
64
65
cstatus = UInt8()
66
67
#Dummy code
68
#Decide how do you determine if your launch file is successful
69
#And replace the if-else statement
70
if (self.flag == True):
71
cstatus.data = 2 # if start_handler successfully called, task is successful and return 2
72
else:
73
cstatus.data = 3 # else task not successful, return 3
74
75
self.client_status.publish(cstatus)
76
77
78
if __name__ == '__main__':
79
80
py_test = Pytest()
81
#py_test.publish_cancel()
82
83
rospy.spin()
Copied!
1
#include <ros/ros.h>
2
#include <std_msgs/Bool.h>
3
#include <std_msgs/UInt8.h>
4
#include <movel_seirios_msgs/StringTrigger.h>
5
6
7
class Cpptest {
8
9
private:
10
11
ros::ServiceServer service_start;
12
ros::ServiceServer service_stop;
13
14
ros::Publisher dummy_publisher;
15
ros::Subscriber topic_process_cancel;
16
17
ros::Publisher client_status;
18
bool flag;
19
20
public:
21
Cpptest(ros::NodeHandle *nh) {
22
service_start = nh->advertiseService("/external_package/triggering_detect_cpp", &Cpptest::start_handler, this);
23
service_stop = nh->advertiseService("/external_package/stopping_detect_cpp", &Cpptest::stop_handler, this);
24
25
// Ignore dummy_publisher - just to simulate ui cancel button
26
dummy_publisher = nh->advertise<std_msgs::Bool>("/cancel_publish_cpp", 10);
27
topic_process_cancel = nh->subscribe("/cancel_publish_cpp", 1, &Cpptest::handle_publish_cancel, this);
28
29
client_status = nh->advertise<std_msgs::UInt8>("/external_process/client_status_cpp", 10);
30
31
}
32
33
bool start_handler(movel_seirios_msgs::StringTrigger::Request &req, movel_seirios_msgs::StringTrigger::Response &res) {
34
std::cout << "inside start handler\n";
35
36
res.success = true;
37
res.message = "starting detect";
38
//std::cout << res << "\n";
39
40
flag = true;
41
publish_client_status();
42
std::cout << "start handler flag "<< flag << "\n";
43
44
return true;
45
}
46
47
bool stop_handler(movel_seirios_msgs::StringTrigger::Request &req, movel_seirios_msgs::StringTrigger::Response &res) {
48
std::cout << "inside stop handler\n";
49
50
res.success = false;
51
res.message = "stopping detect";
52
//std::cout << res << "\n";
53
54
flag = false;
55
std::cout << "stop handler flag "<< flag << "\n";
56
57
return true;
58
}
59
60
// Ignore this method if not subscribing to stop topic
61
void handle_publish_cancel(const std_msgs::Bool& msg) {
62
std::cout << "inside handle publish cancel\n";
63
64
bool cancel_trigger;
65
cancel_trigger = msg.data;
66
//std::cout << "published msg " << cancel_trigger << "\n";
67
if(cancel_trigger){
68
std::cout << "do canceling stuff. cancel_trigger: " << cancel_trigger << "\n";
69
}
70
}
71
72
// Ignore this method if not using launch
73
void publish_client_status() {
74
std::cout << "publish client status called\n";
75
76
std_msgs::UInt8 cstatus;
77
78
if(flag) {
79
cstatus.data = 2;
80
}
81
else {
82
cstatus.data = 3;
83
}
84
85
std::cout << "client status " << cstatus << "2 for success, 3 for fail \n";
86
client_status.publish(cstatus);
87
88
}
89
90
};
91
92
int main(int argc, char** argv) {
93
94
ros::init(argc, argv, "cpp_test");
95
ros::NodeHandle nh;
96
97
Cpptest cpp_test(&nh);
98
99
ros::spin();
100
101
return 0;
102
}
Copied!

3. Files to change in Seirios

After making changes in your own code, you need to also configure task_supervisor so that it runs your program with Seirios.

3.1. Parameters used for external_process_handler

YAML
1
watchdog_rate: 2.0
2
watchdog_timeout: 0
3
service_req: true
4
# Below 4 params are COMPULSORY if service_req is true
5
service_start: "/external_process/trigger_detecting"
6
service_start_msg: "" # Optional, may put blank string
7
service_stop: "/external_process/stop_detecting"
8
service_stop_msg: "" # Optional, may put blank string
9
launch_req: false
10
# Below 3 params COMPULSORY if launch_req is true
11
launch_package:
12
launch_file:
13
launch_nodes:
14
topic_cancel_req: true
15
# topic_process_cancel required if topic_cancel_req is true
16
topic_process_cancel: "external_process/cancel_publish"
17
client_status: # Required if launch_req true, optional otherwise
Copied!
Set boolean status of service_req, launch_reqand topic_cancel_req depending on how you start/stop your program.
The params service_start, service_stop,topic_process_cancel,client_statusmust match the name of the topics and services that you have given in your own file.

3.2. Adding to task supervisor as plugin

Add your program as a plugin to task supervisor so that Seirios can run it. Insert the configurations into task_supervisor.yaml
Filepath: ../config/task_supervisor/config/
File to modify: task_supervisor.yaml
Warn: yaml files forbids tabs. Do not use tabs to indent when editing yaml files.
Under plugins section in task supervisor, insert the below code. The identation must align with the other plugins. You can give any name and type but make sure they don't clash with other plugins. Do not change the class.
1
plugins:
2
- {name: detecting, type: 10, class: 'external_process_handler::ExternalProcessHandler'}
Copied!
At the end of the file, create a new section using the name that you give above. Paste in the parameters.
1
detecting:
2
watchdog_rate: 2.0
3
watchdog_timeout: 0
4
service_req: true
5
launch_req: false
6
service_start: "/external_process/trigger_detecting" #required if service_req is true
7
service_start_msg: "" #optional if there is any particular msg needs to sent or else empty string
8
service_stop: "/external_process/stop_detecting" #required if service_req is true
9
service_start_msg: "" #optional if there is any particular msg needs to sent or else empty string
10
#launch_package: "yocs_velocity_smoother" #required if launch_req is true
11
#launch_file: "standalone.launch" #required if launch_req is true
12
#launch_nodes: "/nodelet_manager /velocity_smoother" #required if launch_req is true
13
topic_cancel_req: true
14
topic_process_cancel: "external_process/cancel_publish"
Copied!

Other things to note

For C++ programs, remember to setup your CMakeLists.txtand package.xmlproperly in your own package. For more information, click here.
Last modified 1mo ago