Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
R
Robomaster_pi
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Requirements
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Locked files
Deploy
Releases
Package Registry
Model registry
Operate
Terraform modules
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
Repository analytics
Code review analytics
Issue analytics
Insights
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Emil Harlan
Robomaster_pi
Commits
f5d3cd30
Commit
f5d3cd30
authored
1 year ago
by
Emil Harlan
Browse files
Options
Downloads
Patches
Plain Diff
a
parent
a1dd5cfa
No related branches found
Branches containing commit
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
robomaster_pi/launch_node.py
+16
-12
16 additions, 12 deletions
robomaster_pi/launch_node.py
with
16 additions
and
12 deletions
robomaster_pi/launch_node.py
+
16
−
12
View file @
f5d3cd30
...
...
@@ -3,6 +3,7 @@ from rclpy.node import Node
from
std_msgs.msg
import
String
from
subprocess
import
Popen
,
PIPE
,
STDOUT
from
concurrent.futures
import
ThreadPoolExecutor
import
threading
class
LaunchNode
(
Node
):
...
...
@@ -15,9 +16,7 @@ class LaunchNode(Node):
# Create a dictionary to store the launched processes
self
.
launched_processes
=
{}
# Create a thread pool
self
.
thread_pool
=
ThreadPoolExecutor
(
max_workers
=
10
)
self
.
process_lock
=
threading
.
Lock
()
# Lock for thread safety
def
on_message
(
self
,
msg
):
# Get the launch command and name from the message
...
...
@@ -26,6 +25,14 @@ class LaunchNode(Node):
# If the launch command is "kill", send a SIGINT signal to the process with the given name
if
command
==
"
kill
"
:
self
.
_terminate_process
(
name
)
else
:
# Otherwise, launch the process with the given command in a separate thread
thread
=
threading
.
Thread
(
target
=
self
.
_launch_process
,
args
=
(
name
,
command
))
thread
.
start
()
def
_terminate_process
(
self
,
name
):
with
self
.
process_lock
:
if
name
in
self
.
launched_processes
:
try
:
process
=
self
.
launched_processes
[
name
]
...
...
@@ -37,9 +44,11 @@ class LaunchNode(Node):
self
.
get_logger
().
error
(
f
"
Error terminating process
'
{
name
}
'
:
{
e
}
"
)
else
:
self
.
get_logger
().
warn
(
f
"
Process
'
{
name
}
'
not found in launched_processes.
"
)
else
:
def
_launch_process
(
self
,
name
,
command
):
with
self
.
process_lock
:
try
:
#
Otherwise, l
aunch the process
with the given command
#
L
aunch the process
process
=
Popen
(
command
,
shell
=
True
,
stdout
=
PIPE
,
stderr
=
STDOUT
)
self
.
launched_processes
[
name
]
=
process
self
.
get_logger
().
info
(
f
"
Process
'
{
name
}
'
has been launched.
"
)
...
...
@@ -59,15 +68,10 @@ def main():
finally
:
# Terminate all running processes before shutting down
for
name
,
process
in
node
.
launched_processes
.
items
():
try
:
process
.
send_signal
(
Popen
.
SIGINT
)
process
.
wait
(
timeout
=
5
)
node
.
get_logger
().
info
(
f
"
Process
'
{
name
}
'
has been terminated before shutdown.
"
)
except
Exception
as
e
:
node
.
get_logger
().
error
(
f
"
Error terminating process
'
{
name
}
'
:
{
e
}
"
)
node
.
_terminate_process
(
name
)
node
.
destroy_node
()
rclpy
.
shutdown
()
if
__name__
==
"
__main__
"
:
main
()
\ No newline at end of file
main
()
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment