to ros_comm
This commit is contained in:
parent
44421dfa8b
commit
d374eb631d
|
@ -1,3 +0,0 @@
|
|||
#!/usr/bin/env python
|
||||
from ros import roslaunch
|
||||
roslaunch.main()
|
|
@ -1,308 +0,0 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
import roslib; roslib.load_manifest('roslaunch')
|
||||
|
||||
import os
|
||||
import sys
|
||||
import curses
|
||||
|
||||
from roslib.msg import Log
|
||||
import roslib.network
|
||||
import rospy
|
||||
import roslaunch.netapi as netapi
|
||||
from roslaunch.netapi import NetProcess
|
||||
|
||||
## Node name
|
||||
NAME='roslaunch-console'
|
||||
|
||||
## strify our data (NetProcess)
|
||||
def datastr(p):
|
||||
if p.is_alive:
|
||||
if p.respawn_count > 1:
|
||||
return pad("%s (respawn %s)"%(p.name, p.respawn_count-1))
|
||||
else:
|
||||
return pad("%s"%p.name)
|
||||
else:
|
||||
return pad("dead:%s"%p.name)
|
||||
|
||||
fake_data = [
|
||||
NetProcess('node1', 1, True, 'http://foo:1234'),
|
||||
NetProcess('node2', 1, True, 'http://foo:1234'),
|
||||
NetProcess('node3', 1, True, 'http://foo:1234'),
|
||||
NetProcess('node4', 1, True, 'http://foo:1234'),
|
||||
NetProcess('node5', 1, False, 'http://foo:1234'),
|
||||
NetProcess('node6', 1, True, 'http://foo:1234'),
|
||||
NetProcess('deadnode7', 11234, False, 'http://foo:1234'),
|
||||
NetProcess('/a/much/longer/name/I/must/persist/to/write/to/screen', 1, True, 'http://foo:1234'),
|
||||
|
||||
NetProcess('m2node1', 1, True, 'http://m2:1234'),
|
||||
NetProcess('m2node2', 1, True, 'http://m2:1234'),
|
||||
NetProcess('m2node3', 1, True, 'http://m2:1234'),
|
||||
NetProcess('m2node4', 4, True, 'http://m2:1234'),
|
||||
NetProcess('m2node5', 1, True, 'http://m2:1234'),
|
||||
NetProcess('m2node6', 1, True, 'http://m2:1234'),
|
||||
|
||||
NetProcess('m3node1', 1, True, 'http://m3:1234'),
|
||||
NetProcess('m3node2', 1, True, 'http://m3:1234'),
|
||||
NetProcess('m3node3', 1, True, 'http://m3:1234'),
|
||||
NetProcess('m3node4', 1, False, 'http://m3:1234'),
|
||||
NetProcess('m3node5', 1, False, 'http://m3:1234'),
|
||||
NetProcess('m3node6', 1, True, 'http://m3:1234'),
|
||||
|
||||
NetProcess('m4node1', 1, True, 'http://m4:1234'),
|
||||
NetProcess('m4node2', 1, True, 'http://m4:1234'),
|
||||
NetProcess('m4node3', 1, True, 'http://m4:1234'),
|
||||
NetProcess('m4node4', 1, True, 'http://m4:1234'),
|
||||
NetProcess('m4node5', 1, True, 'http://m4:1234'),
|
||||
NetProcess('m4node6', 1, True, 'http://m4:1234'),
|
||||
]
|
||||
|
||||
def pad(s):
|
||||
if len(s) < curses.COLS:
|
||||
return s + ' '*(curses.COLS-len(s)-1)
|
||||
else:
|
||||
return s[:curses.COLS-1]
|
||||
|
||||
class RLConsoleException(Exception): pass
|
||||
|
||||
class ROSLaunchConsole(object):
|
||||
|
||||
def __init__(self, stdscr, roslaunch_uris=None, fake=False):
|
||||
if fake:
|
||||
self.roslaunch_uris = []
|
||||
self.data = fake_data
|
||||
elif not roslaunch_uris:
|
||||
roslaunch_uris = netapi.get_roslaunch_uris()
|
||||
if not roslaunch_uris:
|
||||
raise RLConsoleException("Cannot find any launches registered with the Parameter Server")
|
||||
self.data = []
|
||||
|
||||
self.draw_model = []
|
||||
|
||||
self.stdscr = stdscr
|
||||
self.scr_line = 0 #index of line on screen that is selected
|
||||
self.draw_model_line = 0 #first draw_model_line on screen
|
||||
|
||||
self.reserved = 2 # total number of lines we reserve at top and bottom of screen
|
||||
self.reserved_top = 1 #number of lines we reserve at top of screen
|
||||
|
||||
self.update_data()
|
||||
|
||||
self.loggers = {}
|
||||
self.loggers[Log.FATAL] = []
|
||||
self.loggers[Log.ERROR] = []
|
||||
self.loggers[Log.WARN] = []
|
||||
self.loggers[Log.INFO] = []
|
||||
self.loggers[Log.DEBUG] = []
|
||||
|
||||
#self.command_context_stack = [self.base]
|
||||
|
||||
#-------------------------------------------------------------------------------
|
||||
# Logging methods, decoupled from ROS
|
||||
|
||||
def add_logger(self, level, fn):
|
||||
self.loggers[level].append(fn)
|
||||
|
||||
def log(self, level, msg, *args):
|
||||
for l in self.loggers[level]:
|
||||
l(msg, *args)
|
||||
|
||||
def logerr(self, msg, *args):
|
||||
self.log(Log.ERROR, msg, *args)
|
||||
|
||||
def logwarn(self, msg, *args):
|
||||
self.log(Log.WARN, msg, *args)
|
||||
|
||||
def logdebug(self, msg, *args):
|
||||
self.log(Log.DEBUG, msg, *args)
|
||||
|
||||
def loginfo(self, msg, *args):
|
||||
self.log(Log.INFO, msg, *args)
|
||||
|
||||
def logfatal(self, msg, *args):
|
||||
self.log(Log.FATAL, msg, *args)
|
||||
|
||||
|
||||
#-------------------------------------------------------------------------------
|
||||
# Console Data routines
|
||||
|
||||
def update_data(self):
|
||||
# TODO: ordering of self.data must be preserved, so cannot actually replace list
|
||||
self.data = netapi.list_processes()
|
||||
self.draw_model = self.data # for now, equal. need to decouple
|
||||
# Need to have two models: the draw_model and the actual data_model
|
||||
#self.next_data = next_data
|
||||
# on redraw, self.data = self.next_data
|
||||
|
||||
#-------------------------------------------------------------------------------
|
||||
# Console Drawing API
|
||||
|
||||
def get_selected(self):
|
||||
return self.draw_model[self.draw_model_line + self.scr_line]
|
||||
|
||||
def draw_data(self, d, row, selected):
|
||||
scr = self.stdscr
|
||||
if selected:
|
||||
if d.is_alive:
|
||||
scr.addstr(row, 0, datastr(d), curses.A_REVERSE)
|
||||
else:
|
||||
scr.addstr(row, 0, datastr(d), curses.A_REVERSE | curses.A_BOLD)
|
||||
else:
|
||||
if d.is_alive:
|
||||
scr.addstr(row, 0, datastr(d))
|
||||
else:
|
||||
scr.addstr(row, 0, datastr(d), curses.A_BOLD)
|
||||
|
||||
def redraw_scr(self):
|
||||
self.loginfo("redraw")
|
||||
|
||||
model = self.draw_model
|
||||
my_lines = curses.LINES - self.reserved
|
||||
|
||||
scr = self.stdscr
|
||||
scr.clear()
|
||||
dead_count = len([n for n in model if not n.is_alive])
|
||||
for i, l in enumerate(model[self.draw_model_line:self.draw_model_line+my_lines]):
|
||||
# offset draw row by the reserved_top
|
||||
draw_i = i + self.reserved_top
|
||||
self.draw_data(l, draw_i, i == self.scr_line)
|
||||
|
||||
show_count = curses.LINES - self.reserved
|
||||
if show_count > len(model):
|
||||
show_count = len(model)
|
||||
status = "%s of %s nodes, %s dead"%(show_count, len(model), dead_count)
|
||||
scr.addstr(0, 0, pad(status), curses.A_REVERSE | curses.A_BOLD)
|
||||
#scr.addstr(curses.LINES-1, 0, pad('type h for help'), curses.A_BOLD)
|
||||
scr.addstr(curses.LINES-1, 0, pad('space=update, s=sort, r=relaunch, k=kill, q=quit'), curses.A_BOLD)
|
||||
|
||||
def scroll_scr(self, inc):
|
||||
model = self.draw_model
|
||||
|
||||
my_lines = curses.LINES - self.reserved
|
||||
next_line = self.scr_line + inc
|
||||
if (next_line < 0 and self.draw_model_line == 0) or \
|
||||
(next_line + self.draw_model_line >= len(model)):
|
||||
# ignore out-of-bounds
|
||||
return
|
||||
|
||||
scr = self.stdscr
|
||||
|
||||
if next_line < 0:
|
||||
self.draw_model_line -= 1
|
||||
self.scr_line = 0
|
||||
self.redraw_scr()
|
||||
elif next_line >= my_lines:
|
||||
self.draw_model_line += 1
|
||||
self.scr_line = my_lines - 1
|
||||
self.redraw_scr()
|
||||
else:
|
||||
offset = self.reserved_top
|
||||
# unhighlight old line
|
||||
d = model[self.scr_line + self.draw_model_line]
|
||||
self.draw_data(d, offset+self.scr_line, False)
|
||||
|
||||
# draw highlighted
|
||||
self.scr_line = next_line
|
||||
d = model[self.scr_line + self.draw_model_line]
|
||||
self.draw_data(d, offset+self.scr_line, True)
|
||||
scr.refresh()
|
||||
|
||||
#-------------------------------------------------------------------------------
|
||||
# Console Commands
|
||||
|
||||
def update_cmd(self):
|
||||
self.loginfo("update cmd")
|
||||
self.update_data()
|
||||
self.redraw_scr()
|
||||
|
||||
def help_cmd(self):
|
||||
# highlighted line may be a node or a machine
|
||||
# TODO: compute actual width
|
||||
self.stdscr.addstr(curses.LINES-1, 0, pad('space=update, s=sort, k=kill'), curses.A_BOLD)
|
||||
self.stdscr.refresh()
|
||||
|
||||
def relaunch_cmd(self):
|
||||
# highlighted line may be a node or a machine
|
||||
self.loginfo("relaunch cmd")
|
||||
|
||||
selected = self.get_selected()
|
||||
self.loginfo("selected is %s", selected)
|
||||
|
||||
def kill_cmd(self):
|
||||
# highlighted line may be a node or a machine
|
||||
self.loginfo("relaunch cmd")
|
||||
|
||||
def sort_cmd(self):
|
||||
# input: sort by status, name, machine
|
||||
self.loginfo("relaunch cmd")
|
||||
|
||||
|
||||
## @return scr: initialized and configured curses screen
|
||||
def _init_curses():
|
||||
stdscr = curses.initscr()
|
||||
# interpret special keys as curses values (e.g. KEY_LEFT)
|
||||
stdscr.keypad(1)
|
||||
|
||||
# react immediately to keypress
|
||||
curses.cbreak()
|
||||
# hide the cursor
|
||||
curses.curs_set(0)
|
||||
# don't echo keypresses to screen
|
||||
curses.noecho()
|
||||
return stdscr
|
||||
|
||||
## Reset terminal settings (teardown curses)
|
||||
## @param stdscr: screen to tear down
|
||||
def _deinit_curses(stdscr):
|
||||
curses.curs_set(1)
|
||||
curses.nocbreak()
|
||||
if stdscr is not None:
|
||||
stdscr.keypad(0)
|
||||
curses.echo()
|
||||
curses.endwin()
|
||||
|
||||
def roslaunch_console():
|
||||
stdscr = None
|
||||
try:
|
||||
stdscr = _init_curses()
|
||||
|
||||
rospy.init_node(NAME, anonymous=True)
|
||||
|
||||
console = ROSLaunchConsole(stdscr)
|
||||
|
||||
console.add_logger(Log.INFO, rospy.loginfo)
|
||||
console.add_logger(Log.FATAL, rospy.logerr)
|
||||
console.add_logger(Log.ERROR, rospy.logerr)
|
||||
console.add_logger(Log.DEBUG, rospy.logdebug)
|
||||
|
||||
exit = False
|
||||
console.redraw_scr()
|
||||
while not exit:
|
||||
ch = stdscr.getch()
|
||||
if ch == curses.KEY_UP:
|
||||
console.scroll_scr(-1)
|
||||
elif ch == curses.KEY_DOWN:
|
||||
console.scroll_scr(1)
|
||||
else:
|
||||
if ch == ord('q'):
|
||||
exit = True
|
||||
elif ch == ord('k'):
|
||||
console.kill_cmd()
|
||||
elif ch == ord(' '):
|
||||
console.update_cmd()
|
||||
elif ch == ord('s'):
|
||||
console.sort_cmd()
|
||||
|
||||
finally:
|
||||
_deinit_curses(stdscr)
|
||||
|
||||
def roslaunch_console_main():
|
||||
try:
|
||||
roslaunch_console()
|
||||
except RLConsoleException, e:
|
||||
print >> sys.stderr, e
|
||||
except KeyboardInterrupt: pass
|
||||
|
||||
if __name__ == '__main__':
|
||||
roslaunch_console_main()
|
||||
|
|
@ -1,3 +0,0 @@
|
|||
<launch>
|
||||
<param name="example_env_param" value="$(env VALUE)" />
|
||||
</launch>
|
|
@ -1,4 +0,0 @@
|
|||
<!-- NOTE: this requires that you 'rosmake roscpp_tutorials' -->
|
||||
<launch>
|
||||
<node name="talker" pkg="roscpp_tutorials" type="talker" launch-prefix="xterm -e gdb --args"/>
|
||||
</launch>
|
|
@ -1,17 +0,0 @@
|
|||
<launch>
|
||||
<node name="talker" pkg="test_ros" type="talker.py" />
|
||||
<node name="listener" pkg="test_ros" type="listener.py" />
|
||||
|
||||
<param name="param1" value="bar" />
|
||||
<param name="param2" value="2"/>
|
||||
|
||||
<!-- you can set parameters in child namespaces -->
|
||||
<param name="wg2/param3" value="a child namespace parameter" />
|
||||
|
||||
<group ns="wg2">
|
||||
<param name="param4" value="4" />
|
||||
<node name="talker" pkg="test_ros" type="talker.py" />
|
||||
<node name="listener" pkg="test_ros" type="listener.py" />
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,4 +0,0 @@
|
|||
<launch>
|
||||
<!-- $(anon talker) creates an anonymous name for this node -->
|
||||
<node name="$(anon talker)" pkg="test_ros" type="talker.py" />
|
||||
</launch>
|
|
@ -1,46 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<!--
|
||||
|
||||
Parameter Server parameters. You can omit the 'type' attribute if
|
||||
value is unambiguous. Supported types are str, int, double, bool.
|
||||
You can also specify the contents of a file instead using the
|
||||
'textfile' or 'binfile' attributes.
|
||||
|
||||
-->
|
||||
<param name="somestring1" value="bar2" />
|
||||
<!-- force to string instead of integer -->
|
||||
<param name="somestring2" value="10" type="str" />
|
||||
|
||||
<param name="someinteger1" value="1" type="int" />
|
||||
<param name="someinteger2" value="2" />
|
||||
|
||||
<param name="somefloat1" value="3.14159" type="double" />
|
||||
<param name="somefloat2" value="3.0" />
|
||||
|
||||
<!-- you can set parameters in child namespaces -->
|
||||
<param name="wg/wgchildparam" value="a child namespace parameter" />
|
||||
<group ns="wg2">
|
||||
<param name="wg2childparam1" value="a child namespace parameter" />
|
||||
<param name="wg2childparam2" value="a child namespace parameter" />
|
||||
</group>
|
||||
|
||||
<!-- use rosparam for more complex types -->
|
||||
<rosparam param="list">[1, 2, 3, 4]</rosparam>
|
||||
<rosparam>
|
||||
rp_key1: a
|
||||
rp_key2: b
|
||||
</rosparam>
|
||||
|
||||
<!-- use rosparam files -->
|
||||
<group ns="rosparam">
|
||||
<rosparam command="load" file="$(find rosparam)/example.yaml" />
|
||||
</group>
|
||||
|
||||
<!-- upload the contents of a file as a param -->
|
||||
<param name="configfile" textfile="$(find roslaunch)/example.launch" />
|
||||
<!-- upload the contents of a file as base64 binary as a param -->
|
||||
<param name="binaryfile" binfile="$(find roslaunch)/example.launch" />
|
||||
<!-- upload the output of a command as a param. -->
|
||||
|
||||
</launch>
|
|
@ -1,17 +0,0 @@
|
|||
<!-- an example launch configuration that launches two demo nodes on a remote machine -->
|
||||
<launch>
|
||||
|
||||
<group ns="local">
|
||||
<node name="talker" pkg="test_ros" type="talker.py" />
|
||||
<node name="listener" pkg="test_ros" type="listener.py" />
|
||||
</group>
|
||||
|
||||
<!-- default only affects nodes defined later -->
|
||||
<machine name="machine-1" default="true" address="foo.bar.com" ros-root="/home/user/ros/ros/" user="whoami" ssh-port="22" />
|
||||
|
||||
<group ns="remote">
|
||||
<node name="talker" pkg="test_ros" type="talker.py" />
|
||||
<node name="listener" pkg="test_ros" type="listener.py" />
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,62 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<!-- localhost definition can be omitted unless you want to override ros-root or set it as the default machine. -->
|
||||
<machine name="localhost" address="localhost" default="true" />
|
||||
<machine name="localhost-altroot" address="localhost" ros-root="/u/kwc/sf/ros/" ros-package-path="/u/kwc/sf/personalrobots/" />
|
||||
|
||||
<!--
|
||||
|
||||
Parameter Server parameters. You can omit the 'type' attribute if
|
||||
value is unambiguous. Supported types are str, int, double, bool.
|
||||
You can also specify the contents of a file instead using the
|
||||
'textfile' or 'binfile' attributes.
|
||||
|
||||
-->
|
||||
<param name="somestring1" value="bar" />
|
||||
<!-- force to string instead of integer -->
|
||||
<param name="somestring2" value="10" type="str" />
|
||||
|
||||
<param name="someinteger1" value="1" type="int" />
|
||||
<param name="someinteger2" value="2" />
|
||||
|
||||
<param name="somefloat1" value="3.14159" type="double" />
|
||||
<param name="somefloat2" value="3.0" />
|
||||
|
||||
<!-- you can set parameters in child namespaces -->
|
||||
<param name="wg/childparam" value="a child namespace parameter" />
|
||||
|
||||
<!-- upload the contents of a file as a param -->
|
||||
<param name="configfile" textfile="$(find roslaunch)/example.launch" />
|
||||
<!-- upload the contents of a file as base64 binary as a param -->
|
||||
<param name="binaryfile" binfile="$(find roslaunch)/example.launch" />
|
||||
<!-- upload the output of a command as a param. -->
|
||||
<param name="commandoutput" command="cat "$(find roslaunch)/example.launch"" />
|
||||
|
||||
<!-- Group a collection of tags. ns attribute is optional -->
|
||||
<group ns="wg">
|
||||
<!-- remap applies to all future nodes in this group -->
|
||||
<remap from="chatter" to="hello"/>
|
||||
|
||||
<node name="listener" pkg="test_ros" type="listener.py" respawn="true" />
|
||||
|
||||
<node name="talker1" pkg="test_ros" type="talker.py">
|
||||
<env name="ENV_EXAMPLE" value="example value" />
|
||||
<remap from="foo" to="bar"/>
|
||||
<!-- params within node tags are equivalent to ~params.
|
||||
You must set the 'name' attribute of a node to use this feature. -->
|
||||
<param name="talker_param" value="a value" />
|
||||
</node>
|
||||
|
||||
<node name="talker2" pkg="test_ros" type="talker.py" />
|
||||
|
||||
</group>
|
||||
|
||||
|
||||
<!-- import another roslaunch config file -->
|
||||
<group ns="included">
|
||||
<include file="$(find roslaunch)/example-include.launch" />
|
||||
</group>
|
||||
<!-- more compact import syntax -->
|
||||
<include ns="included2" file="$(find roslaunch)/example-include.launch" />
|
||||
|
||||
</launch>
|
|
@ -1,27 +0,0 @@
|
|||
<package>
|
||||
<description brief="ROS Process Launcher">
|
||||
|
||||
roslaunch is a tool for easily launching multiple ROS <a href="http://ros.org/wiki/Nodes">nodes</a> locally and remotely via SSH, as well as setting parameters on the <a href="http://ros.org/wiki/Parameter Server">Parameter Server</a>. It includes options to automatically respawn processes that have already died. roslaunch takes in one or more XML configuration files (with the <tt>.launch</tt> extension) that specify the parameters to set and nodes to launch, as well as the machines that they should be run on.
|
||||
|
||||
</description>
|
||||
<author>Ken Conley/kwc@willowgarage.com</author>
|
||||
<license>BSD</license>
|
||||
<review status="Doc reviewed" notes="01/18/2010"/>
|
||||
<url>http://ros.org/wiki/roslaunch</url>
|
||||
<depend package="roslib"/>
|
||||
<depend package="rosclean"/>
|
||||
<depend package="rosgraph"/>
|
||||
<depend package="rospy"/>
|
||||
<depend package="rosmaster"/>
|
||||
<depend package="rosout"/>
|
||||
<rosdep name="paramiko"/>
|
||||
<rosdep name="python-yaml"/>
|
||||
<export>
|
||||
<rosdoc config="rosdoc.yaml"/>
|
||||
</export>
|
||||
<platform os="ubuntu" version="9.04"/>
|
||||
<platform os="ubuntu" version="9.10"/>
|
||||
<platform os="ubuntu" version="10.04"/>
|
||||
<platform os="macports" version="macports"/>
|
||||
</package>
|
||||
|
|
@ -1,10 +0,0 @@
|
|||
<!--
|
||||
ROS Core Stack definition
|
||||
|
||||
Before making any modifications to this file, please read:
|
||||
http://ros.org/wiki/roscore
|
||||
-->
|
||||
<launch>
|
||||
<!-- all the nodes in the core file must have the name attribute specified -->
|
||||
<node pkg="rosout" type="rosout" name="rosout" respawn="true"/>
|
||||
</launch>
|
|
@ -1 +0,0 @@
|
|||
- builder: epydoc
|
|
@ -1,249 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
import os
|
||||
import logging
|
||||
import sys
|
||||
|
||||
import roslaunch.core
|
||||
|
||||
# symbol exports
|
||||
from roslaunch.core import Node, Test, Master, RLException
|
||||
from roslaunch.config import ROSLaunchConfig
|
||||
from roslaunch.launch import ROSLaunchRunner
|
||||
from roslaunch.xmlloader import XmlLoader, XmlParseException
|
||||
|
||||
# script api
|
||||
from roslaunch.scriptapi import ROSLaunch
|
||||
from roslaunch.pmon import Process
|
||||
|
||||
NAME = 'roslaunch'
|
||||
|
||||
def configure_logging(uuid):
|
||||
"""
|
||||
scripts using roslaunch MUST call configure_logging
|
||||
"""
|
||||
try:
|
||||
import socket
|
||||
import roslib.roslogging
|
||||
logfile_basename = os.path.join(uuid, '%s-%s-%s.log'%(NAME, socket.gethostname(), os.getpid()))
|
||||
# additional: names of python packages we depend on that may also be logging
|
||||
logfile_name = roslib.roslogging.configure_logging(NAME, filename=logfile_basename)
|
||||
if logfile_name:
|
||||
print "... logging to %s"%logfile_name
|
||||
|
||||
# add logger to internal roslaunch logging infrastructure
|
||||
logger = logging.getLogger('roslaunch')
|
||||
roslaunch.core.add_printlog_handler(logger.info)
|
||||
roslaunch.core.add_printerrlog_handler(logger.error)
|
||||
except:
|
||||
print >> sys.stderr, "WARNING: unable to configure logging. No log files will be generated"
|
||||
|
||||
def write_pid_file(options_pid_fn, options_core, port):
|
||||
from roslib.rosenv import get_ros_home
|
||||
from rosmaster import DEFAULT_MASTER_PORT
|
||||
if options_pid_fn or options_core:
|
||||
if options_pid_fn:
|
||||
pid_fn = options_pid_fn
|
||||
else:
|
||||
# NOTE: this assumption is not 100% valid until work on #3097 is complete
|
||||
if port is None:
|
||||
port = DEFAULT_MASTER_PORT
|
||||
#2987
|
||||
pid_fn = os.path.join(get_ros_home(), 'roscore-%s.pid'%(port))
|
||||
with open(pid_fn, "w") as f:
|
||||
f.write(str(os.getpid()))
|
||||
|
||||
def _get_optparse():
|
||||
from optparse import OptionParser
|
||||
|
||||
parser = OptionParser(usage="usage: %prog [options] [package] <filename> [arg_name:=value...]", prog=NAME)
|
||||
parser.add_option("--args",
|
||||
dest="node_args", default=None,
|
||||
help="Print command-line arguments for node", metavar="NODE_NAME")
|
||||
parser.add_option("--nodes",
|
||||
dest="node_list", default=False, action="store_true",
|
||||
help="Print list of node names in launch file")
|
||||
parser.add_option("--find-node",
|
||||
dest="find_node", default=None,
|
||||
help="Find launch file that node is defined in", metavar="NODE_NAME")
|
||||
parser.add_option("-c", "--child",
|
||||
dest="child_name", default=None,
|
||||
help="Run as child service 'NAME'. Required with -u", metavar="NAME")
|
||||
parser.add_option("--local",
|
||||
dest="local_only", default=False, action="store_true",
|
||||
help="Do not launch remote nodes")
|
||||
# #2370
|
||||
parser.add_option("--screen",
|
||||
dest="force_screen", default=False, action="store_true",
|
||||
help="Force output of all local nodes to screen")
|
||||
parser.add_option("-u", "--server_uri",
|
||||
dest="server_uri", default=None,
|
||||
help="URI of server. Required with -c", metavar="URI")
|
||||
parser.add_option("--run_id",
|
||||
dest="run_id", default=None,
|
||||
help="run_id of session. Required with -c", metavar="RUN_ID")
|
||||
# #1254: wait until master comes online before starting
|
||||
parser.add_option("--wait", action="store_true",
|
||||
dest="wait_for_master", default=False,
|
||||
help="wait for master to start before launching")
|
||||
parser.add_option("-p", "--port",
|
||||
dest="port", default=None,
|
||||
help="master port. Only valid if master is launched", metavar="PORT")
|
||||
parser.add_option("--core", action="store_true",
|
||||
dest="core", default=False,
|
||||
help="Launch core services only")
|
||||
parser.add_option("--pid",
|
||||
dest="pid_fn", default="",
|
||||
help="write the roslaunch pid to filename")
|
||||
parser.add_option("-v", action="store_true",
|
||||
dest="verbose", default=False,
|
||||
help="verbose printing")
|
||||
return parser
|
||||
|
||||
def _validate_args(parser, options, args):
|
||||
# validate args first so we don't spin up any resources
|
||||
if options.child_name:
|
||||
if not options.server_uri:
|
||||
parser.error("--child option requires --server_uri to be set as well")
|
||||
if not options.run_id:
|
||||
parser.error("--child option requires --run_id to be set as well")
|
||||
if options.port:
|
||||
parser.error("port option cannot be used with roslaunch child mode")
|
||||
if args:
|
||||
parser.error("Input files are not allowed when run in child mode")
|
||||
elif options.core:
|
||||
if args:
|
||||
parser.error("Input files are not allowed when launching core")
|
||||
if options.run_id:
|
||||
parser.error("--run_id should only be set for child roslaunches (-c)")
|
||||
|
||||
# we don't actually do anything special for core as the roscore.xml file
|
||||
# is an implicit include for any roslaunch
|
||||
|
||||
elif len(args) == 0:
|
||||
parser.error("you must specify at least one input file")
|
||||
elif [f for f in args if not os.path.exists(f)]:
|
||||
parser.error("The following input files do not exist: %s"%f)
|
||||
|
||||
if len([x for x in [options.node_list, options.find_node, options.node_args] if x]) > 1:
|
||||
parser.error("only one of [--nodes, --find-node, --args] may be specified")
|
||||
|
||||
def main(argv=sys.argv):
|
||||
options = None
|
||||
try:
|
||||
import roslaunch.rlutil
|
||||
parser = _get_optparse()
|
||||
|
||||
(options, args) = parser.parse_args(argv[1:])
|
||||
args = roslaunch.rlutil.resolve_launch_arguments(args)
|
||||
_validate_args(parser, options, args)
|
||||
|
||||
# node args doesn't require any roslaunch infrastructure, so process it first
|
||||
if options.node_args or options.node_list or options.find_node:
|
||||
if options.node_args and not args:
|
||||
parser.error("please specify a launch file")
|
||||
import roslaunch.node_args
|
||||
if options.node_args:
|
||||
roslaunch.node_args.print_node_args(options.node_args, args)
|
||||
elif options.find_node:
|
||||
roslaunch.node_args.print_node_filename(options.find_node, args)
|
||||
else:
|
||||
roslaunch.node_args.print_node_list(args)
|
||||
return
|
||||
|
||||
# we have to wait for the master here because we don't have the run_id yet
|
||||
if options.wait_for_master:
|
||||
if options.core:
|
||||
parser.error("--wait cannot be used with roscore")
|
||||
roslaunch.rlutil._wait_for_master()
|
||||
|
||||
# write the pid to a file
|
||||
write_pid_file(options.pid_fn, options.core, options.port)
|
||||
|
||||
# spin up the logging infrastructure. have to wait until we can read options.run_id
|
||||
uuid = roslaunch.rlutil.get_or_generate_uuid(options.run_id, options.wait_for_master)
|
||||
configure_logging(uuid)
|
||||
|
||||
# #3088: don't check disk usage on remote machines
|
||||
if not options.child_name:
|
||||
# #2761
|
||||
roslaunch.rlutil.check_log_disk_usage()
|
||||
|
||||
logger = logging.getLogger('roslaunch')
|
||||
logger.info("roslaunch starting with args %s"%str(argv))
|
||||
logger.info("roslaunch env is %s"%os.environ)
|
||||
|
||||
if options.child_name:
|
||||
logger.info('starting in child mode')
|
||||
|
||||
# This is a roslaunch child, spin up client server.
|
||||
# client spins up an XML-RPC server that waits for
|
||||
# commands and configuration from the server.
|
||||
import roslaunch.child
|
||||
c = roslaunch.child.ROSLaunchChild(uuid, options.child_name, options.server_uri)
|
||||
c.run()
|
||||
else:
|
||||
logger.info('starting in server mode')
|
||||
|
||||
# #1491 change terminal name
|
||||
roslaunch.rlutil.change_terminal_name(args, options.core)
|
||||
|
||||
# This is a roslaunch parent, spin up parent server and launch processes.
|
||||
# args are the roslaunch files to load
|
||||
import roslaunch.parent
|
||||
try:
|
||||
p = roslaunch.parent.ROSLaunchParent(uuid, args, is_core=options.core, port=options.port, local_only=options.local_only, verbose=options.verbose, force_screen=options.force_screen)
|
||||
p.start()
|
||||
p.spin()
|
||||
finally:
|
||||
# remove the pid file
|
||||
if options.pid_fn:
|
||||
try: os.unlink(options.pid_fn)
|
||||
except os.error, reason: pass
|
||||
|
||||
except RLException, e:
|
||||
roslaunch.core.printerrlog(str(e))
|
||||
sys.exit(1)
|
||||
except ValueError, e:
|
||||
# TODO: need to trap better than this high-level trap
|
||||
roslaunch.core.printerrlog(str(e))
|
||||
sys.exit(1)
|
||||
except Exception, e:
|
||||
import traceback
|
||||
traceback.print_exc()
|
||||
sys.exit(1)
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
|
@ -1,127 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
ROSLaunch child server.
|
||||
|
||||
ROSLaunch has a client/server architecture for running remote
|
||||
processes. When a user runs roslaunch, this creates a "parent"
|
||||
roslaunch process. This parent process will then start "child"
|
||||
processes on remote machines. The parent can then invoke methods on
|
||||
this child process to launch remote processes, and the child can
|
||||
invoke methods on the parent to provide feedback.
|
||||
"""
|
||||
|
||||
import logging
|
||||
import sys
|
||||
import time
|
||||
import traceback
|
||||
|
||||
import roslaunch.core
|
||||
import roslaunch.pmon
|
||||
import roslaunch.server
|
||||
|
||||
class ROSLaunchChild(object):
|
||||
"""
|
||||
ROSLaunchChild infrastructure.
|
||||
|
||||
This must be called from the Python Main thread due to signal registration.
|
||||
"""
|
||||
|
||||
def __init__(self, run_id, name, server_uri):
|
||||
"""
|
||||
Startup roslaunch remote client XML-RPC services. Blocks until shutdown
|
||||
@param run_id: UUID of roslaunch session
|
||||
@type run_id: str
|
||||
@param name: name of remote client
|
||||
@type name: str
|
||||
@param server_uri: XML-RPC URI of roslaunch server
|
||||
@type server_uri: str
|
||||
@return: XML-RPC URI
|
||||
@rtype: str
|
||||
"""
|
||||
roslaunch.core.set_child_mode(True)
|
||||
|
||||
self.logger = logging.getLogger("roslaunch.child")
|
||||
self.run_id = run_id
|
||||
self.name = name
|
||||
self.server_uri = server_uri
|
||||
self.child_server = None
|
||||
self.pm = None
|
||||
|
||||
roslaunch.pmon._init_signal_handlers()
|
||||
|
||||
def _start_pm(self):
|
||||
"""
|
||||
Start process monitor for child roslaunch
|
||||
"""
|
||||
# start process monitor
|
||||
# - this test is mainly here so that testing logic can
|
||||
# override process monitor with a mock
|
||||
if self.pm is None:
|
||||
self.pm = roslaunch.pmon.start_process_monitor()
|
||||
if self.pm is None:
|
||||
# this should only happen if a shutdown signal is received during startup
|
||||
raise roslaunch.core.RLException("cannot startup remote child: unable to start process monitor.")
|
||||
self.logger.debug("started process monitor")
|
||||
|
||||
def run(self):
|
||||
"""
|
||||
Runs child. Blocks until child processes exit.
|
||||
"""
|
||||
try:
|
||||
try:
|
||||
self.logger.info("starting roslaunch child process [%s], server URI is [%s]", self.name, self.server_uri)
|
||||
self._start_pm()
|
||||
self.child_server = roslaunch.server.ROSLaunchChildNode(self.run_id, self.name, self.server_uri, self.pm)
|
||||
self.logger.info("... creating XMLRPC server for child")
|
||||
self.child_server.start()
|
||||
self.logger.info("... started XMLRPC server for child")
|
||||
# block until process monitor is shutdown
|
||||
self.pm.mainthread_spin()
|
||||
self.logger.info("... process monitor is done spinning")
|
||||
except:
|
||||
self.logger.error(traceback.format_exc())
|
||||
raise
|
||||
finally:
|
||||
if self.pm:
|
||||
self.pm.shutdown()
|
||||
self.pm.join()
|
||||
if self.child_server:
|
||||
self.child_server.shutdown('roslaunch child complete')
|
||||
|
||||
def shutdown(self):
|
||||
if self.pm:
|
||||
self.pm.shutdown()
|
||||
self.pm.join()
|
|
@ -1,410 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id: launch.py 2165 2008-09-17 22:38:49Z sfkwc $
|
||||
|
||||
"""
|
||||
Defines the L{ROSLaunchConfig} object, which holds and the state of
|
||||
the roslaunch file.
|
||||
"""
|
||||
|
||||
import os
|
||||
import logging
|
||||
import sys
|
||||
import types
|
||||
|
||||
import roslib.names
|
||||
|
||||
from roslaunch.core import Master, local_machine, get_ros_root, is_machine_local, RLException
|
||||
from roslaunch.rlutil import namespaces_of
|
||||
import roslaunch.loader
|
||||
import roslaunch.xmlloader
|
||||
|
||||
def load_roscore(loader, config, verbose=True):
|
||||
"""
|
||||
Load roscore configuration into the ROSLaunchConfig using the specified XmlLoader
|
||||
@param config ROSLaunchConfig
|
||||
@param loader XmlLoader
|
||||
"""
|
||||
import roslib.packages
|
||||
f_roscore = os.path.join(roslib.packages.get_pkg_dir('roslaunch'), 'roscore.xml')
|
||||
logging.getLogger('roslaunch').info('loading roscore config file %s'%f_roscore)
|
||||
loader.load(f_roscore, config, core=True, verbose=verbose)
|
||||
|
||||
def _summary_name(node):
|
||||
"""
|
||||
Generate summary label for node based on its package, type, and name
|
||||
"""
|
||||
if node.name:
|
||||
return "%s (%s/%s)"%(node.name, node.package, node.type)
|
||||
else:
|
||||
return "%s/%s"%(node.package, node.type)
|
||||
|
||||
class ROSLaunchConfig(object):
|
||||
"""
|
||||
ROSLaunchConfig is the container for the loaded roslaunch file state. It also
|
||||
is responsible for validating then executing the desired state.
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
"""
|
||||
Initialize an empty config object. Master defaults to the environment's master.
|
||||
"""
|
||||
self.master = Master()
|
||||
self.nodes_core = []
|
||||
self.nodes = [] #nodes are unnamed
|
||||
|
||||
# list of resolved node names. This is so that we can check for naming collisions
|
||||
self.resolved_node_names = []
|
||||
|
||||
self.tests = []
|
||||
self.machines = {} #key is name
|
||||
self.params = {} #key is name
|
||||
self.clear_params = []
|
||||
self.executables = []
|
||||
|
||||
# for tools like roswtf
|
||||
self.config_errors = []
|
||||
|
||||
m = local_machine() #for local exec
|
||||
self.machines[m.name] = m
|
||||
self._assign_machines_complete = False
|
||||
self._remote_nodes_present = None
|
||||
|
||||
self.logger = logging.getLogger('roslaunch')
|
||||
|
||||
def add_config_error(self, msg):
|
||||
"""
|
||||
Report human-readable error message related to configuration error
|
||||
@param msg: error message
|
||||
@type msg: str
|
||||
"""
|
||||
self.config_errors.append(msg)
|
||||
|
||||
def set_master(self, m):
|
||||
"""
|
||||
Set the master configuration
|
||||
@param m: Master
|
||||
@type m: L{Master}
|
||||
"""
|
||||
self.master = m
|
||||
|
||||
def has_remote_nodes(self):
|
||||
"""
|
||||
@return: True if roslaunch will launch nodes on a remote machine
|
||||
@rtype: bool
|
||||
"""
|
||||
if not self._assign_machines_complete:
|
||||
raise Exception("ERROR: has_remote_nodes() cannot be called until prelaunch check is complete")
|
||||
return self._remote_nodes_present
|
||||
|
||||
def assign_machines(self):
|
||||
"""
|
||||
Assign nodes to machines and determine whether or not there are any remote machines
|
||||
"""
|
||||
# don't repeat machine assignment
|
||||
if self._assign_machines_complete:
|
||||
return
|
||||
|
||||
machine_unify_dict = {}
|
||||
|
||||
self._assign_machines_complete = True
|
||||
# #653: current have to set all core nodes to local launch
|
||||
local_machine = self.machines['']
|
||||
for n in self.nodes_core:
|
||||
n.machine = local_machine
|
||||
|
||||
#for n in self.nodes_core + self.nodes + self.tests:
|
||||
for n in self.nodes + self.tests:
|
||||
m = self._select_machine(n)
|
||||
|
||||
# if machines have the same config keys it means that they are identical except
|
||||
# for their name. we unify the machine assignments so that we don't use
|
||||
# extra resources.
|
||||
config_key = m.config_key()
|
||||
if config_key in machine_unify_dict:
|
||||
new_m = machine_unify_dict[config_key]
|
||||
if m != new_m:
|
||||
self.logger.info("... changing machine assignment from [%s] to [%s] as they are equivalent", m.name, new_m.name)
|
||||
m = new_m
|
||||
else:
|
||||
machine_unify_dict[config_key] = m
|
||||
n.machine = m
|
||||
self.logger.info("... selected machine [%s] for node of type [%s/%s]", m.name, n.package, n.type)
|
||||
|
||||
# determine whether or not there are any machines we will need
|
||||
# to setup remote roslaunch clients for
|
||||
self._remote_nodes_present = False
|
||||
if [m for m in machine_unify_dict.itervalues() if not is_machine_local(m)]:
|
||||
self._remote_nodes_present = True
|
||||
|
||||
def validate(self):
|
||||
"""
|
||||
Perform basic checks on the local ROS environment, master, and core services.
|
||||
master will be launched if configured to do so. Core services will be launched regardless.
|
||||
if they are not already running.
|
||||
|
||||
@raise RLException: if validation fails
|
||||
"""
|
||||
ros_root = get_ros_root()
|
||||
if not os.path.isdir(ros_root):
|
||||
raise RLException("ERROR: ROS_ROOT is not configured properly. Value is [%s]"%ros_root)
|
||||
|
||||
def summary(self, local=False):
|
||||
"""
|
||||
Get a human-readable string summary of the launch
|
||||
@param local bool: if True, only print local nodes
|
||||
@return: summary
|
||||
@rtype: str
|
||||
"""
|
||||
summary = '\nSUMMARY\n========'
|
||||
if self.clear_params:
|
||||
summary += '\n\nCLEAR PARAMETERS\n' + '\n'.join([' * %s'%p for p in self.clear_params])
|
||||
if self.params:
|
||||
summary += '\n\nPARAMETERS\n' + '\n'.join([' * %s'%k for k in self.params])
|
||||
if not local:
|
||||
summary += '\n\nMACHINES\n' + '\n'.join([' * %s'%k for k in self.machines if k])
|
||||
summary += '\n\nNODES\n'
|
||||
namespaces = {}
|
||||
if local:
|
||||
nodes = [n for n in self.nodes if is_machine_local(n.machine)]
|
||||
else:
|
||||
nodes = self.nodes
|
||||
for n in nodes:
|
||||
ns = n.namespace
|
||||
if ns not in namespaces:
|
||||
namespaces[ns] = [n]
|
||||
else:
|
||||
namespaces[ns].append(n)
|
||||
for k,v in namespaces.iteritems():
|
||||
summary += ' %s\n'%k + '\n'.join([' %s'%_summary_name(n) for n in v])
|
||||
summary += '\n'
|
||||
return summary
|
||||
|
||||
def add_executable(self, exe):
|
||||
"""
|
||||
Declare an exectuable to be run during the launch
|
||||
@param exe: Executable
|
||||
@type exe: L{Executable}
|
||||
"""
|
||||
if not exe:
|
||||
raise ValueError("exe is None")
|
||||
self.executables.append(exe)
|
||||
|
||||
def add_clear_param(self, param):
|
||||
"""
|
||||
Declare a parameter to be cleared before new parameters are set
|
||||
@param param: parameter to clear
|
||||
@type param: str
|
||||
"""
|
||||
self.clear_params.append(param)
|
||||
|
||||
def add_param(self, p, filename=None, verbose=True):
|
||||
"""
|
||||
Declare a parameter to be set on the param server before launching nodes
|
||||
@param p: parameter instance
|
||||
@type p: L{Param}
|
||||
"""
|
||||
key = p.key
|
||||
|
||||
# check for direct overrides
|
||||
if key in self.params and self.params[key] != p:
|
||||
if filename:
|
||||
self.logger.debug("[%s] overriding parameter [%s]"%(filename, p.key))
|
||||
else:
|
||||
self.logger.debug("overriding parameter [%s]"%p.key)
|
||||
# check for parent conflicts
|
||||
for parent_key in [pk for pk in namespaces_of(key) if pk in self.params]:
|
||||
self.add_config_error("parameter [%s] conflicts with parent parameter [%s]"%(key, parent_key))
|
||||
|
||||
self.params[key] = p
|
||||
if verbose:
|
||||
print "Added parameter [%s]"%key
|
||||
t = type(p.value)
|
||||
if t in [str, unicode, types.InstanceType]:
|
||||
self.logger.debug("add_param[%s]: type [%s]"%(p.key, t))
|
||||
else:
|
||||
self.logger.debug("add_param[%s]: type [%s] value [%s]"%(p.key, t, p.value))
|
||||
|
||||
def add_machine(self, m, verbose=True):
|
||||
"""
|
||||
Declare a machine and associated parameters so that it can be used for
|
||||
running nodes.
|
||||
@param m: machine instance
|
||||
@type m: L{Machine}
|
||||
@return: True if new machine added, False if machine already specified.
|
||||
@rtype: bool
|
||||
@raise RLException: if cannot add machine as specified
|
||||
"""
|
||||
name = m.name
|
||||
if m.address == 'localhost': #simplify address comparison
|
||||
import roslib.network
|
||||
address = roslib.network.get_local_address()
|
||||
self.logger.info("addMachine[%s]: remapping localhost address to %s"%(name, address))
|
||||
if name in self.machines:
|
||||
if m != self.machines[name]:
|
||||
raise RLException("Machine [%s] already added and does not match duplicate entry"%name)
|
||||
return False
|
||||
else:
|
||||
self.machines[name] = m
|
||||
if verbose:
|
||||
print "Added machine [%s]"%name
|
||||
return True
|
||||
|
||||
def add_test(self, test, verbose=True):
|
||||
"""
|
||||
Add test declaration. Used by rostest
|
||||
@param test: test node instance to add to launch
|
||||
@type test: L{Test}
|
||||
"""
|
||||
self.tests.append(test)
|
||||
|
||||
def add_node(self, node, core=False, verbose=True):
|
||||
"""
|
||||
Add node declaration
|
||||
@param node: node instance to add to launch
|
||||
@type node: L{Node}
|
||||
@param core: if True, node is a ROS core node
|
||||
@type core: bool
|
||||
@raise RLException: if ROS core node is missing required name
|
||||
"""
|
||||
if node.name:
|
||||
# check for duplicates
|
||||
resolved_name = roslib.names.ns_join(node.namespace, node.name)
|
||||
matches = [n for n in self.resolved_node_names if n == resolved_name]
|
||||
if matches:
|
||||
raise RLException("roslaunch file contains multiple nodes named [%s].\nPlease check all <node> 'name' attributes to make sure they are unique.\nAlso check that $(anon id) use different ids."%resolved_name)
|
||||
else:
|
||||
self.resolved_node_names.append(resolved_name)
|
||||
|
||||
if not core:
|
||||
self.nodes.append(node)
|
||||
if verbose:
|
||||
print "Added node of type [%s/%s] in namespace [%s]"%(node.package, node.type, node.namespace)
|
||||
self.logger.info("Added node of type [%s/%s] in namespace [%s]", node.package, node.type, node.namespace)
|
||||
else:
|
||||
if not node.name:
|
||||
raise RLException("ROS core nodes must have a name. [%s/%s]"%(node.package, node.type))
|
||||
self.nodes_core.append(node)
|
||||
if verbose:
|
||||
print "Added core node of type [%s/%s] in namespace [%s]"%(node.package, node.type, node.namespace)
|
||||
self.logger.info("Added core node of type [%s/%s] in namespace [%s]", node.package, node.type, node.namespace)
|
||||
|
||||
def _select_machine(self, node):
|
||||
"""
|
||||
Select a machine for a node to run on. For nodes that are
|
||||
already assigned to a machine, this will map the string name to
|
||||
a L{Machine} instance. If the node isn't already tagged with a
|
||||
particular machine, one will be selected for it.
|
||||
@param node: node to assign machine for
|
||||
@type node: L{Node}
|
||||
@return: machine to run on
|
||||
@rtype: L{Machine}
|
||||
@raise RLException: If machine state is improperly configured
|
||||
"""
|
||||
machine = node.machine_name
|
||||
#Lookup machine
|
||||
if machine:
|
||||
if not machine in self.machines:
|
||||
raise RLException("ERROR: unknown machine [%s]"%machine)
|
||||
return self.machines[machine]
|
||||
else:
|
||||
# assign to local machine
|
||||
return self.machines['']
|
||||
|
||||
def load_config_default(roslaunch_files, port, roslaunch_strs=None, loader=None, verbose=False, assign_machines=True):
|
||||
"""
|
||||
Base routine for creating a ROSLaunchConfig from a set of
|
||||
roslaunch_files and or launch XML strings and initializing it. This
|
||||
config will have a core definition and also set the master to run
|
||||
on port.
|
||||
@param roslaunch_files: list of launch files to load
|
||||
@type roslaunch_files: [str]
|
||||
@param port: roscore/master port override. Set to 0 or None to use default.
|
||||
@type port: int
|
||||
@param roslaunch_strs: (optional) roslaunch XML strings to load
|
||||
@type roslaunch_strs: [str]
|
||||
@param verbose: (optional) print info to screen about model as it is loaded.
|
||||
@type verbose: bool
|
||||
@param assign_machines: (optional) assign nodes to machines (default: True)
|
||||
@type assign_machines: bool
|
||||
@return: initialized rosconfig instance
|
||||
@rytpe: L{ROSLaunchConfig} initialized rosconfig instance
|
||||
"""
|
||||
logger = logging.getLogger('roslaunch.config')
|
||||
|
||||
# This is the main roslaunch server process. Load up the
|
||||
# files specified on the command line and launch the
|
||||
# requested resourcs.
|
||||
|
||||
config = ROSLaunchConfig()
|
||||
loader = loader or roslaunch.xmlloader.XmlLoader()
|
||||
|
||||
# load the roscore file first. we currently have
|
||||
# last-declaration wins rules. roscore is just a
|
||||
# roslaunch file with special load semantics
|
||||
load_roscore(loader, config, verbose=verbose)
|
||||
|
||||
# load the roslaunch_files into the config
|
||||
for f in roslaunch_files:
|
||||
try:
|
||||
logger.info('loading config file %s'%f)
|
||||
loader.load(f, config, verbose=verbose)
|
||||
except roslaunch.xmlloader.XmlParseException, e:
|
||||
raise RLException(e)
|
||||
except roslaunch.loader.LoadException, e:
|
||||
raise RLException(e)
|
||||
|
||||
# we need this for the hardware test systems, which builds up
|
||||
# roslaunch launch files in memory
|
||||
if roslaunch_strs:
|
||||
for launch_str in roslaunch_strs:
|
||||
try:
|
||||
logger.info('loading config file from string')
|
||||
loader.load_string(launch_str, config)
|
||||
except roslaunch.xmlloader.XmlParseException, e:
|
||||
raise RLException('Launch string: %s\nException: %s'%(launch_str, e))
|
||||
except roslaunch.loader.LoadException, e:
|
||||
raise RLException('Launch string: %s\nException: %s'%(launch_str, e))
|
||||
|
||||
if port:
|
||||
logger.info("overriding master port to %s"%port)
|
||||
config.master.set_port(port)
|
||||
|
||||
# make sure our environment is correct
|
||||
config.validate()
|
||||
|
||||
# choose machines for the nodes
|
||||
if assign_machines:
|
||||
config.assign_machines()
|
||||
return config
|
||||
|
|
@ -1,750 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Core roslaunch model and lower-level utility routines.
|
||||
"""
|
||||
|
||||
import os
|
||||
import logging
|
||||
import socket
|
||||
import sys
|
||||
import xmlrpclib
|
||||
|
||||
|
||||
import roslib.names
|
||||
import roslib.network
|
||||
import roslib.substitution_args
|
||||
import roslib.rosenv
|
||||
|
||||
#TODO:temporary until xacro is ported after next ROS stable release
|
||||
resolve_args = roslib.substitution_args.resolve_args
|
||||
|
||||
class RLException(Exception):
|
||||
"""Base roslaunch exception type"""
|
||||
pass
|
||||
|
||||
|
||||
## Phases allow executables to be assigned to a particular run period
|
||||
PHASE_SETUP = 'setup'
|
||||
PHASE_RUN = 'run'
|
||||
PHASE_TEARDOWN = 'teardown'
|
||||
|
||||
_child_mode = False
|
||||
def is_child_mode():
|
||||
"""
|
||||
@return: True if roslaunch is running in remote child mode
|
||||
@rtype: bool
|
||||
"""
|
||||
return _child_mode
|
||||
def set_child_mode(child_mode):
|
||||
"""
|
||||
@param child_mode: True if roslaunch is running in remote
|
||||
child mode
|
||||
@type child_mode: bool
|
||||
"""
|
||||
global _child_mode
|
||||
_child_mode = child_mode
|
||||
|
||||
def is_machine_local(machine):
|
||||
"""
|
||||
Check to see if machine is local. NOTE: a machine is not local if
|
||||
its user credentials do not match the current user.
|
||||
@param machine: Machine
|
||||
@type machine: L{Machine}
|
||||
@return: True if machine is local and doesn't require remote login
|
||||
@rtype: bool
|
||||
"""
|
||||
try:
|
||||
machine_addr = socket.gethostbyname(machine.address)
|
||||
except socket.gaierror:
|
||||
raise RLException("cannot resolve host address for machine [%s]"%machine.address)
|
||||
local_addresses = ['localhost'] + roslib.network.get_local_addresses()
|
||||
# check 127/8 and local addresses
|
||||
is_local = machine_addr.startswith('127.') or machine_addr in local_addresses
|
||||
|
||||
#491: override local to be ssh if machine.user != local user
|
||||
if is_local and machine.user:
|
||||
import getpass
|
||||
is_local = machine.user == getpass.getuser()
|
||||
return is_local
|
||||
|
||||
_printlog_handlers = []
|
||||
_printerrlog_handlers = []
|
||||
def printlog(msg):
|
||||
"""
|
||||
Core utility for printing message to stdout as well as printlog handlers
|
||||
@param msg: message to print
|
||||
@type msg: str
|
||||
"""
|
||||
for h in _printlog_handlers:
|
||||
try: # don't let this bomb out the actual code
|
||||
h(msg)
|
||||
except:
|
||||
pass
|
||||
try: # don't let this bomb out the actual code
|
||||
print msg
|
||||
except:
|
||||
pass
|
||||
|
||||
def printlog_bold(msg):
|
||||
"""
|
||||
Similar to L{printlog()}, but the message printed to screen is bolded for greater clarity
|
||||
@param msg: message to print
|
||||
@type msg: str
|
||||
"""
|
||||
for h in _printlog_handlers:
|
||||
try: # don't let this bomb out the actual code
|
||||
h(msg)
|
||||
except:
|
||||
pass
|
||||
try: # don't let this bomb out the actual code
|
||||
print '\033[1m%s\033[0m'%msg
|
||||
except:
|
||||
pass
|
||||
|
||||
def printerrlog(msg):
|
||||
"""
|
||||
Core utility for printing message to stderr as well as printerrlog handlers
|
||||
@param msg: message to print
|
||||
@type msg: str
|
||||
"""
|
||||
for h in _printerrlog_handlers:
|
||||
try: # don't let this bomb out the actual code
|
||||
h(msg)
|
||||
except:
|
||||
pass
|
||||
# #1003: this has raised IOError (errno 104) in robot use. Better to
|
||||
# trap than let a debugging routine fault code.
|
||||
try: # don't let this bomb out the actual code
|
||||
print >> sys.stderr, '\033[31m%s\033[0m'%msg
|
||||
except:
|
||||
pass
|
||||
|
||||
def add_printlog_handler(h):
|
||||
"""
|
||||
Register additional handler for printlog()
|
||||
"""
|
||||
_printlog_handlers.append(h)
|
||||
|
||||
def add_printerrlog_handler(h):
|
||||
"""
|
||||
Register additional handler for printerrlog()
|
||||
"""
|
||||
_printerrlog_handlers.append(h)
|
||||
|
||||
def clear_printlog_handlers():
|
||||
"""
|
||||
Delete all printlog handlers. required for testing
|
||||
"""
|
||||
del _printlog_handlers[:]
|
||||
|
||||
def clear_printerrlog_handlers():
|
||||
"""
|
||||
Delete all printerrlog handlers. required for testing
|
||||
"""
|
||||
del _printerrlog_handlers[:]
|
||||
|
||||
def setup_env(node, machine, master_uri):
|
||||
"""
|
||||
Create dictionary of environment variables to set for launched
|
||||
process.
|
||||
|
||||
setup_env() will only set ROS_*, PYTHONPATH, and user-specified
|
||||
environment variables.
|
||||
|
||||
@param machine Machine: machine being launched on
|
||||
@type machine: L{Machine}
|
||||
@param node: node that is being launched or None
|
||||
@type node: L{Node}
|
||||
@param master_uri: ROS master URI
|
||||
@type master_uri: str
|
||||
@return: process env dictionary
|
||||
@rtype: dict
|
||||
"""
|
||||
d = {}
|
||||
d[roslib.rosenv.ROS_MASTER_URI] = master_uri
|
||||
d[roslib.rosenv.ROS_ROOT] = machine.ros_root or get_ros_root()
|
||||
if machine.ros_package_path: #optional
|
||||
d[roslib.rosenv.ROS_PACKAGE_PATH] = machine.ros_package_path
|
||||
if machine.ros_ip: #optional
|
||||
d[roslib.rosenv.ROS_IP] = machine.ros_ip
|
||||
|
||||
# roslib now depends on PYTHONPATH being set. This environment
|
||||
# needs to be setup correctly for roslaunch through ssh to work
|
||||
d['PYTHONPATH'] = os.path.join(d[roslib.rosenv.ROS_ROOT],'core','roslib', 'src')
|
||||
|
||||
# load in machine env_args. Node env args have precedence
|
||||
for name, value in machine.env_args:
|
||||
d[name] = value
|
||||
|
||||
# add node-specific env args last as they have highest precedence
|
||||
if node:
|
||||
ns = node.namespace
|
||||
if ns[-1] == '/':
|
||||
ns = ns[:-1]
|
||||
if ns:
|
||||
d[roslib.rosenv.ROS_NAMESPACE] = ns
|
||||
for name, value in node.env_args:
|
||||
d[name] = value
|
||||
|
||||
return d
|
||||
|
||||
def rle_wrapper(fn):
|
||||
"""
|
||||
Wrap lower-level exceptions in RLException class
|
||||
@return: function wrapper that throws an RLException if the
|
||||
wrapped function throws an Exception
|
||||
@rtype: fn
|
||||
"""
|
||||
def wrapped_fn(*args):
|
||||
try:
|
||||
return fn(*args)
|
||||
except Exception, e:
|
||||
# we specifically catch RLExceptions and print their messages differently
|
||||
raise RLException("ERROR: %s"%e)
|
||||
return wrapped_fn
|
||||
|
||||
get_ros_root = rle_wrapper(roslib.rosenv.get_ros_root)
|
||||
get_master_uri_env = rle_wrapper(roslib.rosenv.get_master_uri)
|
||||
def get_ros_package_path():
|
||||
"""
|
||||
@return: ROS_PACKAGE_PATH value
|
||||
@rtype: str
|
||||
"""
|
||||
# ROS_PACKAGE_PATH not required to be set
|
||||
return roslib.rosenv.get_ros_package_path(required=False)
|
||||
|
||||
def remap_localhost_uri(uri, force_localhost=False):
|
||||
"""
|
||||
Resolve localhost addresses to an IP address so that
|
||||
@param uri: XML-RPC URI
|
||||
@type uri: str
|
||||
@param force_localhost: if True, URI is mapped onto the local machine no matter what
|
||||
@type force_localhost: bool
|
||||
"""
|
||||
hostname, port = roslib.network.parse_http_host_and_port(uri)
|
||||
if force_localhost or hostname == 'localhost':
|
||||
return roslib.network.create_local_xmlrpc_uri(port)
|
||||
else:
|
||||
return uri
|
||||
|
||||
##################################################################
|
||||
# DATA STRUCTURES
|
||||
|
||||
class Master:
|
||||
"""
|
||||
Data structure for representing and querying state of master
|
||||
"""
|
||||
__slots__ = ['type', 'auto', 'uri', 'log_output']
|
||||
## don't start a master
|
||||
AUTO_NO = 0
|
||||
## start a master if one isn't running
|
||||
AUTO_START = 1
|
||||
## start/restart master (i.e. restart an existing master)
|
||||
AUTO_RESTART = 2
|
||||
ROSMASTER = 'rosmaster'
|
||||
|
||||
# deprecated
|
||||
ZENMASTER = 'zenmaster'
|
||||
|
||||
def __init__(self, type_=None, uri=None, auto=None):
|
||||
"""
|
||||
Create new Master instance.
|
||||
@param uri: master URI
|
||||
@type uri: str
|
||||
@param type_: Currently only support 'rosmaster'
|
||||
@type type_: str
|
||||
@param auto: AUTO_NO | AUTO_START | AUTO_RESTART. AUTO_NO
|
||||
is the default
|
||||
@type auto: int
|
||||
"""
|
||||
if auto is not None and type(auto) != int:
|
||||
raise RLException("invalid auto value: %s"%auto)
|
||||
self.type = type_ or Master.ROSMASTER
|
||||
self.auto = auto or Master.AUTO_NO
|
||||
if self.auto not in [Master.AUTO_NO, Master.AUTO_START, Master.AUTO_RESTART]:
|
||||
raise RLException("invalid auto value: %s"%auto)
|
||||
self.uri = remap_localhost_uri(uri or get_master_uri_env())
|
||||
# by default, master output goes to screen
|
||||
self.log_output = False
|
||||
|
||||
def __eq__(self, m2):
|
||||
if not isinstance(m2, Master):
|
||||
return False
|
||||
else:
|
||||
return m2.auto == self.auto and m2.type == self.type and m2.uri == self.uri and m2.log_output == self.log_output
|
||||
|
||||
def get(self):
|
||||
"""
|
||||
@return: XMLRPC proxy for communicating with master
|
||||
@rtype: xmlrpclib.ServerProxy
|
||||
"""
|
||||
return xmlrpclib.ServerProxy(self.uri)
|
||||
|
||||
def get_multi(self):
|
||||
"""
|
||||
@return: multicall XMLRPC proxy for communicating with master
|
||||
@rtype: xmlrpclib.MultiCall
|
||||
"""
|
||||
return xmlrpclib.MultiCall(self.get())
|
||||
|
||||
def set_port(self, port):
|
||||
"""
|
||||
Override port specification of Master. This only has an effect on masters that have not
|
||||
been launched yet.
|
||||
@param port: port
|
||||
@type port: int
|
||||
"""
|
||||
host, _ = roslib.network.parse_http_host_and_port(self.uri)
|
||||
self.uri = 'http://%s:%s/'%(host, port)
|
||||
|
||||
def is_running(self):
|
||||
"""
|
||||
Check if master is running.
|
||||
@return: True if the master is running
|
||||
@rtype: bool
|
||||
"""
|
||||
try:
|
||||
try:
|
||||
to_orig = socket.getdefaulttimeout()
|
||||
# enable timeout
|
||||
socket.setdefaulttimeout(5.0)
|
||||
logging.getLogger('roslaunch').info('master.is_running[%s]'%self.uri)
|
||||
code, status, val = self.get().getPid('/roslaunch')
|
||||
if code != 1:
|
||||
raise RLException("ERROR: master failed status check: %s"%msg)
|
||||
logging.getLogger('roslaunch.core').debug('master.is_running[%s]: True'%self.uri)
|
||||
return True
|
||||
finally:
|
||||
socket.setdefaulttimeout(to_orig)
|
||||
except:
|
||||
logging.getLogger('roslaunch.core').debug('master.is_running[%s]: True'%self.uri)
|
||||
return False
|
||||
|
||||
## number of seconds that a child machine is allowed to register with
|
||||
## the parent before being considered failed
|
||||
_DEFAULT_REGISTER_TIMEOUT = 10.0
|
||||
|
||||
class Machine(object):
|
||||
"""
|
||||
Data structure for storing information about a machine in the ROS
|
||||
system. Corresponds to the 'machine' tag in the launch
|
||||
specification.
|
||||
"""
|
||||
__slots__ = ['name', 'ros_root', 'ros_package_path', 'ros_ip',\
|
||||
'address', 'ssh_port', 'user', 'password', 'assignable',\
|
||||
'env_args', 'timeout']
|
||||
def __init__(self, name, ros_root, ros_package_path, \
|
||||
address, ros_ip=None, ssh_port=22, user=None, password=None, \
|
||||
assignable=True, env_args=[], timeout=None):
|
||||
"""
|
||||
@param name: machine name
|
||||
@type name: str
|
||||
@param ros_root: ROS_ROOT on machine
|
||||
@type ros_root: str
|
||||
@param ros_package_path: ROS_PACKAGE_PATH on machine
|
||||
@type ros_package_path: str
|
||||
@param address: network address of machine
|
||||
@type address: str
|
||||
@param ros_ip: ROS_IP on machine
|
||||
@type ros_ip: str
|
||||
@param ssh_port: SSH port number
|
||||
@type ssh_port: int
|
||||
@param user: SSH username
|
||||
@type user: str
|
||||
@param password: SSH password. Not recommended for use. Use SSH keys instead.
|
||||
@type password: str
|
||||
"""
|
||||
self.name = name
|
||||
self.ros_root = ros_root
|
||||
self.ros_package_path = ros_package_path
|
||||
self.ros_ip = ros_ip or None
|
||||
self.user = user or None
|
||||
self.password = password or None
|
||||
self.address = address
|
||||
self.ssh_port = ssh_port
|
||||
self.assignable = assignable
|
||||
self.env_args = env_args
|
||||
self.timeout = timeout or _DEFAULT_REGISTER_TIMEOUT
|
||||
|
||||
def __str__(self):
|
||||
return "Machine(name[%s] ros_root[%s] ros_package_path[%s] ros_ip[%s] address[%s] ssh_port[%s] user[%s] assignable[%s] env_args[%s] timeout[%s])"%(self.name, self.ros_root, self.ros_package_path, self.ros_ip, self.address, self.ssh_port, self.user, self.assignable, str(self.env_args), self.timeout)
|
||||
def __eq__(self, m2):
|
||||
if not isinstance(m2, Machine):
|
||||
return False
|
||||
return self.name == m2.name and \
|
||||
self.assignable == m2.assignable and \
|
||||
self.config_equals(m2)
|
||||
|
||||
def config_key(self):
|
||||
"""
|
||||
Get a key that represents the configuration of the
|
||||
machine. machines with identical configurations have identical
|
||||
keys
|
||||
|
||||
@return: configuration key
|
||||
@rtype: str
|
||||
"""
|
||||
return "Machine(address[%s] ros_root[%s] ros_package_path[%s] ros_ip[%s] ssh_port[%s] user[%s] password[%s] env_args[%s] timeout[%s])"%(self.address, self.ros_root, self.ros_package_path, self.ros_ip or '', self.ssh_port, self.user or '', self.password or '', str(self.env_args), self.timeout)
|
||||
|
||||
def config_equals(self, m2):
|
||||
"""
|
||||
@return: True if machines have identical configurations
|
||||
@rtype: bool
|
||||
"""
|
||||
if not isinstance(m2, Machine):
|
||||
return False
|
||||
return self.ros_root == m2.ros_root and \
|
||||
self.ros_package_path == m2.ros_package_path and \
|
||||
self.ros_ip == m2.ros_ip and \
|
||||
self.address == m2.address and \
|
||||
self.ssh_port == m2.ssh_port and \
|
||||
self.user == m2.user and \
|
||||
self.password == m2.password and \
|
||||
set(self.env_args) == set(m2.env_args) and \
|
||||
self.timeout == m2.timeout
|
||||
|
||||
def __ne__(self, m2):
|
||||
return not self.__eq__(m2)
|
||||
|
||||
class Param(object):
|
||||
"""
|
||||
Data structure for storing information about a desired parameter in
|
||||
the ROS system Corresponds to the 'param' tag in the launch
|
||||
specification.
|
||||
"""
|
||||
def __init__(self, key, value):
|
||||
self.key = roslib.names.canonicalize_name(key)
|
||||
self.value = value
|
||||
def __eq__(self, p):
|
||||
if not isinstance(p, Param):
|
||||
return False
|
||||
return p.key == self.key and p.value == self.value
|
||||
def __ne__(self, p):
|
||||
return not self.__eq__(p)
|
||||
def __str__(self):
|
||||
return "%s=%s"%(self.key, self.value)
|
||||
def __repr__(self):
|
||||
return "%s=%s"%(self.key, self.value)
|
||||
|
||||
_local_m = None
|
||||
def local_machine():
|
||||
"""
|
||||
@return: Machine instance representing the local machine
|
||||
@rtype: L{Machine}
|
||||
"""
|
||||
global _local_m
|
||||
if _local_m is None:
|
||||
_local_m = Machine('', get_ros_root(), \
|
||||
get_ros_package_path(), 'localhost',\
|
||||
ros_ip=roslib.network.get_address_override())
|
||||
return _local_m
|
||||
|
||||
class Node(object):
|
||||
"""
|
||||
Data structure for storing information about a desired node in
|
||||
the ROS system Corresponds to the 'node' tag in the launch
|
||||
specification.
|
||||
"""
|
||||
__slots__ = ['package', 'type', 'name', 'namespace', \
|
||||
'machine_name', 'machine', 'args', 'respawn', \
|
||||
'remap_args', 'env_args',\
|
||||
'process_name', 'output', 'cwd',
|
||||
'launch_prefix', 'required',
|
||||
'filename']
|
||||
|
||||
def __init__(self, package, node_type, name=None, namespace='/', \
|
||||
machine_name=None, args='', respawn=False, \
|
||||
remap_args=None,env_args=None, output=None, cwd=None, \
|
||||
launch_prefix=None, required=False, filename='<unknown>'):
|
||||
"""
|
||||
@param package: node package name
|
||||
@type package: str
|
||||
@param node_type: node type
|
||||
@type node_type: str
|
||||
@param name: node name
|
||||
@type name: str
|
||||
@param namespace: namespace for node
|
||||
@type namespace: str
|
||||
@param machine_name: name of machine to run node on
|
||||
@type machine_name: str
|
||||
@param args: argument string to pass to node executable
|
||||
@type args: str
|
||||
@param respawn: if True, respawn node if it dies
|
||||
@type respawn: bool
|
||||
@param remap_args: list of [(from, to)] remapping arguments
|
||||
@type remap_args: [(str, str)]:
|
||||
@param env_args: list of [(key, value)] of
|
||||
additional environment vars to set for node
|
||||
@type env_args: [(str, str)]
|
||||
@param output: where to log output to, either Node, 'screen' or 'log'
|
||||
@type output: str
|
||||
@param cwd: current working directory of node, either 'node', 'ROS_HOME' or 'ros-root'. Default: ROS_HOME
|
||||
@type cwd: str
|
||||
@param launch_prefix: launch command/arguments to prepend to node executable arguments
|
||||
@type launch_prefix: str
|
||||
@param required: node is required to stay running (launch fails if node dies)
|
||||
@type required: bool
|
||||
@param filename: name of file Node was parsed from
|
||||
@type filename: str
|
||||
|
||||
@raise ValueError: if parameters do not validate
|
||||
"""
|
||||
|
||||
self.package = package
|
||||
self.type = node_type
|
||||
self.name = name or None
|
||||
self.namespace = roslib.names.make_global_ns(namespace or '/')
|
||||
self.machine_name = machine_name or None
|
||||
self.respawn = respawn
|
||||
self.args = args or ''
|
||||
self.remap_args = remap_args or []
|
||||
self.env_args = env_args or []
|
||||
self.output = output
|
||||
self.cwd = cwd
|
||||
if self.cwd == 'ros_home': # be lenient on case
|
||||
self.cwd = 'ROS_HOME'
|
||||
elif self.cwd == 'ros-root':
|
||||
printerrlog("WARNING: 'ros-root' value for <node> 'cwd' attribute is deprecated.")
|
||||
|
||||
self.launch_prefix = launch_prefix or None
|
||||
self.required = required
|
||||
self.filename = filename
|
||||
|
||||
if self.respawn and self.required:
|
||||
raise ValueError("respawn and required cannot both be set to true")
|
||||
|
||||
# validation
|
||||
if self.name and roslib.names.SEP in self.name: # #1821, namespaces in nodes need to be banned
|
||||
raise ValueError("node name cannot contain a namespace")
|
||||
if not len(self.package.strip()):
|
||||
raise ValueError("package must be non-empty")
|
||||
if not len(self.type.strip()):
|
||||
raise ValueError("type must be non-empty")
|
||||
if not self.output in ['log', 'screen', None]:
|
||||
raise ValueError("output must be one of 'log', 'screen'")
|
||||
if not self.cwd in ['ROS_HOME', 'ros-root', 'node', None]:
|
||||
raise ValueError("cwd must be one of 'ROS_HOME', 'ros-root', 'node'")
|
||||
|
||||
# Extra slots for assigning later
|
||||
|
||||
# slot to store the process name in so that we can query the
|
||||
# associated process state
|
||||
self.process_name = None
|
||||
|
||||
# machine is the assigned machine instance. should probably
|
||||
# consider storing this elsewhere as it can be inconsistent
|
||||
# with machine_name and is also a runtime, rather than
|
||||
# configuration property
|
||||
self.machine = None
|
||||
|
||||
|
||||
|
||||
def xmltype(self):
|
||||
return 'node'
|
||||
|
||||
def xmlattrs(self):
|
||||
name_str = cwd_str = respawn_str = None
|
||||
if self.name:
|
||||
name_str = self.name
|
||||
if self.cwd:
|
||||
cwd_str = self.cwd
|
||||
|
||||
return [
|
||||
('pkg', self.package),
|
||||
('type', self.type),
|
||||
('machine', self.machine_name),
|
||||
('ns', self.namespace),
|
||||
('args', self.args),
|
||||
('output', self.output),
|
||||
('cwd', cwd_str),
|
||||
('respawn', self.respawn), #not valid on <test>
|
||||
('name', name_str),
|
||||
('launch-prefix', self.launch_prefix),
|
||||
('required', self.required),
|
||||
]
|
||||
|
||||
#TODO: unify with to_remote_xml using a filter_fn
|
||||
def to_xml(self):
|
||||
"""
|
||||
convert representation into XML representation. Currently cannot represent private parameters.
|
||||
@return: XML representation for remote machine
|
||||
@rtype: str
|
||||
"""
|
||||
t = self.xmltype()
|
||||
attrs = [(a, v) for a, v in self.xmlattrs() if v != None]
|
||||
xmlstr = '<%s %s>\n'%(t, ' '.join(['%s="%s"'%(val[0], _xml_escape(val[1])) for val in attrs]))
|
||||
xmlstr += ''.join([' <remap from="%s" to="%s" />\n'%tuple(r) for r in self.remap_args])
|
||||
xmlstr += ''.join([' <env name="%s" value="%s" />\n'%tuple(e) for e in self.env_args])
|
||||
xmlstr += "</%s>"%t
|
||||
return xmlstr
|
||||
|
||||
def to_remote_xml(self):
|
||||
"""
|
||||
convert representation into remote representation. Remote representation does
|
||||
not include parameter settings or 'machine' attribute
|
||||
@return: XML representation for remote machine
|
||||
@rtype: str
|
||||
"""
|
||||
t = self.xmltype()
|
||||
attrs = [(a, v) for a, v in self.xmlattrs() if v != None and a != 'machine']
|
||||
xmlstr = '<%s %s>\n'%(t, ' '.join(['%s="%s"'%(val[0], _xml_escape(val[1])) for val in attrs]))
|
||||
xmlstr += ''.join([' <remap from="%s" to="%s" />\n'%tuple(r) for r in self.remap_args])
|
||||
xmlstr += ''.join([' <env name="%s" value="%s" />\n'%tuple(e) for e in self.env_args])
|
||||
xmlstr += "</%s>"%t
|
||||
return xmlstr
|
||||
|
||||
def _xml_escape(s):
|
||||
"""
|
||||
Escape string for XML
|
||||
@param s: string to escape
|
||||
@type s: str
|
||||
@return: string with XML entities (<, >, ", &) escaped.
|
||||
@rtype: str
|
||||
"""
|
||||
# gross, but doesn't need to be fast. always replace amp first
|
||||
s = str(s)
|
||||
s = s.replace('&', '&')
|
||||
s = s.replace('"', '"')
|
||||
s = s.replace('>', '>')
|
||||
s = s.replace('<', '<')
|
||||
return s
|
||||
|
||||
TEST_TIME_LIMIT_DEFAULT = 1 * 60 #seconds
|
||||
|
||||
|
||||
class Test(Node):
|
||||
"""
|
||||
A Test is a Node with special semantics that it performs a
|
||||
unit/integration test. The data model is the same except the
|
||||
option to set the respawn flag is removed.
|
||||
"""
|
||||
__slots__ = ['test_name', 'time_limit', 'retry']
|
||||
|
||||
def __init__(self, test_name, package, node_type, name=None, \
|
||||
namespace='/', machine_name=None, args='', \
|
||||
remap_args=None, env_args=None, time_limit=None, cwd=None,
|
||||
launch_prefix=None, retry=None, filename="<unknown>"):
|
||||
"""
|
||||
Construct a new test node.
|
||||
@param test_name: name of test for recording in test results
|
||||
@type test_name: str
|
||||
@param time_limit: number of seconds that a test
|
||||
should run before marked as a failure
|
||||
@type time_limit: int/float/long
|
||||
"""
|
||||
super(Test, self).__init__(package, node_type, name=name, \
|
||||
namespace=namespace, \
|
||||
machine_name=machine_name, args=args, \
|
||||
remap_args=remap_args,
|
||||
env_args=env_args,
|
||||
#output always is log
|
||||
output='log', cwd=cwd,
|
||||
launch_prefix=launch_prefix, filename=filename)
|
||||
self.test_name = test_name
|
||||
|
||||
self.retry = retry or 0
|
||||
time_limit = time_limit or TEST_TIME_LIMIT_DEFAULT
|
||||
if not type(time_limit) in (float, int, long):
|
||||
raise ValueError("'time-limit' must be a number")
|
||||
time_limit = float(time_limit) #force to floating point
|
||||
if time_limit <= 0:
|
||||
raise ValueError("'time-limit' must be a positive number")
|
||||
|
||||
self.time_limit = time_limit
|
||||
|
||||
def xmltype(self):
|
||||
return 'test'
|
||||
|
||||
def xmlattrs(self):
|
||||
"""
|
||||
NOTE: xmlattrs does not necessarily produce identical XML as
|
||||
to what it was initialized with, though the properties are the same
|
||||
"""
|
||||
attrs = Node.xmlattrs(self)
|
||||
attrs = [(a, v) for (a, v) in attrs if a != 'respawn']
|
||||
attrs.append(('test-name', self.test_name))
|
||||
|
||||
if self.retry:
|
||||
attrs.append(('retry', str(self.retry)))
|
||||
if self.time_limit != TEST_TIME_LIMIT_DEFAULT:
|
||||
attrs.append(('time-limit', self.time_limit))
|
||||
return attrs
|
||||
|
||||
|
||||
class Executable(object):
|
||||
"""
|
||||
Executable is a generic container for exectuable commands.
|
||||
"""
|
||||
|
||||
def __init__(self, cmd, args, phase=PHASE_RUN):
|
||||
"""
|
||||
@param cmd: name of command to run
|
||||
@type cmd: str
|
||||
@param args: arguments to command
|
||||
@type args: (str,)
|
||||
@param phase: PHASE_SETUP|PHASE_RUN|PHASE_TEARDOWN. Indicates whether the
|
||||
command should be run before, during, or after launch.
|
||||
@type phase: str
|
||||
"""
|
||||
self.command = cmd
|
||||
self.args = args
|
||||
self.phase = phase
|
||||
def __repr__(self):
|
||||
return "%s %s"%(self.command, ' '.join(self.args))
|
||||
def __str__(self):
|
||||
return "%s %s"%(self.command, ' '.join(self.args))
|
||||
|
||||
class RosbinExecutable(Executable):
|
||||
"""
|
||||
RosbinExecutables are exectuables stored in ROS_ROOT/bin.
|
||||
"""
|
||||
def __init__(self, cmd, args, phase=PHASE_RUN):
|
||||
super(RosbinExecutable, self).__init__(cmd, args, phase)
|
||||
def __repr__(self):
|
||||
return "ros/bin/%s %s"%(self.command, ' '.join(self.args))
|
||||
def __str__(self):
|
||||
return "ros/bin/%s %s"%(self.command, ' '.join(self.args))
|
||||
|
||||
|
||||
def generate_run_id():
|
||||
"""
|
||||
Utility routine for generating run IDs (UUIDs)
|
||||
@return: guid
|
||||
@rtype: str
|
||||
"""
|
||||
import uuid
|
||||
return str(uuid.uuid1())
|
||||
|
|
@ -1,282 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id: __init__.py 3803 2009-02-11 02:04:39Z rob_wheeler $
|
||||
|
||||
"""
|
||||
Utility module of roslaunch that extracts dependency information from
|
||||
roslaunch files, including calculating missing package dependencies.
|
||||
"""
|
||||
|
||||
import roslib; roslib.load_manifest('roslaunch')
|
||||
|
||||
import os
|
||||
import sys
|
||||
|
||||
import roslib.manifest
|
||||
import roslib.packages
|
||||
from roslib.substitution_args import resolve_args, SubstitutionException
|
||||
|
||||
from xml.dom.minidom import parse, parseString
|
||||
from xml.dom import Node as DomNode
|
||||
|
||||
NAME="roslaunch-deps"
|
||||
|
||||
class RoslaunchDepsException(Exception):
|
||||
"""
|
||||
Base exception of roslaunch.depends errors.
|
||||
"""
|
||||
pass
|
||||
|
||||
class RoslaunchDeps(object):
|
||||
"""
|
||||
Represents dependencies of a roslaunch file.
|
||||
"""
|
||||
def __init__(self):
|
||||
self.nodes = []
|
||||
self.includes = []
|
||||
self.pkgs = []
|
||||
|
||||
def _parse_launch(tags, launch_file, file_deps, verbose):
|
||||
_, launch_file_pkg = roslib.packages.get_dir_pkg(os.path.dirname(os.path.abspath(launch_file)))
|
||||
|
||||
# process group, include, node, and test tags from launch file
|
||||
for tag in [t for t in tags if t.nodeType == DomNode.ELEMENT_NODE]:
|
||||
|
||||
if tag.tagName == 'group':
|
||||
|
||||
#descend group tags as they can contain node tags
|
||||
_parse_launch(tag.childNodes, launch_file, file_deps, verbose)
|
||||
|
||||
elif tag.tagName == 'include':
|
||||
try:
|
||||
sub_launch_file = resolve_args(tag.attributes['file'].value)
|
||||
except KeyError, e:
|
||||
raise RoslaunchDepsException("Cannot load roslaunch <%s> tag: missing required attribute %s.\nXML is %s"%(tag.tagName, str(e), tag.toxml()))
|
||||
|
||||
if verbose:
|
||||
print "processing included launch %s"%sub_launch_file
|
||||
|
||||
# determine package dependency for included file
|
||||
_, sub_pkg = roslib.packages.get_dir_pkg(os.path.dirname(os.path.abspath(sub_launch_file)))
|
||||
if sub_pkg is None:
|
||||
print >> sys.stderr, "ERROR: cannot determine package for [%s]"%sub_launch_file
|
||||
|
||||
file_deps[launch_file].includes.append(sub_launch_file)
|
||||
if launch_file_pkg != sub_pkg:
|
||||
file_deps[launch_file].pkgs.append(sub_pkg)
|
||||
|
||||
# recurse
|
||||
file_deps[sub_launch_file] = RoslaunchDeps()
|
||||
try:
|
||||
dom = parse(sub_launch_file).getElementsByTagName('launch')
|
||||
if not len(dom):
|
||||
print >> sys.stderr, "ERROR: %s is not a valid roslaunch file"%sub_launch_file
|
||||
else:
|
||||
launch_tag = dom[0]
|
||||
_parse_launch(launch_tag.childNodes, sub_launch_file, file_deps, verbose)
|
||||
except IOError, e:
|
||||
raise RoslaunchDepsException("Cannot load roslaunch include '%s' in '%s'"%(sub_launch_file, launch_file))
|
||||
|
||||
elif tag.tagName in ['node', 'test']:
|
||||
try:
|
||||
pkg, type = [resolve_args(tag.attributes[a].value) for a in ['pkg', 'type']]
|
||||
except KeyError, e:
|
||||
raise RoslaunchDepsException("Cannot load roslaunch <%s> tag: missing required attribute %s.\nXML is %s"%(tag.tagName, str(e), tag.toxml()))
|
||||
file_deps[launch_file].nodes.append((pkg, type))
|
||||
# we actually want to include the package itself if that's referenced
|
||||
#if launch_file_pkg != pkg:
|
||||
file_deps[launch_file].pkgs.append(pkg)
|
||||
|
||||
def parse_launch(launch_file, file_deps, verbose):
|
||||
if verbose:
|
||||
print "processing launch %s"%launch_file
|
||||
|
||||
dom = parse(launch_file).getElementsByTagName('launch')
|
||||
if not len(dom):
|
||||
print >> sys.stderr, "ignoring %s as it is not a roslaunch file"%launch_file
|
||||
return
|
||||
|
||||
file_deps[launch_file] = RoslaunchDeps()
|
||||
launch_tag = dom[0]
|
||||
_parse_launch(launch_tag.childNodes, launch_file, file_deps, verbose)
|
||||
|
||||
def rl_file_deps(file_deps, launch_file, verbose=False):
|
||||
"""
|
||||
Generate file_deps file dependency info for the specified
|
||||
roslaunch file and its dependencies.
|
||||
@param file_deps: dictionary mapping roslaunch filenames to
|
||||
roslaunch dependency information. This dictionary will be
|
||||
updated with dependency information.
|
||||
@type file_deps: { str : RoslaunchDeps }
|
||||
@param verbose: if True, print verbose output
|
||||
@type verbose: bool
|
||||
@param launch_file: name of roslaunch file
|
||||
@type launch_file: str
|
||||
"""
|
||||
parse_launch(launch_file, file_deps, verbose)
|
||||
|
||||
def fullusage():
|
||||
name = NAME
|
||||
print """Usage:
|
||||
\t%(name)s [options] <file-or-package>
|
||||
"""%locals()
|
||||
|
||||
def print_deps(base_pkg, file_deps, verbose):
|
||||
pkgs = []
|
||||
|
||||
# for verbose output we print extra source information
|
||||
if verbose:
|
||||
for f, deps in file_deps.iteritems():
|
||||
for p, t in deps.nodes:
|
||||
print "%s [%s/%s]"%(p, p, t)
|
||||
|
||||
pkg_dir, pkg = roslib.packages.get_dir_pkg(os.path.dirname(os.path.abspath(f)))
|
||||
if pkg is None: #cannot determine package
|
||||
print >> sys.stderr, "ERROR: cannot determine package for [%s]"%pkg
|
||||
else:
|
||||
print "%s [%s]"%(pkg, f)
|
||||
print '-'*80
|
||||
|
||||
# print out list of package dependencies
|
||||
pkgs = []
|
||||
for deps in file_deps.itervalues():
|
||||
pkgs.extend(deps.pkgs)
|
||||
# print space-separated to be friendly to rosmake
|
||||
print ' '.join([p for p in set(pkgs)])
|
||||
|
||||
def calculate_missing(base_pkg, missing, file_deps):
|
||||
"""
|
||||
Calculate missing package dependencies in the manifest. This is
|
||||
mainly used as a subroutine of roslaunch_deps().
|
||||
|
||||
@param base_pkg: name of package where initial walk begins (unused).
|
||||
@type base_pkg: str
|
||||
@param missing: dictionary mapping package names to set of missing package dependencies.
|
||||
@type missing: { str: set(str) }
|
||||
@param file_deps: dictionary mapping launch file names to RoslaunchDeps of each file
|
||||
@type file_deps: { str: RoslaunchDeps}
|
||||
@return: missing (see parameter)
|
||||
@rtype: { str: set(str) }
|
||||
"""
|
||||
for launch_file in file_deps.iterkeys():
|
||||
pkg_dir, pkg = roslib.packages.get_dir_pkg(os.path.dirname(os.path.abspath(launch_file)))
|
||||
|
||||
if pkg is None: #cannot determine package
|
||||
print >> sys.stderr, "ERROR: cannot determine package for [%s]"%pkg
|
||||
continue
|
||||
m_file = roslib.manifest.manifest_file(pkg)
|
||||
m = roslib.manifest.parse_file(m_file)
|
||||
d_pkgs = set([d.package for d in m.depends])
|
||||
# make sure we don't count ourselves as a dep
|
||||
d_pkgs.add(pkg)
|
||||
|
||||
|
||||
diff = list(set(file_deps[launch_file].pkgs) - d_pkgs)
|
||||
if not pkg in missing:
|
||||
missing[pkg] = set()
|
||||
missing[pkg].update(diff)
|
||||
return missing
|
||||
|
||||
|
||||
def roslaunch_deps(files, verbose=False):
|
||||
"""
|
||||
@param packages: list of packages to check
|
||||
@type packages: [str]
|
||||
@param files [str]: list of roslaunch files to check. Must be in
|
||||
same package.
|
||||
@type files: [str]
|
||||
@return: base_pkg, file_deps, missing.
|
||||
base_pkg is the package of all files
|
||||
file_deps is a { filename : RoslaunchDeps } dictionary of
|
||||
roslaunch dependency information to update, indexed by roslaunch
|
||||
file name.
|
||||
missing is a { package : [packages] } dictionary of missing
|
||||
manifest dependencies, indexed by package.
|
||||
@rtype: str, dict, dict
|
||||
"""
|
||||
file_deps = {}
|
||||
missing = {}
|
||||
base_pkg = None
|
||||
|
||||
for launch_file in files:
|
||||
if not os.path.exists(launch_file):
|
||||
raise RoslaunchDepsException("roslaunch file [%s] does not exist"%launch_file)
|
||||
|
||||
pkg_dir, pkg = roslib.packages.get_dir_pkg(os.path.dirname(os.path.abspath(launch_file)))
|
||||
if base_pkg and pkg != base_pkg:
|
||||
raise RoslaunchDepsException("roslaunch files must be in the same package: %s vs. %s"%(base_pkg, pkg))
|
||||
base_pkg = pkg
|
||||
rl_file_deps(file_deps, launch_file, verbose)
|
||||
|
||||
calculate_missing(base_pkg, missing, file_deps)
|
||||
return base_pkg, file_deps, missing
|
||||
|
||||
def roslaunch_deps_main(argv=sys.argv):
|
||||
from optparse import OptionParser
|
||||
parser = OptionParser(usage="usage: %prog [options] <file(s)...>", prog=NAME)
|
||||
parser.add_option("--verbose", "-v", action="store_true",
|
||||
dest="verbose", default=False,
|
||||
help="Verbose output")
|
||||
parser.add_option("--warn", "-w", action="store_true",
|
||||
dest="warn", default=False,
|
||||
help="Warn about missing manifest dependencies")
|
||||
|
||||
(options, args) = parser.parse_args(argv[1:])
|
||||
if not args:
|
||||
parser.error('please specify a launch file')
|
||||
|
||||
files = [arg for arg in args if os.path.exists(arg)]
|
||||
packages = [arg for arg in args if not os.path.exists(arg)]
|
||||
if packages:
|
||||
parser.error("cannot located %s"%','.join(packages))
|
||||
try:
|
||||
base_pkg, file_deps, missing = roslaunch_deps(files, verbose=options.verbose)
|
||||
except RoslaunchDepsException, e:
|
||||
print >> sys.stderr, str(e)
|
||||
sys.exit(1)
|
||||
|
||||
if options.warn:
|
||||
print "Dependencies:"
|
||||
|
||||
print_deps(base_pkg, file_deps, options.verbose)
|
||||
|
||||
if options.warn:
|
||||
print '\nMissing declarations:'
|
||||
for pkg, miss in missing.iteritems():
|
||||
if miss:
|
||||
print "%s/manifest.xml:"%pkg
|
||||
for m in miss:
|
||||
print ' <depend package="%s" />'%m
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
|
@ -1,707 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Top-level implementation of launching processes. Coordinates
|
||||
lower-level libraries.
|
||||
"""
|
||||
|
||||
import os
|
||||
import logging
|
||||
import sys
|
||||
import time
|
||||
|
||||
import roslib.names
|
||||
import roslib.network
|
||||
|
||||
from roslaunch.core import *
|
||||
from roslaunch.config import ROSLaunchConfig
|
||||
from roslaunch.nodeprocess import create_master_process, create_node_process
|
||||
from roslaunch.pmon import start_process_monitor, ProcessListener, FatalProcessLaunch
|
||||
|
||||
from roslaunch.rlutil import update_terminal_name
|
||||
|
||||
_TIMEOUT_MASTER_START = 10.0 #seconds
|
||||
_TIMEOUT_MASTER_STOP = 10.0 #seconds
|
||||
|
||||
_ID = '/roslaunch'
|
||||
|
||||
class RLTestTimeoutException(RLException): pass
|
||||
|
||||
def _all_namespace_parents(p):
|
||||
splits = [s for s in p.split(roslib.names.SEP) if s]
|
||||
curr =roslib.names.SEP
|
||||
parents = [curr]
|
||||
for s in splits[:-1]:
|
||||
next_ = curr + s + roslib.names.SEP
|
||||
parents.append(next_)
|
||||
curr = next_
|
||||
return parents
|
||||
|
||||
def _unify_clear_params(params):
|
||||
"""
|
||||
Reduce clear_params such that only the highest-level namespaces
|
||||
are represented for overlapping namespaces. e.g. if both /foo/ and
|
||||
/foo/bar are present, return just /foo/.
|
||||
|
||||
@param params: paremter namees
|
||||
@type params: [str]
|
||||
@return: unified parameters
|
||||
@rtype: [str]
|
||||
"""
|
||||
# note: this is a quick-and-dirty implementation
|
||||
|
||||
# canonicalize parameters
|
||||
canon_params = []
|
||||
for p in params:
|
||||
if not p[-1] == roslib.names.SEP:
|
||||
p += roslib.names.SEP
|
||||
if not p in canon_params:
|
||||
canon_params.append(p)
|
||||
# reduce operation
|
||||
clear_params = canon_params[:]
|
||||
for p in canon_params:
|
||||
for parent in _all_namespace_parents(p):
|
||||
if parent in canon_params and p in clear_params and p != '/':
|
||||
clear_params.remove(p)
|
||||
return clear_params
|
||||
|
||||
def _hostname_to_rosname(hostname):
|
||||
"""
|
||||
Utility function to strip illegal characters from hostname. This
|
||||
is implemented to be correct, not efficient."""
|
||||
|
||||
# prepend 'host_', which guarantees leading alpha character
|
||||
fixed = 'host_'
|
||||
# simplify comparison by making name lowercase
|
||||
hostname = hostname.lower()
|
||||
for c in hostname:
|
||||
# only allow alphanumeric and numeral
|
||||
if (c >= 'a' and c <= 'z') or \
|
||||
(c >= '0' and c <= '9'):
|
||||
fixed+=c
|
||||
else:
|
||||
fixed+='_'
|
||||
return fixed
|
||||
|
||||
class _ROSLaunchListeners(ProcessListener):
|
||||
"""
|
||||
Helper class to manage distributing process events. It functions as
|
||||
a higher level aggregator of events. In particular, events about
|
||||
remote and local processes require different mechanisms for being
|
||||
caught and reported.
|
||||
"""
|
||||
def __init__(self):
|
||||
self.process_listeners = []
|
||||
|
||||
def add_process_listener(self, l):
|
||||
"""
|
||||
Add listener to list of listeners. Not threadsafe.
|
||||
@param l: listener
|
||||
@type l: L{ProcessListener}
|
||||
"""
|
||||
self.process_listeners.append(l)
|
||||
|
||||
def process_died(self, process_name, exit_code):
|
||||
"""
|
||||
ProcessListener callback
|
||||
"""
|
||||
for l in self.process_listeners:
|
||||
try:
|
||||
l.process_died(process_name, exit_code)
|
||||
except Exception, e:
|
||||
import traceback
|
||||
logging.getLogger('roslaunch').error(traceback.format_exc())
|
||||
|
||||
class ROSLaunchListener(object):
|
||||
"""
|
||||
Listener interface for events related to ROSLaunch.
|
||||
ROSLaunchListener is currently identical to the lower-level
|
||||
L{roslaunch.pmon.ProcessListener} interface, but is separate for
|
||||
architectural reasons. The lower-level
|
||||
L{roslaunch.pmon.ProcessMonitor} does not provide events about
|
||||
remotely running processes.
|
||||
"""
|
||||
|
||||
def process_died(self, process_name, exit_code):
|
||||
"""
|
||||
Notifies listener that process has died. This callback only
|
||||
occurs for processes that die during normal process monitor
|
||||
execution -- processes that are forcibly killed during
|
||||
L{roslaunch.pmon.ProcessMonitor} shutdown are not reported.
|
||||
@param process_name: name of process
|
||||
@type process_name: str
|
||||
@param exit_code int: exit code of process. If None, it means
|
||||
that L{roslaunch.pmon.ProcessMonitor} was unable to determine an exit code.
|
||||
@type exit_code: int
|
||||
"""
|
||||
pass
|
||||
|
||||
class ROSLaunchRunner(object):
|
||||
"""
|
||||
Runs a roslaunch. The normal sequence of API calls is L{launch()}
|
||||
followed by L{spin()}. An external thread can call L{stop()}; otherwise
|
||||
the runner will block until an exit signal. Another usage is to
|
||||
call L{launch()} followed by repeated calls to L{spin_once()}. This usage
|
||||
allows the main thread to continue to do work while processes are
|
||||
monitored.
|
||||
"""
|
||||
|
||||
def __init__(self, run_id, config, server_uri=None, pmon=None, is_core=False, remote_runner=None, is_child=False):
|
||||
"""
|
||||
@param run_id: /run_id for this launch. If the core is not
|
||||
running, this value will be used to initialize /run_id. If
|
||||
the core is already running, this value will be checked
|
||||
against the value stored on the core. L{ROSLaunchRunner} will
|
||||
fail during L{launch()} if they do not match.
|
||||
@type run_id: str
|
||||
@param config: roslauch instance to run
|
||||
@type config: L{ROSLaunchConfig}
|
||||
@param server_uri: XML-RPC URI of roslaunch server.
|
||||
@type server_uri: str
|
||||
@param pmon: optionally override the process
|
||||
monitor the runner uses for starting and tracking processes
|
||||
@type pmon: L{ProcessMonitor}
|
||||
|
||||
@param is_core: if True, this runner is a roscore
|
||||
instance. This affects the error behavior if a master is
|
||||
already running -- aborts if is_core is True and a core is
|
||||
detected.
|
||||
@type is_core: bool
|
||||
@param remote_runner: remote roslaunch process runner
|
||||
"""
|
||||
if run_id is None:
|
||||
raise RLException("run_id is None")
|
||||
self.run_id = run_id
|
||||
|
||||
# In the future we should can separate the notion of a core
|
||||
# config vs. the config being launched. In that way, we can
|
||||
# start to migrate to a model where a config is a parameter to
|
||||
# a launch() method, rather than a central thing to the
|
||||
# runner.
|
||||
self.config = config
|
||||
self.server_uri = server_uri
|
||||
self.is_child = is_child
|
||||
self.is_core = is_core
|
||||
self.logger = logging.getLogger('roslaunch')
|
||||
self.pm = pmon or start_process_monitor()
|
||||
|
||||
# wire in ProcessMonitor events to our listeners
|
||||
# aggregator. We similarly wire in the remote events when we
|
||||
# create the remote runner.
|
||||
self.listeners = _ROSLaunchListeners()
|
||||
if self.pm is None:
|
||||
raise RLException("unable to initialize roslaunch process monitor")
|
||||
if self.pm.is_shutdown:
|
||||
raise RLException("bad roslaunch process monitor initialization: process monitor is already dead")
|
||||
|
||||
self.pm.add_process_listener(self.listeners)
|
||||
|
||||
self.remote_runner = remote_runner
|
||||
|
||||
def add_process_listener(self, l):
|
||||
"""
|
||||
Add listener to list of listeners. Not threadsafe. Must be
|
||||
called before processes started.
|
||||
@param l: listener
|
||||
@type l: L{ProcessListener}
|
||||
"""
|
||||
self.listeners.add_process_listener(l)
|
||||
|
||||
def _load_parameters(self):
|
||||
"""
|
||||
Load parameters onto the parameter server
|
||||
"""
|
||||
self.logger.info("load_parameters starting ...")
|
||||
config = self.config
|
||||
param_server = config.master.get()
|
||||
p = None
|
||||
try:
|
||||
# multi-call style xmlrpc
|
||||
param_server_multi = config.master.get_multi()
|
||||
|
||||
# clear specified parameter namespaces
|
||||
# #2468 unify clear params to prevent error
|
||||
for p in _unify_clear_params(config.clear_params):
|
||||
if param_server.hasParam(_ID, p)[2]:
|
||||
#printlog("deleting parameter [%s]"%p)
|
||||
param_server_multi.deleteParam(_ID, p)
|
||||
r = param_server_multi()
|
||||
for code, msg, _ in r:
|
||||
if code != 1:
|
||||
raise RLException("Failed to clear parameter: %s"%(msg))
|
||||
|
||||
# multi-call objects are not reusable
|
||||
param_server_multi = config.master.get_multi()
|
||||
for p in config.params.itervalues():
|
||||
# suppressing this as it causes too much spam
|
||||
#printlog("setting parameter [%s]"%p.key)
|
||||
param_server_multi.setParam(_ID, p.key, p.value)
|
||||
r = param_server_multi()
|
||||
for code, msg, _ in r:
|
||||
if code != 1:
|
||||
raise RLException("Failed to set parameter: %s"%(msg))
|
||||
except RLException:
|
||||
raise
|
||||
except Exception, e:
|
||||
printerrlog("load_parameters: unable to set parameters (last param was [%s]): %s"%(p,e))
|
||||
raise #re-raise as this is fatal
|
||||
self.logger.info("... load_parameters complete")
|
||||
|
||||
def _launch_nodes(self):
|
||||
"""
|
||||
Launch all the declared nodes/master
|
||||
@return: two lists of node names where the first
|
||||
is the nodes that successfully launched and the second is the
|
||||
nodes that failed to launch.
|
||||
@rtype: [[str], [str]]
|
||||
"""
|
||||
config = self.config
|
||||
succeeded = []
|
||||
failed = []
|
||||
self.logger.info("launch_nodes: launching local nodes ...")
|
||||
local_nodes = config.nodes
|
||||
|
||||
# don't launch remote nodes
|
||||
local_nodes = [n for n in config.nodes if is_machine_local(n.machine)]
|
||||
|
||||
for node in local_nodes:
|
||||
proc, success = self.launch_node(node)
|
||||
if success:
|
||||
succeeded.append(str(proc))
|
||||
else:
|
||||
failed.append(str(proc))
|
||||
|
||||
if self.remote_runner:
|
||||
self.logger.info("launch_nodes: launching remote nodes ...")
|
||||
r_succ, r_fail = self.remote_runner.launch_remote_nodes()
|
||||
succeeded.extend(r_succ)
|
||||
failed.extend(r_fail)
|
||||
|
||||
self.logger.info("... launch_nodes complete")
|
||||
return succeeded, failed
|
||||
|
||||
def _setup_master(self):
|
||||
"""
|
||||
Validates master configuration and changes the master URI if
|
||||
necessary. Also shuts down any existing master.
|
||||
@raise RLException: if existing master cannot be killed
|
||||
"""
|
||||
m = self.config.master
|
||||
self.logger.info("initial ROS_MASTER_URI is %s", m.uri)
|
||||
if m.auto in [m.AUTO_START, m.AUTO_RESTART]:
|
||||
running = m.is_running() #save state as calls are expensive
|
||||
if m.auto == m.AUTO_RESTART and running:
|
||||
print "shutting down existing master"
|
||||
try:
|
||||
m.get().shutdown(_ID, 'roslaunch restart request')
|
||||
except:
|
||||
pass
|
||||
timeout_t = time.time() + _TIMEOUT_MASTER_STOP
|
||||
while m.is_running() and time.time() < timeout_t:
|
||||
time.sleep(0.1)
|
||||
if m.is_running():
|
||||
raise RLException("ERROR: could not stop existing master")
|
||||
running = False
|
||||
if not running:
|
||||
# force the master URI to be for this machine as we are starting it locally
|
||||
olduri = m.uri
|
||||
m.uri = remap_localhost_uri(m.uri, True)
|
||||
|
||||
# this block does some basic DNS checks so that we can
|
||||
# warn the user in the _very_ common case that their
|
||||
# hostnames are not configured properly
|
||||
hostname, _ = roslib.network.parse_http_host_and_port(m.uri)
|
||||
local_addrs = roslib.network.get_local_addresses()
|
||||
import socket
|
||||
reverse_ip = socket.gethostbyname(hostname)
|
||||
# 127. check is due to #1260
|
||||
if reverse_ip not in local_addrs and not reverse_ip.startswith('127.'):
|
||||
self.logger.warn("IP address %s local hostname '%s' not in local addresses (%s)."%(reverse_ip, hostname, ','.join(local_addrs)))
|
||||
print >> sys.stderr, \
|
||||
"""WARNING: IP address %s for local hostname '%s' does not appear to match
|
||||
any local IP address (%s). Your ROS nodes may fail to communicate.
|
||||
|
||||
Please use ROS_IP to set the correct IP address to use."""%(reverse_ip, hostname, ','.join(local_addrs))
|
||||
|
||||
if m.uri != olduri:
|
||||
self.logger.info("changing ROS_MASTER_URI to [%s] for starting master locally", m.uri)
|
||||
print "changing ROS_MASTER_URI to [%s] for starting master locally"%m.uri
|
||||
|
||||
def _launch_master(self):
|
||||
"""
|
||||
Launches master if requested. Must be run after L{_setup_master()}.
|
||||
@raise RLException: if master launch fails
|
||||
"""
|
||||
m = self.config.master
|
||||
auto = m.auto
|
||||
is_running = m.is_running()
|
||||
|
||||
if self.is_core and is_running:
|
||||
raise RLException("roscore cannot run as another roscore/master is already running. \nPlease kill other roscore/master processes before relaunching.\nThe ROS_MASTER_URI is %s"%(m.uri))
|
||||
|
||||
self.logger.debug("launch_master [%s]", auto)
|
||||
if auto in [m.AUTO_START, m.AUTO_RESTART] and not is_running:
|
||||
if auto == m.AUTO_START:
|
||||
printlog("starting new master (master configured for auto start)")
|
||||
elif auto == m.AUTO_RESTART:
|
||||
printlog("starting new master (master configured for auto restart)")
|
||||
|
||||
_, urlport = roslib.network.parse_http_host_and_port(m.uri)
|
||||
if urlport <= 0:
|
||||
raise RLException("ERROR: master URI is not a valid XML-RPC URI. Value is [%s]"%m.uri)
|
||||
|
||||
p = create_master_process(self.run_id, m.type, get_ros_root(), urlport, m.log_output)
|
||||
self.pm.register_core_proc(p)
|
||||
success = p.start()
|
||||
if not success:
|
||||
raise RLException("ERROR: unable to auto-start master process")
|
||||
timeout_t = time.time() + _TIMEOUT_MASTER_START
|
||||
while not m.is_running() and time.time() < timeout_t:
|
||||
time.sleep(0.1)
|
||||
|
||||
if not m.is_running():
|
||||
raise RLException("ERROR: could not contact master [%s]"%m.uri)
|
||||
|
||||
printlog_bold("ROS_MASTER_URI=%s"%m.uri)
|
||||
# TODO: although this dependency doesn't cause anything bad,
|
||||
# it's still odd for launch to know about console stuff. This
|
||||
# really should be an event.
|
||||
update_terminal_name(m.uri)
|
||||
|
||||
# Param Server config params
|
||||
param_server = m.get()
|
||||
|
||||
# #773: unique run ID
|
||||
self._check_and_set_run_id(param_server, self.run_id)
|
||||
|
||||
if self.server_uri:
|
||||
# store parent XML-RPC URI on param server
|
||||
# - param name is the /roslaunch/hostname:port so that multiple roslaunches can store at once
|
||||
hostname, port = roslib.network.parse_http_host_and_port(self.server_uri)
|
||||
hostname = _hostname_to_rosname(hostname)
|
||||
self.logger.info("setting /roslaunch/uris/%s__%s' to %s"%(hostname, port, self.server_uri))
|
||||
param_server.setParam(_ID, '/roslaunch/uris/%s__%s'%(hostname, port),self.server_uri)
|
||||
|
||||
def _check_and_set_run_id(self, param_server, run_id):
|
||||
"""
|
||||
Initialize self.run_id to existing value or setup parameter
|
||||
server with /run_id set to default_run_id
|
||||
@param default_run_id: run_id to use if value is not set
|
||||
@type default_run_id: str
|
||||
@param param_server: parameter server proxy
|
||||
@type param_server: xmlrpclib.ServerProxy
|
||||
"""
|
||||
code, _, val = param_server.hasParam(_ID, '/run_id')
|
||||
if code == 1 and not val:
|
||||
printlog_bold("setting /run_id to %s"%run_id)
|
||||
param_server.setParam('/roslaunch', '/run_id', run_id)
|
||||
else:
|
||||
# verify that the run_id we have been set to matches what's on the parameter server
|
||||
code, _, val = param_server.getParam('/roslaunch', '/run_id')
|
||||
if code != 1:
|
||||
#could only happen in a bad race condition with
|
||||
#someone else restarting core
|
||||
raise RLException("ERROR: unable to retrieve /run_id from parameter server")
|
||||
if run_id != val:
|
||||
raise RLException("run_id on parameter server does not match declared run_id: %s vs %s"%(val, run_id))
|
||||
#self.run_id = val
|
||||
#printlog_bold("/run_id is %s"%self.run_id)
|
||||
|
||||
def _launch_executable(self, e):
|
||||
"""
|
||||
Launch a single L{Executable} object. Blocks until executable finishes.
|
||||
@param e: Executable
|
||||
@type e: L{Executable}
|
||||
@raise RLException: if exectuable fails. Failure includes non-zero exit code.
|
||||
"""
|
||||
try:
|
||||
#kwc: I'm still debating whether shell=True is proper
|
||||
cmd = e.command
|
||||
if isinstance(e, RosbinExecutable):
|
||||
cmd = os.path.join(get_ros_root(), 'bin', cmd)
|
||||
cmd = "%s %s"%(cmd, ' '.join(e.args))
|
||||
print "running %s"%cmd
|
||||
local_machine = self.config.machines['']
|
||||
import roslaunch.node_args
|
||||
env = roslaunch.node_args.create_local_process_env(None, local_machine, self.config.master.uri)
|
||||
import subprocess
|
||||
retcode = subprocess.call(cmd, shell=True, env=env)
|
||||
if retcode < 0:
|
||||
raise RLException("command [%s] failed with exit code %s"%(cmd, retcode))
|
||||
except OSError, e:
|
||||
raise RLException("command [%s] failed: %s"%(cmd, e))
|
||||
|
||||
#TODO: _launch_run_executables, _launch_teardown_executables
|
||||
#TODO: define and implement behavior for remote launch
|
||||
def _launch_setup_executables(self):
|
||||
"""
|
||||
@raise RLException: if exectuable fails. Failure includes non-zero exit code.
|
||||
"""
|
||||
exes = [e for e in self.config.executables if e.phase == PHASE_SETUP]
|
||||
for e in exes:
|
||||
self._launch_executable(e)
|
||||
|
||||
def _launch_core_nodes(self):
|
||||
"""
|
||||
launch any core services that are not already running. master must
|
||||
be already running
|
||||
@raise RLException: if core launches fail
|
||||
"""
|
||||
import roslib.names
|
||||
|
||||
config = self.config
|
||||
master = config.master.get()
|
||||
tolaunch = []
|
||||
for node in config.nodes_core:
|
||||
node_name = roslib.names.ns_join(node.namespace, node.name)
|
||||
code, msg, _ = master.lookupNode(_ID, node_name)
|
||||
if code == -1:
|
||||
tolaunch.append(node)
|
||||
elif code == 1:
|
||||
print "core service [%s] found"%node_name
|
||||
else:
|
||||
print >> sys.stderr, "WARN: master is not behaving well (unexpected return value when looking up node)"
|
||||
self.logger.error("ERROR: master return [%s][%s] on lookupNode call"%(code,msg))
|
||||
|
||||
for node in tolaunch:
|
||||
node_name = roslib.names.ns_join(node.namespace, node.name)
|
||||
name, success = self.launch_node(node, core=True)
|
||||
if success:
|
||||
print "started core service [%s]"%node_name
|
||||
else:
|
||||
raise RLException("failed to start core service [%s]"%node_name)
|
||||
|
||||
def launch_node(self, node, core=False):
|
||||
"""
|
||||
Launch a single node locally. Remote launching is handled separately by the remote module.
|
||||
If node name is not assigned, one will be created for it.
|
||||
|
||||
@param node Node: node to launch
|
||||
@param core bool: if True, core node
|
||||
@return obj, bool: Process handle, successful launch. If success, return actual Process instance. Otherwise return name.
|
||||
"""
|
||||
self.logger.info("... preparing to launch node of type [%s/%s]", node.package, node.type)
|
||||
|
||||
# TODO: should this always override, per spec?. I added this
|
||||
# so that this api can be called w/o having to go through an
|
||||
# extra assign machines step.
|
||||
if node.machine is None:
|
||||
node.machine = self.config.machines['']
|
||||
if node.name is None:
|
||||
node.name = roslib.names.anonymous_name(node.type)
|
||||
|
||||
master = self.config.master
|
||||
import roslaunch.node_args
|
||||
try:
|
||||
process = create_node_process(self.run_id, node, master.uri)
|
||||
except roslaunch.node_args.NodeParamsException, e:
|
||||
self.logger.error(e)
|
||||
if node.package == 'rosout' and node.type == 'rosout':
|
||||
printerrlog("\n\n\nERROR: rosout is not built. Please run 'rosmake rosout'\n\n\n")
|
||||
else:
|
||||
printerrlog("ERROR: cannot launch node of type [%s/%s]: %s"%(node.package, node.type, str(e)))
|
||||
if node.name:
|
||||
return node.name, False
|
||||
else:
|
||||
return "%s/%s"%(node.package,node.type), False
|
||||
|
||||
self.logger.info("... created process [%s]", process.name)
|
||||
if core:
|
||||
self.pm.register_core_proc(process)
|
||||
else:
|
||||
self.pm.register(process)
|
||||
node.process_name = process.name #store this in the node object for easy reference
|
||||
self.logger.info("... registered process [%s]", process.name)
|
||||
|
||||
# note: this may raise FatalProcessLaunch, which aborts the entire launch
|
||||
success = process.start()
|
||||
if not success:
|
||||
if node.machine.name:
|
||||
printerrlog("launch of %s/%s on %s failed"%(node.package, node.type, node.machine.name))
|
||||
else:
|
||||
printerrlog("local launch of %s/%s failed"%(node.package, node.type))
|
||||
else:
|
||||
self.logger.info("... successfully launched [%s]", process.name)
|
||||
return process, success
|
||||
|
||||
def is_node_running(self, node):
|
||||
"""
|
||||
Check for running node process.
|
||||
@param node Node: node object to check
|
||||
@return bool: True if process associated with node is running (launched && !dead)
|
||||
"""
|
||||
#process_name is not set until node is launched.
|
||||
return node.process_name and self.pm.has_process(node.process_name)
|
||||
|
||||
def spin_once(self):
|
||||
"""
|
||||
Same as spin() but only does one cycle. must be run from the main thread.
|
||||
"""
|
||||
if not self.pm:
|
||||
return False
|
||||
return self.pm.mainthread_spin_once()
|
||||
|
||||
def spin(self):
|
||||
"""
|
||||
spin() must be run from the main thread. spin() is very
|
||||
important for roslaunch as it picks up jobs that the process
|
||||
monitor need to be run in the main thread.
|
||||
"""
|
||||
self.logger.info("spin")
|
||||
|
||||
# #556: if we're just setting parameters and aren't launching
|
||||
# any processes, exit.
|
||||
if not self.pm or not self.pm.get_active_names():
|
||||
printlog_bold("No processes to monitor")
|
||||
self.stop()
|
||||
return # no processes
|
||||
self.pm.mainthread_spin()
|
||||
#self.pm.join()
|
||||
self.logger.info("process monitor is done spinning, initiating full shutdown")
|
||||
self.stop()
|
||||
printlog_bold("done")
|
||||
|
||||
def stop(self):
|
||||
"""
|
||||
Stop the launch and all associated processes. not thread-safe.
|
||||
"""
|
||||
self.logger.info("runner.stop()")
|
||||
if self.pm is not None:
|
||||
printlog("shutting down processing monitor...")
|
||||
self.logger.info("shutting down processing monitor %s"%self.pm)
|
||||
self.pm.shutdown()
|
||||
self.pm.join()
|
||||
self.pm = None
|
||||
printlog("... shutting down processing monitor complete")
|
||||
else:
|
||||
self.logger.info("... roslaunch runner has already been stopped")
|
||||
|
||||
def _setup(self):
|
||||
"""
|
||||
Setup the state of the ROS network, including the parameter
|
||||
server state and core services
|
||||
"""
|
||||
# this may have already been done, but do just in case
|
||||
self.config.assign_machines()
|
||||
|
||||
# have to do setup on master before launching remote roslaunch
|
||||
# children as we may be changing the ROS_MASTER_URI.
|
||||
self._setup_master()
|
||||
|
||||
if self.remote_runner:
|
||||
# hook in our listener aggregator
|
||||
self.remote_runner.add_process_listener(self.listeners)
|
||||
|
||||
# start up the core: master + core nodes defined in core.xml
|
||||
self._launch_master()
|
||||
self._launch_core_nodes()
|
||||
|
||||
# run exectuables marked as setup period. this will block
|
||||
# until these executables exit. setup executable have to run
|
||||
# *before* parameters are uploaded so that commands like
|
||||
# rosparam delete can execute.
|
||||
self._launch_setup_executables()
|
||||
|
||||
# no parameters for a child process
|
||||
if not self.is_child:
|
||||
self._load_parameters()
|
||||
|
||||
def launch(self):
|
||||
"""
|
||||
Run the launch. Depending on usage, caller should call
|
||||
spin_once or spin as appropriate after launch().
|
||||
@return ([str], [str]): tuple containing list of nodes that
|
||||
successfully launches and list of nodes that failed to launch
|
||||
@rtype: ([str], [str])
|
||||
@raise RLException: if launch fails (e.g. run_id parameter does
|
||||
not match ID on parameter server)
|
||||
"""
|
||||
try:
|
||||
self._setup()
|
||||
succeeded, failed = self._launch_nodes()
|
||||
return succeeded, failed
|
||||
except KeyboardInterrupt:
|
||||
self.stop()
|
||||
raise
|
||||
|
||||
def run_test(self, test):
|
||||
"""
|
||||
Run the test node. Blocks until completion or timeout.
|
||||
@param test: test node to run
|
||||
@type test: Test
|
||||
@raise RLTestTimeoutException: if test fails to launch or test times out
|
||||
"""
|
||||
self.logger.info("... preparing to run test [%s] of type [%s/%s]", test.test_name, test.package, test.type)
|
||||
proc_h, success = self.launch_node(test)
|
||||
if not success:
|
||||
raise RLException("test [%s] failed to launch"%test.test_name)
|
||||
|
||||
#poll until test terminates or alloted time exceed
|
||||
timeout_t = time.time() + test.time_limit
|
||||
pm = self.pm
|
||||
while pm.mainthread_spin_once() and self.is_node_running(test):
|
||||
#test fails on timeout
|
||||
if time.time() > timeout_t:
|
||||
raise RLTestTimeoutException("test max time allotted")
|
||||
time.sleep(0.1)
|
||||
|
||||
# NOTE: the mainly exists to prevent implicit circular dependency as
|
||||
# the runner needs to invoke methods on the remote API, which depends
|
||||
# on launch.
|
||||
|
||||
class ROSRemoteRunnerIF(object):
|
||||
"""
|
||||
API for remote running
|
||||
"""
|
||||
def __init__(self):
|
||||
pass
|
||||
def setup(self):
|
||||
pass
|
||||
def add_process_listener(self, l):
|
||||
"""
|
||||
Listen to events about remote processes dying. Not
|
||||
threadsafe. Must be called before processes started.
|
||||
@param l: listener
|
||||
@type l: L{ProcessListener}
|
||||
"""
|
||||
pass
|
||||
|
||||
def launch_remote_nodes(self):
|
||||
"""
|
||||
Contact each child to launch remote nodes
|
||||
@return: succeeded, failed
|
||||
@rtype: [str], [str]
|
||||
"""
|
||||
pass
|
|
@ -1,510 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
General routines and representations for loading roslaunch model.
|
||||
"""
|
||||
|
||||
from __future__ import with_statement
|
||||
|
||||
import os
|
||||
import sys
|
||||
from copy import deepcopy
|
||||
|
||||
from roslaunch.core import Param, Master, RosbinExecutable, Node, Test, Machine, \
|
||||
RLException, PHASE_SETUP
|
||||
|
||||
try:
|
||||
from roslib.names import make_global_ns, ns_join, PRIV_NAME, load_mappings, is_legal_name, canonicalize_name
|
||||
except ImportError:
|
||||
raise ImportError('Cannot import new roslib libraries.\nThis is probably due to incompatible "roslib" directories on your PYTHONPATH.\nPlease check your PYTHONPATH and try again')
|
||||
|
||||
|
||||
#lazy-import global for yaml
|
||||
yaml = None
|
||||
|
||||
# maps master auto attribute to Master auto property
|
||||
_master_auto = {
|
||||
'no': Master.AUTO_NO, 'start': Master.AUTO_START, 'restart': Master.AUTO_RESTART,
|
||||
}
|
||||
|
||||
class LoadException(RLException):
|
||||
"""Error loading data as specified (e.g. cannot find included files, etc...)"""
|
||||
pass
|
||||
|
||||
#TODO: lists, maps(?)
|
||||
def convert_value(value, type_):
|
||||
"""
|
||||
Convert a value from a string representation into the specified
|
||||
type
|
||||
|
||||
@param value: string representation of value
|
||||
@type value: str
|
||||
@param type_: int, double, string, bool, or auto
|
||||
@type type_: str
|
||||
@raise ValueError: if parameters are invalid
|
||||
"""
|
||||
type_ = type_.lower()
|
||||
# currently don't support XML-RPC date, dateTime, maps, or list
|
||||
# types
|
||||
if type_ == 'auto':
|
||||
#attempt numeric conversion
|
||||
try:
|
||||
if '.' in value:
|
||||
return float(value)
|
||||
else:
|
||||
return int(value)
|
||||
except ValueError, e:
|
||||
pass
|
||||
#bool
|
||||
lval = value.lower()
|
||||
if lval == 'true' or lval == 'false':
|
||||
return convert_value(value, 'bool')
|
||||
#string
|
||||
return value
|
||||
elif type_ == 'str' or type_ == 'string':
|
||||
return value
|
||||
elif type_ == 'int':
|
||||
return int(value)
|
||||
elif type_ == 'double':
|
||||
return float(value)
|
||||
elif type_ == 'bool' or type_ == 'boolean':
|
||||
value = value.lower()
|
||||
if value == 'true' or value == '1':
|
||||
return True
|
||||
elif value == 'false' or value == '0':
|
||||
return False
|
||||
raise ValueError("%s is not a '%s' type"%(value, type_))
|
||||
else:
|
||||
raise ValueError("Unknown type '%s'"%type_)
|
||||
|
||||
def process_include_args(context):
|
||||
"""
|
||||
Processes arg declarations in context and makes sure that they are
|
||||
properly declared for passing into an included file. Also will
|
||||
correctly setup the context for passing to the included file.
|
||||
"""
|
||||
|
||||
# make sure all arguments have values. arg_names and resolve_dict
|
||||
# are cleared when the context was initially created.
|
||||
arg_dict = context.include_resolve_dict.get('arg', {})
|
||||
for arg in context.arg_names:
|
||||
if not arg in arg_dict:
|
||||
raise LoadException("include args must have declared values")
|
||||
|
||||
# save args that were passed so we can check for unused args in post-processing
|
||||
context.args_passed = arg_dict.keys()[:]
|
||||
# clear arg declarations so included file can re-declare
|
||||
context.arg_names = []
|
||||
|
||||
# swap in new resolve dict for passing
|
||||
context.resolve_dict = context.include_resolve_dict
|
||||
context.include_resolve_dict = None
|
||||
|
||||
def post_process_include_args(context):
|
||||
bad = [a for a in context.args_passed if a not in context.arg_names]
|
||||
if bad:
|
||||
raise LoadException("unused args [%s] for include of [%s]"%(', '.join(bad), context.filename))
|
||||
|
||||
def load_sysargs_into_context(context, argv):
|
||||
"""
|
||||
Load in ROS remapping arguments as arg assignments for context.
|
||||
|
||||
@param context: context to load into. context's resolve_dict for 'arg' will be reinitialized with values.
|
||||
@type context: L{LoaderContext{
|
||||
@param argv: command-line arguments
|
||||
@type argv: [str]
|
||||
"""
|
||||
# we use same command-line spec as ROS nodes
|
||||
mappings = load_mappings(argv)
|
||||
context.resolve_dict['arg'] = mappings
|
||||
|
||||
class LoaderContext(object):
|
||||
"""
|
||||
Container for storing current loader context (e.g. namespace,
|
||||
local parameter state, remapping state).
|
||||
"""
|
||||
|
||||
def __init__(self, ns, filename, parent=None, params=None, env_args=None, \
|
||||
resolve_dict=None, include_resolve_dict=None, arg_names=None):
|
||||
"""
|
||||
@param ns: namespace
|
||||
@type ns: str
|
||||
@param filename: name of file this is being loaded from
|
||||
@type filename: str
|
||||
@param resolve_dict: (optional) resolution dictionary for substitution args
|
||||
@type resolve_dict: dict
|
||||
@param include_resolve_dict: special resolution dictionary for
|
||||
<include> tags. Must be None if this is not an <include>
|
||||
context.
|
||||
@type include_resolve_dict: dict
|
||||
@param arg_names: name of args that have been declared in this context
|
||||
@type arg_names: [str]
|
||||
"""
|
||||
self.parent = parent
|
||||
self.ns = make_global_ns(ns or '/')
|
||||
self._remap_args = []
|
||||
self.params = params or []
|
||||
self.env_args = env_args or []
|
||||
self.filename = filename
|
||||
# for substitution args
|
||||
self.resolve_dict = resolve_dict or {}
|
||||
# arg names. Args that have been declared in this context
|
||||
self.arg_names = arg_names or []
|
||||
# special scoped resolve dict for processing in <include> tag
|
||||
self.include_resolve_dict = include_resolve_dict or None
|
||||
|
||||
def add_param(self, p):
|
||||
"""
|
||||
Add a ~param to the context. ~params are evaluated by any node
|
||||
declarations that occur later in the same context.
|
||||
|
||||
@param p: parameter
|
||||
@type p: L{Param}
|
||||
"""
|
||||
|
||||
# override any params already set
|
||||
matches = [m for m in self.params if m.key == p.key]
|
||||
for m in matches:
|
||||
self.params.remove(m)
|
||||
self.params.append(p)
|
||||
|
||||
def add_remap(self, remap):
|
||||
"""
|
||||
Add a new remap setting to the context. if a remap already
|
||||
exists with the same from key, it will be removed
|
||||
|
||||
@param remap: remap setting
|
||||
@type remap: (str, str)
|
||||
"""
|
||||
remap = [canonicalize_name(x) for x in remap]
|
||||
if not remap[0] or not remap[1]:
|
||||
raise RLException("remap from/to attributes cannot be empty")
|
||||
if not is_legal_name(remap[0]):
|
||||
raise RLException("remap from [%s] is not a valid ROS name"%remap[0])
|
||||
if not is_legal_name(remap[1]):
|
||||
raise RLException("remap to [%s] is not a valid ROS name"%remap[1])
|
||||
|
||||
matches = [r for r in self._remap_args if r[0] == remap[0]]
|
||||
for m in matches:
|
||||
self._remap_args.remove(m)
|
||||
self._remap_args.append(remap)
|
||||
|
||||
def add_arg(self, name, default=None, value=None):
|
||||
"""
|
||||
Add 'arg' to existing context. Args are only valid for their immediate context.
|
||||
"""
|
||||
if name in self.arg_names:
|
||||
raise LoadException("arg '%s' has already been declared"%name)
|
||||
self.arg_names.append(name)
|
||||
|
||||
resolve_dict = self.resolve_dict if self.include_resolve_dict is None else self.include_resolve_dict
|
||||
|
||||
if not 'arg' in resolve_dict:
|
||||
resolve_dict['arg'] = {}
|
||||
arg_dict = resolve_dict['arg']
|
||||
|
||||
# args can only be declared once. they must also have one and
|
||||
# only value at the time that they are declared.
|
||||
if value is not None:
|
||||
# value is set, error if declared in our arg dict as args
|
||||
# with set values are constant/grounded.
|
||||
if name in arg_dict:
|
||||
raise LoadException("cannot override arg '%s', which has already been set"%name)
|
||||
arg_dict[name] = value
|
||||
elif default is not None:
|
||||
# assign value if not in context
|
||||
if name not in arg_dict:
|
||||
arg_dict[name] = default
|
||||
else:
|
||||
# no value or default: appending to arg_names is all we
|
||||
# need to do as it declares the existence of the arg.
|
||||
pass
|
||||
|
||||
def remap_args(self):
|
||||
"""
|
||||
@return: copy of the current remap arguments
|
||||
@rtype: [(str, str)]
|
||||
"""
|
||||
if self.parent:
|
||||
args = []
|
||||
# filter out any parent remap args that have the same from key
|
||||
for pr in self.parent.remap_args():
|
||||
if not [r for r in self._remap_args if r[0] == pr[0]]:
|
||||
args.append(pr)
|
||||
args.extend(self._remap_args)
|
||||
return args
|
||||
return self._remap_args[:]
|
||||
|
||||
def include_child(self, ns, filename):
|
||||
"""
|
||||
Create child namespace based on include inheritance rules
|
||||
@param ns: sub-namespace of child context, or None if the
|
||||
child context shares the same namespace
|
||||
@type ns: str
|
||||
@param filename: name of include file
|
||||
@type filename: str
|
||||
@return: A child xml context that inherits from this context
|
||||
@rtype: L{LoaderContext}jj
|
||||
"""
|
||||
ctx = self.child(ns)
|
||||
# arg declarations are reset across include boundaries
|
||||
ctx.arg_names = []
|
||||
ctx.filename = filename
|
||||
# keep the resolve_dict for now, we will do all new assignments into include_resolve_dict
|
||||
ctx.include_resolve_dict = {}
|
||||
#del ctx.resolve_dict['arg']
|
||||
return ctx
|
||||
|
||||
def child(self, ns):
|
||||
"""
|
||||
@param ns: sub-namespace of child context, or None if the
|
||||
child context shares the same namespace
|
||||
@type ns: str
|
||||
@return: A child xml context that inherits from this context
|
||||
@rtype: L{LoaderContext}
|
||||
"""
|
||||
if ns:
|
||||
if ns[0] == '/': # global (discouraged)
|
||||
child_ns = ns
|
||||
elif ns == PRIV_NAME: # ~name
|
||||
# private names can only be scoped privately or globally
|
||||
child_ns = PRIV_NAME
|
||||
else:
|
||||
child_ns = ns_join(self.ns, ns)
|
||||
else:
|
||||
child_ns = self.ns
|
||||
return LoaderContext(child_ns, self.filename, parent=self,
|
||||
params=self.params, env_args=self.env_args[:],
|
||||
resolve_dict=deepcopy(self.resolve_dict),
|
||||
arg_names=self.arg_names[:], include_resolve_dict=self.include_resolve_dict)
|
||||
|
||||
#TODO: in-progress refactorization. I'm slowly separating out
|
||||
#non-XML-specific logic from xmlloader and moving into Loader. Soon
|
||||
#this will mean that it will be easier to write coverage tests for
|
||||
#lower-level logic.
|
||||
|
||||
class Loader(object):
|
||||
"""
|
||||
Lower-level library for loading ROS launch model. It provides an
|
||||
abstraction between the representation (e.g. XML) and the
|
||||
validation of the property values.
|
||||
"""
|
||||
|
||||
def create_master(self, type_, uri, auto_str):
|
||||
"""
|
||||
@param type_: type attribute or None if type attribute not provided
|
||||
@type type_: str
|
||||
@param uri: URI attribute or None if not specified
|
||||
@type uri: str
|
||||
@param auto_str: auto attribute or None if not provided
|
||||
@type auto_str: str
|
||||
@raise ValueError: if parameters cannot be processed into valid Master
|
||||
"""
|
||||
if type_ is not None and type_.strip() == '':
|
||||
raise ValueError("'type' must be non-empty")
|
||||
|
||||
try: # auto attribute
|
||||
auto_str = (auto_str or 'no').lower().strip()
|
||||
auto = _master_auto[auto_str]
|
||||
except KeyError:
|
||||
raise ValueError("invalid <master> 'auto' value: %s"%auto_str)
|
||||
|
||||
# TODO: URI validation
|
||||
return Master(type_=type_, uri=uri, auto=auto)
|
||||
|
||||
def add_param(self, ros_config, param_name, param_value, verbose=True):
|
||||
"""
|
||||
Add L{Param} instances to launch config. Dictionary values are
|
||||
unrolled into individual parameters.
|
||||
|
||||
@param ros_config: launch configuration
|
||||
@type ros_config: L{ROSLaunchConfig}
|
||||
@param param_name: name of parameter namespace to load values
|
||||
into. If param_name is '/', param_value must be a dictionary
|
||||
@type param_name: str
|
||||
@param param_value: value to assign to param_name. If
|
||||
param_value is a dictionary, it's values will be unrolled
|
||||
into individual parameters.
|
||||
@type param_value: str
|
||||
@raise ValueError: if parameters cannot be processed into valid Params
|
||||
"""
|
||||
|
||||
# shouldn't ever happen
|
||||
if not param_name:
|
||||
raise ValueError("no parameter name specified")
|
||||
|
||||
if param_name == '/' and type(param_value) != dict:
|
||||
raise ValueError("Cannot load non-dictionary types into global namespace '/'")
|
||||
|
||||
if type(param_value) == dict:
|
||||
# unroll params
|
||||
for k, v in param_value.iteritems():
|
||||
self.add_param(ros_config, ns_join(param_name, k), v, verbose=verbose)
|
||||
else:
|
||||
ros_config.add_param(Param(param_name, param_value), verbose=verbose)
|
||||
|
||||
def load_rosparam(self, context, ros_config, cmd, param, file, text, verbose=True):
|
||||
"""
|
||||
Load rosparam setting
|
||||
|
||||
@param context: Loader context
|
||||
@type context: L{LoaderContext}
|
||||
@param ros_config: launch configuration
|
||||
@type ros_config: L{ROSLaunchConfig}
|
||||
@param cmd: 'load', 'dump', or 'delete'
|
||||
@type cmd: str
|
||||
@param file: filename for rosparam to use or None
|
||||
@type file: str
|
||||
@param text: text for rosparam to load. Ignored if file is set.
|
||||
@type text: str
|
||||
@raise ValueError: if parameters cannot be processed into valid rosparam setting
|
||||
"""
|
||||
if not cmd in ('load', 'dump', 'delete'):
|
||||
raise ValueError("command must be 'load', 'dump', or 'delete'")
|
||||
if file is not None:
|
||||
if cmd == 'load' and not os.path.isfile(file):
|
||||
raise ValueError("file does not exist [%s]"%file)
|
||||
if cmd == 'delete':
|
||||
raise ValueError("'file' attribute is invalid with 'delete' command.")
|
||||
|
||||
full_param = ns_join(context.ns, param) if param else context.ns
|
||||
|
||||
if cmd == 'dump':
|
||||
ros_config.add_executable(RosbinExecutable('rosparam', (cmd, file, full_param), PHASE_SETUP))
|
||||
elif cmd == 'delete':
|
||||
ros_config.add_executable(RosbinExecutable('rosparam', (cmd, full_param), PHASE_SETUP))
|
||||
elif cmd == 'load':
|
||||
# load YAML text
|
||||
if file:
|
||||
with open(file, 'r') as f:
|
||||
text = f.read()
|
||||
|
||||
if not text:
|
||||
if file:
|
||||
raise ValueError("no YAML in file %s"%file)
|
||||
else:
|
||||
raise ValueError("no YAML to load")
|
||||
|
||||
# parse YAML text
|
||||
# - lazy import
|
||||
global yaml
|
||||
if yaml is None:
|
||||
import yaml
|
||||
try:
|
||||
data = yaml.load(text)
|
||||
except yaml.MarkedYAMLError, e:
|
||||
if not file:
|
||||
raise ValueError("Error within YAML block:\n\t%s\n\nYAML is:\n%s"%(str(e), text))
|
||||
else:
|
||||
raise ValueError("file %s contains invalid YAML:\n%s"%(file, str(e)))
|
||||
except Exception, e:
|
||||
if not file:
|
||||
raise ValueError("invalid YAML: %s\n\nYAML is:\n%s"%(str(e), text))
|
||||
else:
|
||||
raise ValueError("file %s contains invalid YAML:\n%s"%(file, str(e)))
|
||||
|
||||
# 'param' attribute is required for non-dictionary types
|
||||
if not param and type(data) != dict:
|
||||
raise ValueError("'param' attribute must be set for non-dictionary values")
|
||||
|
||||
self.add_param(ros_config, full_param, data, verbose=verbose)
|
||||
|
||||
else:
|
||||
raise ValueError("unknown command %s"%cmd)
|
||||
|
||||
|
||||
def load_env(self, context, ros_config, name, value):
|
||||
"""
|
||||
Load environment variable setting
|
||||
|
||||
@param context: Loader context
|
||||
@type context: L{LoaderContext}
|
||||
@param ros_config: launch configuration
|
||||
@type ros_config: L{ROSLaunchConfig}
|
||||
@param name: environment variable name
|
||||
@type name: str
|
||||
@param value: environment variable value
|
||||
@type value: str
|
||||
"""
|
||||
if not name:
|
||||
raise ValueError("'name' attribute must be non-empty")
|
||||
context.env_args.append((name, value))
|
||||
|
||||
|
||||
def param_value(self, verbose, name, ptype, value, textfile, binfile, command):
|
||||
"""
|
||||
Parse text representation of param spec into Python value
|
||||
@param name: param name, for error message use only
|
||||
@type name: str
|
||||
@param verbose: print verbose output
|
||||
@type verbose: bool
|
||||
@param textfile: name of text file to load from, or None
|
||||
@type textfile: str
|
||||
@param binfile: name of binary file to load from, or None
|
||||
@type binfile: str
|
||||
@param command: command to execute for parameter value, or None
|
||||
@type command: str
|
||||
@raise ValueError: if parameters are invalid
|
||||
"""
|
||||
if value is not None:
|
||||
return convert_value(value.strip(), ptype)
|
||||
elif textfile is not None:
|
||||
with open(textfile, 'r') as f:
|
||||
return f.read()
|
||||
elif binfile is not None:
|
||||
import xmlrpclib
|
||||
with open(binfile, 'rb') as f:
|
||||
return xmlrpclib.Binary(f.read())
|
||||
elif command is not None:
|
||||
if type(command) == unicode:
|
||||
command = command.encode('UTF-8') #attempt to force to string for shlex/subprocess
|
||||
if verbose:
|
||||
print "... executing command param [%s]"%command
|
||||
import subprocess, shlex #shlex rocks
|
||||
try:
|
||||
p = subprocess.Popen(shlex.split(command), stdout=subprocess.PIPE)
|
||||
c_value = p.communicate()[0]
|
||||
if p.returncode != 0:
|
||||
raise ValueError("Cannot load command parameter [%s]: command [%s] returned with code [%s]"%(name, command, p.returncode))
|
||||
except OSError, (errno, strerr):
|
||||
if errno == 2:
|
||||
raise ValueError("Cannot load command parameter [%s]: no such command [%s]"%(name, command))
|
||||
raise
|
||||
if c_value is None:
|
||||
raise ValueError("parameter: unable to get output of command [%s]"%command)
|
||||
return c_value
|
||||
else: #_param_tag prevalidates, so this should not be reachable
|
||||
raise ValueError("unable to determine parameter value")
|
||||
|
|
@ -1,102 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Convience methods for manipulating XML-RPC APIs
|
||||
"""
|
||||
|
||||
import socket
|
||||
import xmlrpclib
|
||||
|
||||
import roslib.network
|
||||
import roslib.scriptutil
|
||||
|
||||
_ID = '/roslaunch_netapi'
|
||||
def get_roslaunch_uris():
|
||||
"""
|
||||
@return: list of roslaunch XML-RPC URIs for roscore that's in
|
||||
the current environment, or None if roscore cannot be contacted.
|
||||
@rtype: [str]
|
||||
"""
|
||||
try:
|
||||
param_server = roslib.scriptutil.get_param_server()
|
||||
code, msg, vals = param_server.getParam(_ID, '/roslaunch/uris')
|
||||
if code == 1 and vals:
|
||||
return vals.values()
|
||||
except socket.error: pass
|
||||
return None
|
||||
|
||||
class NetProcess(object):
|
||||
def __init__(self, name, respawn_count, is_alive, roslaunch_uri):
|
||||
self.is_alive = is_alive
|
||||
self.respawn_count = respawn_count
|
||||
self.name = name
|
||||
|
||||
self.roslaunch_uri = roslaunch_uri
|
||||
self.machine, _ = roslib.network.parse_http_host_and_port(roslaunch_uri)
|
||||
|
||||
def list_processes(roslaunch_uris=None):
|
||||
"""
|
||||
@param roslaunch_uris: (optional) list of XML-RPCS. If none
|
||||
are provided, will look up URIs dynamically
|
||||
@type roslaunch_uris: [str]
|
||||
@return: list of roslaunch processes
|
||||
@rtype: [L{NetProcess}]
|
||||
"""
|
||||
if not roslaunch_uris:
|
||||
roslaunch_uris = get_roslaunch_uris()
|
||||
if not roslaunch_uris:
|
||||
return []
|
||||
|
||||
procs = []
|
||||
for uri in roslaunch_uris:
|
||||
try:
|
||||
r = xmlrpclib.ServerProxy(uri)
|
||||
code, msg, val = r.list_processes()
|
||||
if code == 1:
|
||||
active, dead = val
|
||||
procs.extend([NetProcess(a[0], a[1], True, uri) for a in active])
|
||||
procs.extend([NetProcess(d[0], d[1], False, uri) for d in dead])
|
||||
except:
|
||||
#import traceback
|
||||
#traceback.print_exc()
|
||||
# don't have a mechanism for reporting these errors upwards yet
|
||||
pass
|
||||
return procs
|
||||
|
||||
if __name__ == "__main__":
|
||||
import roslib; roslib.load_manifest('roslaunch')
|
||||
print list_processes()
|
||||
print "done"
|
||||
|
|
@ -1,272 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2009, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Utility module of roslaunch that computes the command-line arguments
|
||||
for a node.
|
||||
"""
|
||||
|
||||
import logging
|
||||
import os
|
||||
import shlex
|
||||
import sys
|
||||
import time
|
||||
|
||||
import roslib.packages
|
||||
import roslib.rosenv
|
||||
import roslib.substitution_args
|
||||
from roslib.scriptutil import script_resolve_name
|
||||
|
||||
from roslaunch.core import setup_env, local_machine, RLException
|
||||
from roslaunch.config import load_config_default
|
||||
import roslaunch.xmlloader
|
||||
|
||||
class NodeParamsException(Exception):
|
||||
"""
|
||||
Exception to indicate that node parameters were invalid
|
||||
"""
|
||||
pass
|
||||
|
||||
def get_node_list(config):
|
||||
"""
|
||||
@param config: roslaunch config
|
||||
@type config: ROSLaunchConfig
|
||||
@return: list of node names in config
|
||||
@rtype: [str]
|
||||
"""
|
||||
l = [_resolved_name(node) for node in config.nodes] + [_resolved_name(test) for test in config.tests]
|
||||
# filter out unnamed nodes
|
||||
return [x for x in l if x]
|
||||
|
||||
def print_node_list(roslaunch_files):
|
||||
"""
|
||||
Print list of nodes to screen. Will cause system exit if exception
|
||||
occurs. This is a subroutine for the roslaunch main handler.
|
||||
|
||||
@param roslaunch_files: list of launch files to load
|
||||
@type roslaunch_files: str
|
||||
"""
|
||||
try:
|
||||
loader = roslaunch.xmlloader.XmlLoader(resolve_anon=False)
|
||||
config = load_config_default(roslaunch_files, None, loader=loader, verbose=False, assign_machines=False)
|
||||
node_list = get_node_list(config)
|
||||
print '\n'.join(node_list)
|
||||
except RLException, e:
|
||||
print >> sys.stderr, str(e)
|
||||
sys.exit(1)
|
||||
|
||||
def print_node_args(node_name, roslaunch_files):
|
||||
"""
|
||||
Print arguments of node to screen. Will cause system exit if
|
||||
exception occurs. This is a subroutine for the roslaunch main
|
||||
handler.
|
||||
|
||||
@param node_name: node name
|
||||
@type node_name: str
|
||||
@param roslaunch_files: list of launch files to load
|
||||
@type roslaunch_files: str
|
||||
"""
|
||||
try:
|
||||
node_name = script_resolve_name('roslaunch', node_name)
|
||||
args = get_node_args(node_name, roslaunch_files)
|
||||
print ' '.join(args)
|
||||
except RLException, e:
|
||||
print >> sys.stderr, str(e)
|
||||
sys.exit(1)
|
||||
|
||||
def _resolved_name(node):
|
||||
if node.name:
|
||||
# $(anon id) passthrough
|
||||
if node.name.startswith('$'):
|
||||
return node.name
|
||||
else:
|
||||
return roslib.names.ns_join(node.namespace, node.name)
|
||||
else:
|
||||
return None
|
||||
|
||||
def print_node_filename(node_name, roslaunch_files):
|
||||
try:
|
||||
# #2309
|
||||
node_name = script_resolve_name('roslaunch', node_name)
|
||||
|
||||
loader = roslaunch.xmlloader.XmlLoader(resolve_anon=False)
|
||||
config = load_config_default(roslaunch_files, None, loader=loader, verbose=False, assign_machines=False)
|
||||
nodes = [n for n in config.nodes if _resolved_name(n) == node_name] + \
|
||||
[t for t in config.tests if _resolved_name(t) == node_name]
|
||||
|
||||
if len(nodes) > 1:
|
||||
raise RLException("ERROR: multiple nodes named [%s] in [%s].\nPlease fix the launch files as duplicate names are not allowed."%(node_name, ', '.join(roslaunch_files)))
|
||||
if not nodes:
|
||||
print >> sys.stderr, 'ERROR: cannot find node named [%s]. Run \n\troslaunch --nodes <files>\nto see list of node names.'%(node_name)
|
||||
else:
|
||||
print nodes[0].filename
|
||||
|
||||
except RLException, e:
|
||||
print >> sys.stderr, str(e)
|
||||
sys.exit(1)
|
||||
|
||||
def get_node_args(node_name, roslaunch_files):
|
||||
"""
|
||||
Get the node arguments for a node in roslaunch_files.
|
||||
|
||||
@param node_name: name of node in roslaunch_files.
|
||||
@type node_name: str
|
||||
@param roslaunch_files: roslaunch file names
|
||||
@type roslaunch_files: [str]
|
||||
@return: list of command-line arguments used to launch node_name
|
||||
@rtype: [str]
|
||||
@raise RLException: if node args cannot be retrieved
|
||||
"""
|
||||
|
||||
# we have to create our own XmlLoader so that we can use the same
|
||||
# resolution context for substitution args
|
||||
|
||||
loader = roslaunch.xmlloader.XmlLoader(resolve_anon=False)
|
||||
config = load_config_default(roslaunch_files, None, loader=loader, verbose=False, assign_machines=False)
|
||||
(node_name) = roslib.substitution_args.resolve_args((node_name), resolve_anon=False)
|
||||
node_name = script_resolve_name('roslaunch', node_name) if not node_name.startswith('$') else node_name
|
||||
|
||||
node = [n for n in config.nodes if _resolved_name(n) == node_name] + \
|
||||
[n for n in config.tests if _resolved_name(n) == node_name]
|
||||
if not node:
|
||||
node_list = get_node_list(config)
|
||||
node_list_str = '\n'.join([" * %s"%x for x in node_list])
|
||||
raise RLException("ERROR: Cannot find node named [%s] in [%s].\nNode names are:\n%s"%(node_name, ', '.join(roslaunch_files), node_list_str))
|
||||
elif len(node) > 1:
|
||||
raise RLException("ERROR: multiple nodes named [%s] in [%s].\nPlease fix the launch files as duplicate names are not allowed."%(node_name, ', '.join(roslaunch_files)))
|
||||
node = node[0]
|
||||
|
||||
master_uri = roslib.rosenv.get_master_uri()
|
||||
machine = local_machine()
|
||||
|
||||
# don't use create_local_process_env, which merges the env with the full env of the shell
|
||||
env = setup_env(node, machine, master_uri)
|
||||
to_remove = []
|
||||
for k in env.iterkeys():
|
||||
if env[k] == os.environ.get(k, None):
|
||||
to_remove.append(k)
|
||||
for k in to_remove:
|
||||
del env[k]
|
||||
|
||||
# resolve node name for generating args
|
||||
args = create_local_process_args(node, machine)
|
||||
# join environment vars are bash prefix args
|
||||
return ["%s=%s"%(k, v) for k, v in env.iteritems()] + args
|
||||
|
||||
def create_local_process_env(node, machine, master_uri, env=os.environ):
|
||||
"""
|
||||
Setup environment for locally launched process. The local
|
||||
environment includes the default os environment, with any
|
||||
ROS-specific environment variables overriding this enviornment.
|
||||
@return: environment variables
|
||||
@rtype: dict
|
||||
"""
|
||||
|
||||
# #1029: generate environment for the node. unset
|
||||
# #ROS-related environment vars before
|
||||
# update() so that extra environment variables don't end
|
||||
# up in the call.
|
||||
full_env = env.copy()
|
||||
|
||||
for evar in [
|
||||
roslib.rosenv.ROS_MASTER_URI,
|
||||
roslib.rosenv.ROS_ROOT,
|
||||
roslib.rosenv.ROS_PACKAGE_PATH,
|
||||
roslib.rosenv.ROS_IP,
|
||||
'PYTHONPATH',
|
||||
roslib.rosenv.ROS_NAMESPACE]:
|
||||
if evar in full_env:
|
||||
del full_env[evar]
|
||||
|
||||
proc_env = setup_env(node, machine, master_uri)
|
||||
|
||||
# #2372: add ROS_ROOT/bin to path if it is not present
|
||||
rosroot_bin = os.path.join(roslib.rosenv.get_ros_root(), 'bin')
|
||||
path = os.environ.get('PATH', '')
|
||||
if not rosroot_bin in path.split(os.pathsep):
|
||||
proc_env['PATH'] = path + os.pathsep + rosroot_bin
|
||||
|
||||
full_env.update(proc_env)
|
||||
return full_env
|
||||
|
||||
def _launch_prefix_args(node):
|
||||
if node.launch_prefix:
|
||||
prefix = node.launch_prefix
|
||||
if type(prefix) == unicode:
|
||||
prefix = prefix.encode('UTF-8')
|
||||
return shlex.split(prefix)
|
||||
else:
|
||||
return []
|
||||
|
||||
def create_local_process_args(node, machine):
|
||||
"""
|
||||
Subroutine for creating node arguments.
|
||||
@return: arguments for node process
|
||||
@rtype: [str]
|
||||
@raise NodeParamsException: if args cannot be constructed for Node
|
||||
as specified (e.g. the node type does not exist)
|
||||
"""
|
||||
if not node.name:
|
||||
raise ValueError("node name must be defined")
|
||||
|
||||
# - Construct rosrun command
|
||||
remap_args = ["%s:=%s"%(src,dst) for src, dst in node.remap_args]
|
||||
resolve_dict = {}
|
||||
|
||||
#resolve args evaluates substitution commands
|
||||
#shlex parses a command string into a list of args
|
||||
# - for the local process args, we *do* resolve the anon tag so that the user can execute
|
||||
# - the node name and args must be resolved together in case the args refer to the anon node name
|
||||
(node_name) = roslib.substitution_args.resolve_args((node.name), context=resolve_dict, resolve_anon=True)
|
||||
node.name = node_name
|
||||
remap_args.append('__name:=%s'%node_name)
|
||||
|
||||
resolved = roslib.substitution_args.resolve_args(node.args, context=resolve_dict, resolve_anon=True)
|
||||
if type(resolved) == unicode:
|
||||
resolved = resolved.encode('UTF-8') #attempt to force to string for shlex/subprocess
|
||||
args = shlex.split(resolved) + remap_args
|
||||
|
||||
start_t = time.time()
|
||||
try:
|
||||
cmd = roslib.packages.find_node(node.package, node.type,\
|
||||
machine.ros_root, machine.ros_package_path)
|
||||
except roslib.packages.ROSPkgException, e:
|
||||
# multiple nodes, invalid package
|
||||
raise NodeParamsException(str(e))
|
||||
end_t = time.time()
|
||||
logging.getLogger('roslaunch.node_args').info('find_node(%s, %s, %s, %s) took %ss'%(node.package, node.type, machine.ros_root, machine.ros_package_path, (end_t - start_t)))
|
||||
if not cmd:
|
||||
raise NodeParamsException("Cannot locate node of type [%s] in package [%s]"%(node.type, node.package))
|
||||
return _launch_prefix_args(node) + [cmd] + args
|
||||
|
|
@ -1,445 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Local process implementation for running and monitoring nodes.
|
||||
"""
|
||||
|
||||
import os
|
||||
import sys
|
||||
import signal
|
||||
import socket
|
||||
import subprocess
|
||||
import time
|
||||
import traceback
|
||||
|
||||
import roslib.rosenv
|
||||
import roslib.network
|
||||
|
||||
from roslaunch.core import *
|
||||
from roslaunch.node_args import create_local_process_env, create_local_process_args
|
||||
from roslaunch.pmon import Process, FatalProcessLaunch
|
||||
|
||||
import logging
|
||||
_logger = logging.getLogger("roslaunch")
|
||||
|
||||
_TIMEOUT_SIGINT = 15.0 #seconds
|
||||
_TIMEOUT_SIGTERM = 2.0 #seconds
|
||||
|
||||
_counter = 0
|
||||
def _next_counter():
|
||||
global _counter
|
||||
_counter += 1
|
||||
return _counter
|
||||
|
||||
def create_master_process(run_id, type_, ros_root, port, log_output=False):
|
||||
"""
|
||||
Launch a master
|
||||
@param type_: name of master executable (currently just Master.ZENMASTER)
|
||||
@type type_: str
|
||||
@param ros_root: ROS_ROOT environment setting
|
||||
@type ros_root: str
|
||||
@param port: port to launch master on
|
||||
@type port: int
|
||||
@param log_output: if True, output goes to log file. Else, output goes to screen.
|
||||
@type log_output: bool
|
||||
@raise RLException: if type_ or port is invalid
|
||||
"""
|
||||
if port < 1 or port > 65535:
|
||||
raise RLException("invalid port assignment: %s"%port)
|
||||
|
||||
_logger.info("create_master_process: %s, %s, %s", type_, ros_root, port)
|
||||
master = os.path.join(ros_root, 'bin', type_)
|
||||
# zenmaster is deprecated and aliased to rosmaster
|
||||
if type_ in [Master.ROSMASTER, Master.ZENMASTER]:
|
||||
package = 'rosmaster'
|
||||
args = [master, '--core', '-p', str(port)]
|
||||
else:
|
||||
raise RLException("unknown master typ_: %s"%type_)
|
||||
|
||||
_logger.info("process[master]: launching with args [%s]"%args)
|
||||
return LocalProcess(run_id, package, 'master', args, os.environ, log_output, None)
|
||||
|
||||
def create_node_process(run_id, node, master_uri):
|
||||
"""
|
||||
Factory for generating processes for launching local ROS
|
||||
nodes. Also registers the process with the L{ProcessMonitor} so that
|
||||
events can be generated when the process dies.
|
||||
|
||||
@param run_id: run_id of launch
|
||||
@type run_id: str
|
||||
@param node: node to launch. Node name must be assigned.
|
||||
@type node: L{Node}
|
||||
@param master_uri: API URI for master node
|
||||
@type master_uri: str
|
||||
@return: local process instance
|
||||
@rtype: L{LocalProcess}
|
||||
@raise NodeParamsException: If the node's parameters are improperly specific
|
||||
"""
|
||||
_logger.info("create_node_process: package[%s] type[%s] machine[%s] master_uri[%s]", node.package, node.type, node.machine, master_uri)
|
||||
# check input args
|
||||
machine = node.machine
|
||||
if machine is None:
|
||||
raise RLException("Internal error: no machine selected for node of type [%s/%s]"%(node.package, node.type))
|
||||
if not node.name:
|
||||
raise ValueError("node name must be assigned")
|
||||
|
||||
# - setup env for process (vars must be strings for os.environ)
|
||||
env = create_local_process_env(node, machine, master_uri)
|
||||
|
||||
if not node.name:
|
||||
raise ValueError("node name must be assigned")
|
||||
|
||||
# we have to include the counter to prevent potential name
|
||||
# collisions between the two branches
|
||||
name = "%s-%s"%(node.name, _next_counter())
|
||||
|
||||
_logger.info('process[%s]: env[%s]', name, env)
|
||||
|
||||
args = create_local_process_args(node, machine)
|
||||
_logger.info('process[%s]: args[%s]', name, args)
|
||||
|
||||
# default for node.output not set is 'log'
|
||||
log_output = node.output != 'screen'
|
||||
_logger.debug('process[%s]: returning LocalProcess wrapper')
|
||||
return LocalProcess(run_id, node.package, name, args, env, log_output, respawn=node.respawn, required=node.required, cwd=node.cwd)
|
||||
|
||||
|
||||
class LocalProcess(Process):
|
||||
"""
|
||||
Process launched on local machine
|
||||
"""
|
||||
|
||||
def __init__(self, run_id, package, name, args, env, log_output, respawn=False, required=False, cwd=None, is_node=True):
|
||||
"""
|
||||
@param run_id: unique run ID for this roslaunch. Used to
|
||||
generate log directory location. run_id may be None if this
|
||||
feature is not being used.
|
||||
@type run_id: str
|
||||
@param package: name of package process is part of
|
||||
@type package: str
|
||||
@param name: name of process
|
||||
@type name: str
|
||||
@param args: list of arguments to process
|
||||
@type args: [str]
|
||||
@param env: environment dictionary for process
|
||||
@type env: {str : str}
|
||||
@param log_output: if True, log output streams of process
|
||||
@type log_output: bool
|
||||
@param respawn: respawn process if it dies (default is False)
|
||||
@type respawn: bool
|
||||
@param cwd: working directory of process, or None
|
||||
@type cwd: str
|
||||
@param is_node: (optional) if True, process is ROS node and accepts ROS node command-line arguments. Default: True
|
||||
@type is_node: False
|
||||
"""
|
||||
super(LocalProcess, self).__init__(package, name, args, env, respawn, required)
|
||||
self.run_id = run_id
|
||||
self.popen = None
|
||||
self.log_output = log_output
|
||||
self.started = False
|
||||
self.stopped = False
|
||||
self.cwd = cwd
|
||||
self.log_dir = None
|
||||
self.pid = -1
|
||||
self.is_node = is_node
|
||||
|
||||
# NOTE: in the future, info() is going to have to be sufficient for relaunching a process
|
||||
def get_info(self):
|
||||
"""
|
||||
Get all data about this process in dictionary form
|
||||
"""
|
||||
info = super(LocalProcess, self).get_info()
|
||||
info['pid'] = self.pid
|
||||
if self.run_id:
|
||||
info['run_id'] = self.run_id
|
||||
info['log_output'] = self.log_output
|
||||
if self.cwd is not None:
|
||||
info['cwd'] = self.cwd
|
||||
return info
|
||||
|
||||
def _configure_logging(self):
|
||||
"""
|
||||
Configure logging of node's log file and stdout/stderr
|
||||
@return: stdout log file name, stderr log file
|
||||
name. Values are None if stdout/stderr are not logged.
|
||||
@rtype: str, str
|
||||
"""
|
||||
log_dir = roslib.rosenv.get_log_dir(env=os.environ)
|
||||
if self.run_id:
|
||||
log_dir = os.path.join(log_dir, self.run_id)
|
||||
if not os.path.exists(log_dir):
|
||||
try:
|
||||
os.makedirs(log_dir)
|
||||
except OSError, (errno, msg):
|
||||
if errno == 13:
|
||||
raise RLException("unable to create directory for log file [%s].\nPlease check permissions."%log_dir)
|
||||
else:
|
||||
raise RLException("unable to create directory for log file [%s]: %s"%(log_dir, msg))
|
||||
# #973: save log dir for error messages
|
||||
self.log_dir = log_dir
|
||||
|
||||
# send stdout/stderr to file. in the case of respawning, we have to
|
||||
# open in append mode
|
||||
# note: logfileerr: disabling in favor of stderr appearing in the console.
|
||||
# will likely reinstate once roserr/rosout is more properly used.
|
||||
logfileout = logfileerr = None
|
||||
|
||||
if self.log_output:
|
||||
outf, errf = [os.path.join(log_dir, '%s-%s.log'%(self.name, n)) for n in ['stdout', 'stderr']]
|
||||
if self.respawn:
|
||||
mode = 'a'
|
||||
else:
|
||||
mode = 'w'
|
||||
logfileout = open(outf, mode)
|
||||
if is_child_mode():
|
||||
logfileerr = open(errf, mode)
|
||||
|
||||
# #986: pass in logfile name to node
|
||||
node_log_file = log_dir
|
||||
if self.is_node:
|
||||
# #1595: on respawn, these keep appending
|
||||
self.args = _cleanup_remappings(self.args, '__log:=')
|
||||
self.args.append("__log:=%s"%os.path.join(log_dir, "%s.log"%self.name))
|
||||
|
||||
return logfileout, logfileerr
|
||||
|
||||
def start(self):
|
||||
"""
|
||||
Start the process.
|
||||
|
||||
@raise FatalProcessLaunch: if process cannot be started and it
|
||||
is not likely to ever succeed
|
||||
"""
|
||||
super(LocalProcess, self).start()
|
||||
try:
|
||||
self.lock.acquire()
|
||||
if self.started:
|
||||
_logger.info("process[%s]: restarting os process", self.name)
|
||||
else:
|
||||
_logger.info("process[%s]: starting os process", self.name)
|
||||
self.started = self.stopped = False
|
||||
|
||||
full_env = self.env
|
||||
|
||||
# _configure_logging() can mutate self.args
|
||||
try:
|
||||
logfileout, logfileerr = self._configure_logging()
|
||||
except Exception, e:
|
||||
_logger.error(traceback.format_exc())
|
||||
printerrlog("[%s] ERROR: unable to configure logging [%s]"%(self.name, str(e)))
|
||||
# it's not safe to inherit from this process as
|
||||
# rostest changes stdout to a StringIO, which is not a
|
||||
# proper file.
|
||||
logfileout, logfileerr = subprocess.PIPE, subprocess.PIPE
|
||||
|
||||
if self.cwd == 'node':
|
||||
cwd = os.path.dirname(self.args[0])
|
||||
elif self.cwd == 'cwd':
|
||||
cwd = os.getcwd()
|
||||
elif self.cwd == 'ros-root':
|
||||
cwd = get_ros_root()
|
||||
else:
|
||||
cwd = roslib.rosenv.get_ros_home()
|
||||
|
||||
_logger.info("process[%s]: start w/ args [%s]", self.name, self.args)
|
||||
_logger.info("process[%s]: cwd will be [%s]", self.name, cwd)
|
||||
|
||||
try:
|
||||
self.popen = subprocess.Popen(self.args, cwd=cwd, stdout=logfileout, stderr=logfileerr, env=full_env, close_fds=True, preexec_fn=os.setsid)
|
||||
except OSError, (errno, msg):
|
||||
self.started = True # must set so is_alive state is correct
|
||||
_logger.error("OSError(%d, %s)", errno, msg)
|
||||
if errno == 8: #Exec format error
|
||||
raise FatalProcessLaunch("Unable to launch [%s]. \nIf it is a script, you may be missing a '#!' declaration at the top."%self.name)
|
||||
elif errno == 2: #no such file or directory
|
||||
raise FatalProcessLaunch("""Roslaunch got a '%s' error while attempting to run:
|
||||
|
||||
%s
|
||||
|
||||
Please make sure that all the executables in this command exist and have
|
||||
executable permission. This is often caused by a bad launch-prefix."""%(msg, ' '.join(self.args)))
|
||||
else:
|
||||
raise FatalProcessLaunch("unable to launch [%s]: %s"%(' '.join(self.args), msg))
|
||||
|
||||
self.started = True
|
||||
# Check that the process is either still running (poll returns
|
||||
# None) or that it completed successfully since when we
|
||||
# launched it above (poll returns the return code, 0).
|
||||
poll_result = self.popen.poll()
|
||||
if poll_result is None or poll_result == 0:
|
||||
self.pid = self.popen.pid
|
||||
printlog_bold("process[%s]: started with pid [%s]"%(self.name, self.pid))
|
||||
return True
|
||||
else:
|
||||
printerrlog("failed to start local process: %s"%(' '.join(self.args)))
|
||||
return False
|
||||
finally:
|
||||
self.lock.release()
|
||||
|
||||
def is_alive(self):
|
||||
"""
|
||||
@return: True if process is still running
|
||||
@rtype: bool
|
||||
"""
|
||||
if not self.started: #not started yet
|
||||
return True
|
||||
if self.stopped or self.popen is None:
|
||||
return False
|
||||
self.exit_code = self.popen.poll()
|
||||
if self.exit_code is not None:
|
||||
return False
|
||||
return True
|
||||
|
||||
def get_exit_description(self):
|
||||
"""
|
||||
@return: human-readable description of exit state
|
||||
@rtype: str
|
||||
"""
|
||||
# #973: include location of output location in message
|
||||
if self.exit_code is not None:
|
||||
if self.exit_code:
|
||||
if self.log_dir:
|
||||
return 'process has died [pid %s, exit code %s].\nlog files: %s*.log'%(self.pid, self.exit_code, os.path.join(self.log_dir, self.name))
|
||||
else:
|
||||
return 'process has died [pid %s, exit code %s]'%(self.pid, self.exit_code)
|
||||
else:
|
||||
if self.log_dir:
|
||||
return 'process has finished cleanly.\nlog file: %s*.log'%(os.path.join(self.log_dir, self.name))
|
||||
else:
|
||||
return 'process has finished cleanly'
|
||||
else:
|
||||
return 'process has died'
|
||||
|
||||
def _stop_unix(self, errors):
|
||||
"""
|
||||
UNIX implementation of process killing
|
||||
|
||||
@param errors: error messages. stop() will record messages into this list.
|
||||
@type errors: [str]
|
||||
"""
|
||||
self.exit_code = self.popen.poll()
|
||||
if self.exit_code is not None:
|
||||
_logger.debug("process[%s].stop(): process has already returned %s", self.name, self.exit_code)
|
||||
#print "process[%s].stop(): process has already returned %s"%(self.name, self.exit_code)
|
||||
self.popen = None
|
||||
self.stopped = True
|
||||
return
|
||||
|
||||
pid = self.popen.pid
|
||||
pgid = os.getpgid(pid)
|
||||
_logger.info("process[%s]: killing os process with pid[%s] pgid[%s]", self.name, pid, pgid)
|
||||
|
||||
try:
|
||||
# Start with SIGINT and escalate from there.
|
||||
_logger.info("[%s] sending SIGINT to pgid [%s]", self.name, pgid)
|
||||
os.killpg(pgid, signal.SIGINT)
|
||||
_logger.info("[%s] sent SIGINT to pgid [%s]", self.name, pgid)
|
||||
timeout_t = time.time() + _TIMEOUT_SIGINT
|
||||
retcode = self.popen.poll()
|
||||
while time.time() < timeout_t and retcode is None:
|
||||
time.sleep(0.1)
|
||||
retcode = self.popen.poll()
|
||||
# Escalate non-responsive process
|
||||
if retcode is None:
|
||||
printerrlog("[%s] escalating to SIGTERM"%self.name)
|
||||
timeout_t = time.time() + _TIMEOUT_SIGTERM
|
||||
os.killpg(pgid, signal.SIGTERM)
|
||||
_logger.info("[%s] sent SIGTERM to pgid [%s]"%(self.name, pgid))
|
||||
retcode = self.popen.poll()
|
||||
while time.time() < timeout_t and retcode is None:
|
||||
time.sleep(0.2)
|
||||
_logger.debug('poll for retcode')
|
||||
retcode = self.popen.poll()
|
||||
if retcode is None:
|
||||
printerrlog("[%s] escalating to SIGKILL"%self.name)
|
||||
errors.append("process[%s, pid %s]: required SIGKILL. May still be running."%(self.name, pid))
|
||||
try:
|
||||
os.killpg(pgid, signal.SIGKILL)
|
||||
_logger.info("[%s] sent SIGKILL to pgid [%s]"%(self.name, pgid))
|
||||
# #2096: don't block on SIGKILL, because this results in more orphaned processes overall
|
||||
#self.popen.wait()
|
||||
#os.wait()
|
||||
_logger.info("process[%s]: sent SIGKILL", self.name)
|
||||
except OSError, e:
|
||||
if e.args[0] == 3:
|
||||
printerrlog("no [%s] process with pid [%s]"%(self.name, pid))
|
||||
else:
|
||||
printerrlog("errors shutting down [%s], see log for details"%self.name)
|
||||
_logger.error(traceback.format_exc())
|
||||
else:
|
||||
_logger.info("process[%s]: SIGTERM killed with return value %s", self.name, retcode)
|
||||
else:
|
||||
_logger.info("process[%s]: SIGINT killed with return value %s", self.name, retcode)
|
||||
|
||||
finally:
|
||||
self.popen = None
|
||||
|
||||
def stop(self, errors=[]):
|
||||
"""
|
||||
Stop the process. Record any significant error messages in the errors parameter
|
||||
|
||||
@param errors: error messages. stop() will record messages into this list.
|
||||
@type errors: [str]
|
||||
"""
|
||||
super(LocalProcess, self).stop(errors)
|
||||
self.lock.acquire()
|
||||
try:
|
||||
try:
|
||||
_logger.debug("process[%s].stop() starting", self.name)
|
||||
if self.popen is None:
|
||||
_logger.debug("process[%s].stop(): popen is None, nothing to kill")
|
||||
return
|
||||
#NOTE: currently POSIX-only. Need to add in Windows code once I have a test environment:
|
||||
# http://aspn.activestate.com/ASPN/Cookbook/Python/Recipe/347462
|
||||
self._stop_unix(errors)
|
||||
except:
|
||||
#traceback.print_exc()
|
||||
_logger.error("[%s] EXCEPTION %s", self.name, traceback.format_exc())
|
||||
finally:
|
||||
self.stopped = True
|
||||
self.lock.release()
|
||||
|
||||
|
||||
# #1595
|
||||
def _cleanup_remappings(args, prefix):
|
||||
"""
|
||||
Remove all instances of args that start with prefix. This is used
|
||||
to remove args that were previously added (and are now being
|
||||
regenerated due to respawning)
|
||||
"""
|
||||
existing_args = [a for a in args if a.startswith(prefix)]
|
||||
for a in existing_args:
|
||||
args.remove(a)
|
||||
return args
|
|
@ -1,296 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
roslaunch.parent providees the L{ROSLaunchParent} implementation,
|
||||
which represents the main 'parent' roslaunch process.
|
||||
|
||||
ROSLaunch has a client/server architecture for running remote
|
||||
processes. When a user runs roslaunch, this creates a "parent"
|
||||
roslaunch process, which is responsible for managing local
|
||||
processes. This parent process will also start "child" processes on
|
||||
remote machines. The parent can then invoke methods on this child
|
||||
process to launch remote processes, and the child can invoke methods
|
||||
on the parent to provide feedback.
|
||||
"""
|
||||
|
||||
import logging
|
||||
import sys
|
||||
|
||||
import roslaunch.config
|
||||
from roslaunch.core import printlog_bold, printerrlog, RLException
|
||||
import roslaunch.launch
|
||||
import roslaunch.pmon
|
||||
import roslaunch.server
|
||||
import roslaunch.xmlloader
|
||||
|
||||
#TODO: probably move process listener infrastructure into here
|
||||
|
||||
# TODO: remove after wg_hardware_roslaunch has been updated
|
||||
# qualification accesses this API, which has been relocated
|
||||
load_config_default = roslaunch.config.load_config_default
|
||||
|
||||
class ROSLaunchParent(object):
|
||||
"""
|
||||
ROSLaunchParent represents the main 'parent' roslaunch process. It
|
||||
is responsible for loading the launch files, assigning machines,
|
||||
and then starting up any remote processes. The __main__ method
|
||||
delegates most of runtime to ROSLaunchParent.
|
||||
|
||||
This must be called from the Python Main thread due to signal registration.
|
||||
"""
|
||||
|
||||
def __init__(self, run_id, roslaunch_files, is_core=False, port=None, local_only=False, process_listeners=None, verbose=False, force_screen=False):
|
||||
"""
|
||||
@param run_id: UUID of roslaunch session
|
||||
@type run_id: str
|
||||
@param roslaunch_files: list of launch configuration
|
||||
files to load
|
||||
@type roslaunch_files: [str]
|
||||
@param is_core bool: if True, this launch is a roscore
|
||||
instance. This affects the error behavior if a master is
|
||||
already running (i.e. it fails).
|
||||
@type is_core: bool
|
||||
@param process_listeners: (optional) list of process listeners
|
||||
to register with process monitor once launch is running
|
||||
@type process_listeners: [L{roslaunch.pmon.ProcessListener}]
|
||||
@param port: (optional) override master port number from what is specified in the master URI.
|
||||
@type port: int
|
||||
@param verbose: (optional) print verbose output
|
||||
@type verbose: boolean
|
||||
@param force_screen: (optional) force output of all nodes to screen
|
||||
@type force_screen: boolean
|
||||
@throws RLException
|
||||
"""
|
||||
|
||||
self.logger = logging.getLogger('roslaunch.parent')
|
||||
self.run_id = run_id
|
||||
self.process_listeners = process_listeners
|
||||
|
||||
self.roslaunch_files = roslaunch_files
|
||||
self.is_core = is_core
|
||||
self.port = port
|
||||
self.local_only = local_only
|
||||
self.verbose = verbose
|
||||
|
||||
# I don't think we should have to pass in so many options from
|
||||
# the outside into the roslaunch parent. One possibility is to
|
||||
# allow alternate config loaders to be passed in.
|
||||
self.force_screen = force_screen
|
||||
|
||||
# flag to prevent multiple shutdown attempts
|
||||
self._shutting_down = False
|
||||
|
||||
self.config = self.runner = self.server = self.pm = self.remote_runner = None
|
||||
|
||||
def _load_config(self):
|
||||
self.config = roslaunch.config.load_config_default(self.roslaunch_files, self.port, verbose=self.verbose)
|
||||
|
||||
# #2370 (I really want to move this logic outside of parent)
|
||||
if self.force_screen:
|
||||
for n in self.config.nodes:
|
||||
n.output = 'screen'
|
||||
|
||||
def _start_pm(self):
|
||||
"""
|
||||
Start the process monitor
|
||||
"""
|
||||
self.pm = roslaunch.pmon.start_process_monitor()
|
||||
|
||||
def _init_runner(self):
|
||||
"""
|
||||
Initialize the roslaunch runner
|
||||
"""
|
||||
if self.config is None:
|
||||
raise RLException("config is not initialized")
|
||||
if self.pm is None:
|
||||
raise RLException("pm is not initialized")
|
||||
if self.server is None:
|
||||
raise RLException("server is not initialized")
|
||||
self.runner = roslaunch.launch.ROSLaunchRunner(self.run_id, self.config, server_uri=self.server.uri, pmon=self.pm, is_core=self.is_core, remote_runner=self.remote_runner)
|
||||
|
||||
# print runner info to user, put errors last to make the more visible
|
||||
print self.config.summary(local=self.remote_runner is None)
|
||||
if self.config:
|
||||
for err in self.config.config_errors:
|
||||
printerrlog("WARNING: %s"%err)
|
||||
|
||||
def _start_server(self):
|
||||
"""
|
||||
Initialize the roslaunch parent XML-RPC server
|
||||
"""
|
||||
if self.config is None:
|
||||
raise RLException("config is not initialized")
|
||||
if self.pm is None:
|
||||
raise RLException("pm is not initialized")
|
||||
|
||||
self.logger.info("starting parent XML-RPC server")
|
||||
self.server = roslaunch.server.ROSLaunchParentNode(self.config, self.pm)
|
||||
self.server.start()
|
||||
if not self.server.uri:
|
||||
raise RLException("server URI did not initialize")
|
||||
self.logger.info("... parent XML-RPC server started")
|
||||
|
||||
def _init_remote(self):
|
||||
"""
|
||||
Initialize the remote process runner, if required. Subroutine
|
||||
of _start_remote, separated out for easier testing
|
||||
"""
|
||||
if self.config is None:
|
||||
raise RLException("config is not initialized")
|
||||
if self.pm is None:
|
||||
raise RLException("pm is not initialized")
|
||||
if self.server is None:
|
||||
raise RLException("server is not initialized")
|
||||
|
||||
if not self.local_only and self.config.has_remote_nodes():
|
||||
# keep the remote package lazy-imported
|
||||
import roslaunch.remote
|
||||
self.remote_runner = roslaunch.remote.ROSRemoteRunner(self.run_id, self.config, self.pm, self.server)
|
||||
elif self.local_only:
|
||||
printlog_bold("LOCAL\nlocal only launch specified, will not launch remote nodes\nLOCAL\n")
|
||||
|
||||
def _start_remote(self):
|
||||
"""
|
||||
Initializes and runs the remote process runner, if required
|
||||
"""
|
||||
if self.remote_runner is None:
|
||||
self._init_remote()
|
||||
|
||||
if self.remote_runner is not None:
|
||||
# start_servers() runs the roslaunch children
|
||||
self.remote_runner.start_children()
|
||||
|
||||
def _start_infrastructure(self):
|
||||
"""
|
||||
load config, start XMLRPC servers and process monitor
|
||||
"""
|
||||
if self.config is None:
|
||||
self._load_config()
|
||||
|
||||
# Start the process monitor
|
||||
if self.pm is None:
|
||||
self._start_pm()
|
||||
|
||||
# Startup the roslaunch runner and XMLRPC server.
|
||||
# Requires pm
|
||||
if self.server is None:
|
||||
self._start_server()
|
||||
|
||||
# Startup the remote infrastructure.
|
||||
# Requires config, pm, and server
|
||||
self._start_remote()
|
||||
|
||||
def _stop_infrastructure(self):
|
||||
"""
|
||||
Tear down server and process monitor. Not multithread safe.
|
||||
"""
|
||||
#TODO more explicit teardown of remote infrastructure
|
||||
|
||||
# test and set flag so we don't shutdown multiple times
|
||||
if self._shutting_down:
|
||||
return
|
||||
self._shutting_down = True
|
||||
|
||||
if self.server:
|
||||
try:
|
||||
self.server.shutdown("roslaunch parent complete")
|
||||
except:
|
||||
# don't let exceptions halt the rest of the shutdown
|
||||
pass
|
||||
if self.pm:
|
||||
self.pm.shutdown()
|
||||
self.pm.join()
|
||||
|
||||
def start(self, auto_terminate=True):
|
||||
"""
|
||||
Run the parent roslaunch.
|
||||
|
||||
@param auto_terminate: stop process monitor once there are no
|
||||
more processes to monitor (default True). This defaults to
|
||||
True, which is the command-line behavior of roslaunch. Scripts
|
||||
may wish to set this to False if they wish to keep the
|
||||
roslauch infrastructure up regardless of processes being
|
||||
monitored.
|
||||
"""
|
||||
self.logger.info("starting roslaunch parent run")
|
||||
|
||||
# load config, start XMLRPC servers and process monitor
|
||||
try:
|
||||
self._start_infrastructure()
|
||||
except:
|
||||
# infrastructure did not initialize, do teardown on whatever did come up
|
||||
self._stop_infrastructure()
|
||||
raise
|
||||
|
||||
# Initialize the actual runner.
|
||||
# Requires config, pm, server and remote_runner
|
||||
self._init_runner()
|
||||
|
||||
# Start the launch
|
||||
self.runner.launch()
|
||||
|
||||
# inform process monitor that we are done with process registration
|
||||
if auto_terminate:
|
||||
self.pm.registrations_complete()
|
||||
|
||||
self.logger.info("... roslaunch parent running, waiting for process exit")
|
||||
if self.process_listeners:
|
||||
for l in self.process_listeners:
|
||||
self.runner.pm.add_process_listener(l)
|
||||
|
||||
def spin_once(self):
|
||||
"""
|
||||
Run the parent roslaunch event loop once
|
||||
"""
|
||||
if self.runner:
|
||||
self.runner.spin_once()
|
||||
|
||||
def spin(self):
|
||||
"""
|
||||
Run the parent roslaunch until exit
|
||||
"""
|
||||
if not self.runner:
|
||||
raise RLException("parent not started yet")
|
||||
try:
|
||||
# Blocks until all processes dead/shutdown
|
||||
self.runner.spin()
|
||||
finally:
|
||||
self._stop_infrastructure()
|
||||
|
||||
def shutdown(self):
|
||||
"""
|
||||
Stop the parent roslaunch.
|
||||
"""
|
||||
self._stop_infrastructure()
|
|
@ -1,665 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Process monitoring implementation for roslaunch.
|
||||
"""
|
||||
|
||||
from __future__ import with_statement
|
||||
|
||||
import os
|
||||
import sys
|
||||
import time
|
||||
import traceback
|
||||
import logging
|
||||
import Queue
|
||||
import signal
|
||||
import atexit
|
||||
from threading import Thread, RLock, Lock
|
||||
|
||||
import roslib
|
||||
from roslaunch.core import printlog, printlog_bold, printerrlog, RLException
|
||||
|
||||
logger = logging.getLogger("roslaunch.pmon")
|
||||
|
||||
class FatalProcessLaunch(RLException):
|
||||
"""
|
||||
Exception to indicate that a process launch has failed in a fatal
|
||||
manner (i.e. relaunch is unlikely to succeed)
|
||||
"""
|
||||
pass
|
||||
|
||||
# start/shutdown ################################################
|
||||
|
||||
_pmons = []
|
||||
_pmon_counter = 0
|
||||
def start_process_monitor():
|
||||
global _pmon_counter
|
||||
if _shutting_down:
|
||||
#logger.error("start_process_monitor: cannot start new ProcessMonitor (shutdown initiated)")
|
||||
return None
|
||||
_pmon_counter += 1
|
||||
name = "ProcessMonitor-%s"%_pmon_counter
|
||||
logger.info("start_process_monitor: creating ProcessMonitor")
|
||||
process_monitor = ProcessMonitor(name)
|
||||
try:
|
||||
# prevent race condition with pmon_shutdown() being triggered
|
||||
# as we are starting a ProcessMonitor (i.e. user hits ctrl-C
|
||||
# during startup)
|
||||
_shutdown_lock.acquire()
|
||||
_pmons.append(process_monitor)
|
||||
process_monitor.start()
|
||||
logger.info("start_process_monitor: ProcessMonitor started")
|
||||
finally:
|
||||
_shutdown_lock.release()
|
||||
|
||||
return process_monitor
|
||||
|
||||
def shutdown_process_monitor(process_monitor):
|
||||
"""
|
||||
@param process_monitor: process monitor to kill
|
||||
@type process_monitor: L{ProcessMonitor}
|
||||
@return: True if process_monitor was successfully
|
||||
shutdown. False if it could not be shutdown cleanly or if there is
|
||||
a problem with process_monitor
|
||||
parameter. shutdown_process_monitor() does not throw any exceptions
|
||||
as this is shutdown-critical code.
|
||||
@rtype: bool
|
||||
"""
|
||||
try:
|
||||
if process_monitor is None or process_monitor.is_shutdown:
|
||||
return False
|
||||
|
||||
# I've decided to comment out use of logger until after
|
||||
# critical section is done, just in case logger is already
|
||||
# being torn down
|
||||
|
||||
#logger.debug("shutdown_process_monitor: shutting down ProcessMonitor")
|
||||
process_monitor.shutdown()
|
||||
#logger.debug("shutdown_process_monitor: joining ProcessMonitor")
|
||||
process_monitor.join(20.0)
|
||||
if process_monitor.isAlive():
|
||||
logger.error("shutdown_process_monitor: ProcessMonitor shutdown failed!")
|
||||
return False
|
||||
else:
|
||||
logger.debug("shutdown_process_monitor: ProcessMonitor shutdown succeeded")
|
||||
return True
|
||||
except Exception, e:
|
||||
print >> sys.stderr, "exception in shutdown_process_monitor: %s"%e
|
||||
traceback.print_exc()
|
||||
return False
|
||||
|
||||
_shutdown_lock = Lock()
|
||||
def pmon_shutdown():
|
||||
global _pmons
|
||||
try:
|
||||
_shutdown_lock.acquire()
|
||||
try:
|
||||
if not _pmons:
|
||||
return
|
||||
for p in _pmons:
|
||||
shutdown_process_monitor(p)
|
||||
del _pmons[:]
|
||||
except:
|
||||
print "exception in pmon_shutdown"
|
||||
traceback.print_exc()
|
||||
finally:
|
||||
_shutdown_lock.release()
|
||||
|
||||
_signal_chain = {}
|
||||
_shutting_down = False
|
||||
def rl_signal(sig, stackframe):
|
||||
global _shutting_down
|
||||
if _shutting_down:
|
||||
return #prevent infinite callbacks
|
||||
_shutting_down = True
|
||||
pmon_shutdown()
|
||||
prev_handler = _signal_chain.get(sig, None)
|
||||
if prev_handler and prev_handler not in [signal.SIG_IGN, signal.SIG_DFL, rl_signal]:
|
||||
try:
|
||||
prev_handler(sig, stackframe)
|
||||
except KeyboardInterrupt:
|
||||
pass #filter out generic keyboard interrupt handler
|
||||
|
||||
_sig_initialized = False
|
||||
def _init_signal_handlers():
|
||||
global _sig_initialized
|
||||
if _sig_initialized:
|
||||
return
|
||||
if not roslib.is_interactive():
|
||||
_signal_chain[signal.SIGTERM] = signal.signal(signal.SIGTERM, rl_signal)
|
||||
_signal_chain[signal.SIGINT] = signal.signal(signal.SIGINT, rl_signal)
|
||||
_signal_chain[signal.SIGHUP] = signal.signal(signal.SIGHUP, rl_signal)
|
||||
atexit.register(pmon_shutdown)
|
||||
_sig_initialized = True
|
||||
|
||||
# ##############################################################
|
||||
|
||||
class Process(object):
|
||||
"""
|
||||
Basic process representation for L{ProcessMonitor}. Must be subclassed
|
||||
to provide actual start()/stop() implementations.
|
||||
|
||||
Constructor *must* be called from the Python Main thread in order
|
||||
for signal handlers to register properly.
|
||||
"""
|
||||
|
||||
def __init__(self, package, name, args, env, respawn=False, required=False):
|
||||
self.package = package
|
||||
self.name = name
|
||||
self.args = args
|
||||
self.env = env
|
||||
self.respawn = respawn
|
||||
self.required = required
|
||||
self.lock = Lock()
|
||||
self.exit_code = None
|
||||
# for keeping track of respawning
|
||||
self.spawn_count = 0
|
||||
|
||||
_init_signal_handlers()
|
||||
|
||||
def __str__(self):
|
||||
return "Process<%s>"%(self.name)
|
||||
|
||||
# NOTE: get_info() is going to have to be sufficient for
|
||||
# generating respawn requests, so we must be complete about it
|
||||
|
||||
def get_info(self):
|
||||
"""
|
||||
Get all data about this process in dictionary form
|
||||
@return: dictionary of all relevant process properties
|
||||
@rtype: dict { str: val }
|
||||
"""
|
||||
info = {
|
||||
'spawn_count': self.spawn_count,
|
||||
'args': self.args,
|
||||
'env': self.env,
|
||||
'package': self.package,
|
||||
'name': self.name,
|
||||
'alive': self.is_alive(),
|
||||
'respawn': self.respawn,
|
||||
'required': self.required,
|
||||
}
|
||||
if self.exit_code is not None:
|
||||
info['exit_code'] = self.exit_code
|
||||
return info
|
||||
|
||||
def start(self):
|
||||
self.spawn_count += 1
|
||||
|
||||
def is_alive(self):
|
||||
return False
|
||||
|
||||
def stop(self, errors=[]):
|
||||
"""
|
||||
Stop the process. Record any significant error messages in the errors parameter
|
||||
|
||||
@param errors: error messages. stop() will record messages into this list.
|
||||
@type errors: [str]
|
||||
"""
|
||||
pass
|
||||
|
||||
def get_exit_description(self):
|
||||
if self.exit_code is not None:
|
||||
if self.exit_code:
|
||||
return 'process has died [exit code %s]'%self.exit_code
|
||||
else:
|
||||
# try not to scare users about process exit
|
||||
return 'process has finished cleanly'
|
||||
else:
|
||||
return 'process has died'
|
||||
|
||||
class DeadProcess(Process):
|
||||
"""
|
||||
Container class to maintain information about a process that has died. This
|
||||
container allows us to delete the actual Process but still maintain the metadata
|
||||
"""
|
||||
def __init__(self, p):
|
||||
super(DeadProcess, self).__init__(p.package, p.name, p.args, p.env, p.respawn)
|
||||
self.exit_code = p.exit_code
|
||||
self.lock = None
|
||||
self.spawn_count = p.spawn_count
|
||||
self.info = p.get_info()
|
||||
def get_info(self):
|
||||
return self.info
|
||||
def start(self):
|
||||
raise Exception("cannot call start on a dead process!")
|
||||
def is_alive(self):
|
||||
return False
|
||||
|
||||
class ProcessListener(object):
|
||||
"""
|
||||
Listener class for L{ProcessMonitor}
|
||||
"""
|
||||
|
||||
def process_died(self, process_name, exit_code):
|
||||
"""
|
||||
Notifies listener that process has died. This callback only
|
||||
occurs for processes that die during normal process monitor
|
||||
execution -- processes that are forcibly killed during
|
||||
ProcessMonitor shutdown are not reported.
|
||||
@param process_name: name of process
|
||||
@type process_name: str
|
||||
@param exit_code: exit code of process. If None, it means
|
||||
that ProcessMonitor was unable to determine an exit code.
|
||||
@type exit_code: int
|
||||
"""
|
||||
pass
|
||||
|
||||
class ProcessMonitor(Thread):
|
||||
|
||||
def __init__(self, name="ProcessMonitor"):
|
||||
Thread.__init__(self, name=name)
|
||||
self.procs = []
|
||||
self.plock = RLock()
|
||||
self.is_shutdown = False
|
||||
self.done = False
|
||||
self.setDaemon(True)
|
||||
self.reacquire_signals = set()
|
||||
self.listeners = []
|
||||
self.dead_list = []
|
||||
# #885: ensure core procs
|
||||
self.core_procs = []
|
||||
# #642: flag to prevent process monitor exiting prematurely
|
||||
self._registrations_complete = False
|
||||
|
||||
logger.info("created process monitor %s"%self)
|
||||
|
||||
def add_process_listener(self, l):
|
||||
"""
|
||||
Listener for process events. MUST be called before
|
||||
ProcessMonitor is running.See ProcessListener class.
|
||||
@param l: listener instance
|
||||
@type l: L{ProcessListener}
|
||||
"""
|
||||
self.listeners.append(l)
|
||||
|
||||
def register(self, p):
|
||||
"""
|
||||
Register process with L{ProcessMonitor}
|
||||
@param p: Process
|
||||
@type p: L{Process}
|
||||
@raise RLException: if process with same name is already registered
|
||||
"""
|
||||
logger.info("ProcessMonitor.register[%s]"%p.name)
|
||||
e = None
|
||||
with self.plock:
|
||||
if self.has_process(p.name):
|
||||
e = RLException("cannot add process with duplicate name '%s'"%p.name)
|
||||
elif self.is_shutdown:
|
||||
e = RLException("cannot add process [%s] after process monitor has been shut down"%p.name)
|
||||
else:
|
||||
self.procs.append(p)
|
||||
if e:
|
||||
logger.error("ProcessMonitor.register[%s] failed %s"%(p.name, e))
|
||||
raise e
|
||||
else:
|
||||
logger.info("ProcessMonitor.register[%s] complete"%p.name)
|
||||
|
||||
def register_core_proc(self, p):
|
||||
"""
|
||||
Register core process with ProcessMonitor. Coreprocesses
|
||||
have special shutdown semantics. They are killed after all
|
||||
other processes, in reverse order in which they are added.
|
||||
@param p Process
|
||||
@type p: L{Process}
|
||||
@raise RLException: if process with same name is already registered
|
||||
"""
|
||||
self.register(p)
|
||||
self.core_procs.append(p)
|
||||
|
||||
def registrations_complete(self):
|
||||
"""
|
||||
Inform the process monitor that registrations are complete.
|
||||
After the registrations_complete flag is set, process monitor
|
||||
will exit if there are no processes left to monitor.
|
||||
"""
|
||||
self._registrations_complete = True
|
||||
logger.info("registrations completed %s"%self)
|
||||
|
||||
def unregister(self, p):
|
||||
logger.info("ProcessMonitor.unregister[%s] starting"%p.name)
|
||||
with self.plock:
|
||||
self.procs.remove(p)
|
||||
logger.info("ProcessMonitor.unregister[%s] complete"%p.name)
|
||||
|
||||
def has_process(self, name):
|
||||
"""
|
||||
@return: True if process is still be monitored. If False, process
|
||||
has died or was never registered with process
|
||||
@rtype: bool
|
||||
"""
|
||||
return len([p for p in self.procs if p.name == name]) > 0
|
||||
|
||||
def get_process(self, name):
|
||||
"""
|
||||
@return: process registered under \a name, or None
|
||||
@rtype: L{Process}
|
||||
"""
|
||||
with self.plock:
|
||||
v = [p for p in self.procs if p.name == name]
|
||||
if v:
|
||||
return v[0]
|
||||
|
||||
def has_main_thread_jobs(self):
|
||||
"""
|
||||
@return: True if ProcessMonitor has tasks that need to be run in the main thread
|
||||
@rtype: bool
|
||||
"""
|
||||
return len(self.reacquire_signals)
|
||||
|
||||
def do_main_thread_jobs(self):
|
||||
"""
|
||||
Execute tasks that need to be run in the main thread. Must be
|
||||
called from main thread.
|
||||
"""
|
||||
#not entirely threadsafe
|
||||
sigs = [s for s in self.reacquire_signals]
|
||||
for s in sigs:
|
||||
_signal_chain[s] = signal.signal(s, rl_signal)
|
||||
self.reacquire_signals.remove(s)
|
||||
|
||||
def kill_process(self, name):
|
||||
"""
|
||||
Kill process that matches name. NOTE: a killed process will
|
||||
continue to show up as active until the process monitor thread
|
||||
has caught that it has died.
|
||||
@param name: Process name
|
||||
@type name: str
|
||||
@return: True if a process named name was removed from
|
||||
process monitor. A process is considered killed if its stop()
|
||||
method was called.
|
||||
@rtype: bool
|
||||
"""
|
||||
if not isinstance(name, basestring):
|
||||
raise RLException("kill_process takes in a process name but was given: %s"%name)
|
||||
logger.debug("ProcessMonitor.kill_process[%s]"%name)
|
||||
printlog("[%s] kill requested"%name)
|
||||
with self.plock:
|
||||
p = self.get_process(name)
|
||||
if p:
|
||||
try:
|
||||
# no need to accumulate errors, so pass in []
|
||||
p.stop([])
|
||||
except:
|
||||
logger.error(traceback.format_exc())
|
||||
return True
|
||||
else:
|
||||
return False
|
||||
|
||||
def shutdown(self):
|
||||
"""
|
||||
Shutdown the process monitor thread
|
||||
"""
|
||||
logger.info("ProcessMonitor.shutdown %s"%self)
|
||||
self.is_shutdown = True
|
||||
|
||||
def get_active_names(self):
|
||||
"""
|
||||
@return [str]: list of active process names
|
||||
"""
|
||||
with self.plock:
|
||||
retval = [p.name for p in self.procs]
|
||||
return retval
|
||||
|
||||
def get_process_names_with_spawn_count(self):
|
||||
"""
|
||||
@return: Two lists, where first
|
||||
list of active process names along with the number of times
|
||||
that process has been spawned. Second list contains dead process names
|
||||
and their spawn count.
|
||||
@rtype: [[(str, int),], [(str,int),]]
|
||||
"""
|
||||
with self.plock:
|
||||
actives = [(p.name, p.spawn_count) for p in self.procs]
|
||||
deads = [(p.name, p.spawn_count) for p in self.dead_list]
|
||||
retval = [actives, deads]
|
||||
return retval
|
||||
|
||||
def mainthread_spin_once(self):
|
||||
"""
|
||||
run() occurs in a separate thread and cannot do certain signal-related
|
||||
work. The main thread of the application must call mainthread_spin()
|
||||
or mainthread_spin_once() in order to perform these jobs.
|
||||
"""
|
||||
if not self.done:
|
||||
if self.has_main_thread_jobs():
|
||||
self.do_main_thread_jobs()
|
||||
return True
|
||||
else:
|
||||
return False
|
||||
|
||||
def mainthread_spin(self):
|
||||
"""
|
||||
run() occurs in a separate thread and cannot do certain signal-related
|
||||
work. The main thread of the application must call mainthread_spin()
|
||||
or mainthread_spin_once() in order to perform these jobs. mainthread_spin()
|
||||
blocks until the process monitor is complete.
|
||||
"""
|
||||
while not self.done:
|
||||
time.sleep(0.1)
|
||||
if self.has_main_thread_jobs():
|
||||
self.do_main_thread_jobs()
|
||||
|
||||
def run(self):
|
||||
"""
|
||||
thread routine of the process monitor. NOTE: you must still
|
||||
call mainthread_spin or mainthread_spin_once() from the main
|
||||
thread in order to pick up main thread work from the process
|
||||
monitor.
|
||||
"""
|
||||
try:
|
||||
#don't let exceptions bomb thread, interferes with exit
|
||||
try:
|
||||
self._run()
|
||||
except:
|
||||
logger.error(traceback.format_exc())
|
||||
traceback.print_exc()
|
||||
finally:
|
||||
self._post_run()
|
||||
|
||||
def _run(self):
|
||||
"""
|
||||
Internal run loop of ProcessMonitor
|
||||
"""
|
||||
plock = self.plock
|
||||
dead = []
|
||||
respawn = []
|
||||
while not self.is_shutdown:
|
||||
with plock: #copy self.procs
|
||||
procs = self.procs[:]
|
||||
if self.is_shutdown:
|
||||
break
|
||||
|
||||
# check current signal handlers to see if children have stolen them away
|
||||
# TODO: this code may not be necessary anymore (have to test)
|
||||
for s in [signal.SIGTERM, signal.SIGINT, signal.SIGHUP]:
|
||||
if signal.getsignal(s) != rl_signal:
|
||||
self.reacquire_signals.add(s)
|
||||
|
||||
for p in procs:
|
||||
try:
|
||||
if not p.is_alive():
|
||||
logger.debug("Process[%s] has died, respawn=%s, required=%s, exit_code=%s",p.name, p.respawn, p.required, p.exit_code)
|
||||
exit_code_str = p.get_exit_description()
|
||||
if p.respawn:
|
||||
printlog_bold("[%s] %s\nrespawning..."%(p.name, exit_code_str))
|
||||
respawn.append(p)
|
||||
elif p.required:
|
||||
printerrlog('='*80+"REQUIRED process [%s] has died!\n%s\nInitiating shutdown!\n"%(p.name, exit_code_str)+'='*80)
|
||||
self.is_shutdown = True
|
||||
else:
|
||||
if p.exit_code:
|
||||
printerrlog("[%s] %s"%(p.name, exit_code_str))
|
||||
else:
|
||||
printlog_bold("[%s] %s"%(p.name, exit_code_str))
|
||||
dead.append(p)
|
||||
|
||||
## no need for lock as we require listeners be
|
||||
## added before process monitor is launched
|
||||
for l in self.listeners:
|
||||
l.process_died(p.name, p.exit_code)
|
||||
|
||||
except Exception, e:
|
||||
traceback.print_exc()
|
||||
#don't respawn as this is an internal error
|
||||
dead.append(p)
|
||||
if self.is_shutdown:
|
||||
break #stop polling
|
||||
for d in dead:
|
||||
try:
|
||||
self.unregister(d)
|
||||
# stop process, don't accumulate errors
|
||||
d.stop([])
|
||||
|
||||
# save process data to dead list
|
||||
with plock:
|
||||
self.dead_list.append(DeadProcess(d))
|
||||
except:
|
||||
logger.error(traceback.format_exc())
|
||||
|
||||
# dead check is to make sure that ProcessMonitor at least
|
||||
# waits until its had at least one process before exiting
|
||||
if self._registrations_complete and dead and not self.procs and not respawn:
|
||||
printlog("all processes on machine have died, roslaunch will exit")
|
||||
self.is_shutdown = True
|
||||
del dead[:]
|
||||
for r in respawn:
|
||||
try:
|
||||
if self.is_shutdown:
|
||||
break
|
||||
printlog("[%s] restarting process"%r.name)
|
||||
# stop process, don't accumulate errors
|
||||
r.stop([])
|
||||
r.start()
|
||||
except:
|
||||
traceback.print_exc()
|
||||
logger.error("Restart failed %s",traceback.format_exc())
|
||||
del respawn[:]
|
||||
time.sleep(0.1) #yield thread
|
||||
#moved this to finally block of _post_run
|
||||
#self._post_run() #kill all processes
|
||||
|
||||
def _post_run(self):
|
||||
logger.info("ProcessMonitor._post_run %s"%self)
|
||||
# this is already true entering, but go ahead and make sure
|
||||
self.is_shutdown = True
|
||||
# killall processes on run exit
|
||||
|
||||
q = Queue.Queue()
|
||||
q.join()
|
||||
|
||||
with self.plock:
|
||||
# make copy of core_procs for threadsafe usage
|
||||
core_procs = self.core_procs[:]
|
||||
logger.info("ProcessMonitor._post_run %s: remaining procs are %s"%(self, self.procs))
|
||||
|
||||
# enqueue all non-core procs in reverse order for parallel kill
|
||||
# #526/885: ignore core procs
|
||||
[q.put(p) for p in reversed(self.procs) if not p in core_procs]
|
||||
|
||||
# use 10 workers
|
||||
killers = []
|
||||
for i in range(10):
|
||||
t = _ProcessKiller(q, i)
|
||||
killers.append(t)
|
||||
t.start()
|
||||
|
||||
# wait for workers to finish
|
||||
q.join()
|
||||
shutdown_errors = []
|
||||
|
||||
# accumulate all the shutdown errors
|
||||
for t in killers:
|
||||
shutdown_errors.extend(t.errors)
|
||||
del killers[:]
|
||||
|
||||
# #526/885: kill core procs last
|
||||
# we don't want to parallelize this as the master has to be last
|
||||
for p in reversed(core_procs):
|
||||
_kill_process(p, shutdown_errors)
|
||||
|
||||
# delete everything except dead_list
|
||||
logger.info("ProcessMonitor exit: cleaning up data structures and signals")
|
||||
with self.plock:
|
||||
del core_procs[:]
|
||||
del self.procs[:]
|
||||
del self.core_procs[:]
|
||||
|
||||
reacquire_signals = self.reacquire_signals
|
||||
if reacquire_signals:
|
||||
reacquire_signals.clear()
|
||||
logger.info("ProcessMonitor exit: pmon has shutdown")
|
||||
self.done = True
|
||||
|
||||
if shutdown_errors:
|
||||
printerrlog("Shutdown errors:\n"+'\n'.join([" * %s"%e for e in shutdown_errors]))
|
||||
|
||||
def _kill_process(p, errors):
|
||||
"""
|
||||
Routine for kill Process p with appropriate logging to screen and logfile
|
||||
|
||||
@param p: process to kill
|
||||
@type p: Process
|
||||
@param errors: list of error messages from killed process
|
||||
@type errors: [str]
|
||||
"""
|
||||
try:
|
||||
logger.info("ProcessMonitor exit: killing %s", p.name)
|
||||
printlog("[%s] killing on exit"%p.name)
|
||||
# we accumulate errors from each process so that we can print these at the end
|
||||
p.stop(errors)
|
||||
except:
|
||||
traceback.print_exc()
|
||||
logger.error(traceback.format_exc())
|
||||
|
||||
class _ProcessKiller(Thread):
|
||||
|
||||
def __init__(self, q, i):
|
||||
Thread.__init__(self, name="ProcessKiller-%s"%i)
|
||||
self.q = q
|
||||
self.errors = []
|
||||
|
||||
def run(self):
|
||||
q = self.q
|
||||
while not q.empty():
|
||||
try:
|
||||
p = q.get(False)
|
||||
_kill_process(p, self.errors)
|
||||
q.task_done()
|
||||
except Queue.Empty:
|
||||
pass
|
||||
|
||||
|
||||
|
|
@ -1,235 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Integrates roslaunch remote process launching capabilities.
|
||||
"""
|
||||
|
||||
import logging
|
||||
import socket
|
||||
import sys
|
||||
import time
|
||||
|
||||
import roslib.network as network
|
||||
|
||||
import roslaunch.config
|
||||
import roslaunch.remoteprocess
|
||||
from roslaunch.remoteprocess import SSHChildROSLaunchProcess
|
||||
import roslaunch.launch
|
||||
import roslaunch.server #ROSLaunchParentNode hidden dep
|
||||
from roslaunch.core import RLException, setup_env, is_machine_local, printerrlog
|
||||
|
||||
#For using Log message level constants
|
||||
from roslib.msg import Log
|
||||
|
||||
_CHILD_REGISTER_TIMEOUT = 10.0 #seconds
|
||||
|
||||
|
||||
class ROSRemoteRunner(roslaunch.launch.ROSRemoteRunnerIF):
|
||||
"""
|
||||
Manages the running of remote roslaunch children
|
||||
"""
|
||||
|
||||
def __init__(self, run_id, rosconfig, pm, server):
|
||||
"""
|
||||
@param run_id: roslaunch run_id of this runner
|
||||
@type run_id: str
|
||||
@param config: launch configuration
|
||||
@type config: L{ROSConfig}
|
||||
@param pm process monitor
|
||||
@type pm: L{ProcessMonitor}
|
||||
@param server: roslaunch parent server
|
||||
@type server: L{ROSLaunchParentNode}
|
||||
"""
|
||||
self.run_id = run_id
|
||||
self.rosconfig = rosconfig
|
||||
self.server = server
|
||||
self.pm = pm
|
||||
self.logger = logging.getLogger('roslaunch.remote')
|
||||
self.listeners = []
|
||||
|
||||
self.machine_list = []
|
||||
self.remote_processes = []
|
||||
|
||||
def add_process_listener(self, l):
|
||||
"""
|
||||
Listen to events about remote processes dying. Not
|
||||
threadsafe. Must be called before processes started.
|
||||
@param l: ProcessListener
|
||||
@type l: L{ProcessListener}
|
||||
"""
|
||||
self.listeners.append(l)
|
||||
|
||||
def _start_child(self, server_node_uri, machine, counter):
|
||||
# generate a name for the machine. don't use config key as
|
||||
# it's too long to easily display
|
||||
name = "%s-%s"%(machine.address, counter)
|
||||
|
||||
self.logger.info("remote[%s] starting roslaunch", name)
|
||||
print "remote[%s] starting roslaunch"%name
|
||||
|
||||
env_dict = setup_env(None, machine, self.rosconfig.master.uri)
|
||||
p = SSHChildROSLaunchProcess(self.run_id, name, server_node_uri, env_dict, machine)
|
||||
success = p.start()
|
||||
self.pm.register(p)
|
||||
if not success: #treat as fatal
|
||||
raise RLException("unable to start remote roslaunch child: %s"%name)
|
||||
self.server.add_child(name, p)
|
||||
return p
|
||||
|
||||
def start_children(self):
|
||||
"""
|
||||
Start the child roslaunch processes
|
||||
"""
|
||||
server_node_uri = self.server.uri
|
||||
if not server_node_uri:
|
||||
raise RLException("server URI is not initialized")
|
||||
|
||||
# TODOXXX: break out table building code into a separate
|
||||
# routine so we can unit test it _start_child() should not be
|
||||
# determining the process name
|
||||
|
||||
# Build table of unique machines that we are going to launch on
|
||||
machines = {}
|
||||
for n in self.rosconfig.nodes:
|
||||
if not is_machine_local(n.machine):
|
||||
machines[n.machine.config_key()] = n.machine
|
||||
|
||||
# Launch child roslaunch processes on remote machines
|
||||
counter = 0
|
||||
# - keep a list of procs so we can check for those that failed to launch
|
||||
procs = []
|
||||
for m in machines:
|
||||
p = self._start_child(server_node_uri, machines[m], counter)
|
||||
procs.append(p)
|
||||
counter += 1
|
||||
|
||||
# Wait for all children to call register() callback. The machines can have
|
||||
# non-uniform registration timeouts. We consider the failure to occur once
|
||||
# one of the machines has failed to meet it's timeout.
|
||||
start_t = time.time()
|
||||
while True:
|
||||
pending = []
|
||||
for p in procs:
|
||||
if not p.is_alive():
|
||||
raise RLException("remote roslaunch failed to launch: %s"%p.machine.name)
|
||||
elif not p.uri:
|
||||
pending.append(p.machine)
|
||||
if not pending:
|
||||
break
|
||||
# timeout is the minimum of the remaining timeouts of the machines
|
||||
timeout_t = start_t + min([m.timeout for m in pending])
|
||||
if time.time() > timeout_t:
|
||||
break
|
||||
time.sleep(0.1)
|
||||
if pending:
|
||||
raise RLException(
|
||||
"""The following roslaunch remote processes failed to register:
|
||||
%s
|
||||
|
||||
If this is a network latency issue, you may wish to consider setting
|
||||
<machine timeout="NUMBER OF SECONDS" ... />
|
||||
in your launch"""%'\n'.join([" * %s (timeout %ss)"%(m.name, m.timeout) for m in pending]))
|
||||
|
||||
# convert machine dictionary to a list
|
||||
self.machine_list = machines.values()
|
||||
# save a list of the remote processes
|
||||
self.remote_processes = procs
|
||||
|
||||
|
||||
def _assume_failed(self, nodes, failed):
|
||||
"""
|
||||
Utility routine for logging/recording nodes that failed
|
||||
@param nodes: list of nodes that are assumed to have failed
|
||||
@type nodes: [L{Node}]
|
||||
@param failed: list of names of nodes that have failed to extend
|
||||
@type failed: [str]
|
||||
"""
|
||||
str_nodes = ["%s/%s"%(n.package, n.type) for n in nodes]
|
||||
failed.extend(str_nodes)
|
||||
printerrlog("Launch of the following nodes most likely failed: %s"%', '.join(str_nodes))
|
||||
|
||||
def launch_remote_nodes(self):
|
||||
"""
|
||||
Contact each child to launch remote nodes
|
||||
"""
|
||||
succeeded = []
|
||||
failed = []
|
||||
|
||||
# initialize remote_nodes. we use the machine config key as
|
||||
# the key for the dictionary so that we can bin the nodes.
|
||||
self.remote_nodes = {}
|
||||
for m in self.machine_list:
|
||||
self.remote_nodes[m.config_key()] = []
|
||||
|
||||
# build list of nodes that will be launched by machine
|
||||
nodes = [x for x in self.rosconfig.nodes if not is_machine_local(x.machine)]
|
||||
for n in nodes:
|
||||
self.remote_nodes[n.machine.config_key()].append(n)
|
||||
|
||||
for child in self.remote_processes:
|
||||
nodes = self.remote_nodes[child.machine.config_key()]
|
||||
body = '\n'.join([n.to_remote_xml() for n in nodes])
|
||||
xml = '<launch>\n%s</launch>'%body
|
||||
if 0:
|
||||
print xml
|
||||
|
||||
api = child.getapi()
|
||||
# TODO: timeouts
|
||||
try:
|
||||
self.logger.debug("sending [%s] XML [\n%s\n]"%(child.uri, xml))
|
||||
code, msg, val = api.launch(xml)
|
||||
if code == 1:
|
||||
c_succ, c_fail = val
|
||||
succeeded.extend(c_succ)
|
||||
failed.extend(c_fail)
|
||||
else:
|
||||
printerrlog('error launching on [%s, uri %s]: %s'%(child.name, child.uri, msg))
|
||||
self._assume_failed(nodes, failed)
|
||||
except socket.error, (errno, msg):
|
||||
printerrlog('error launching on [%s, uri %s]: %s'%(child.name, child.uri, str(msg)))
|
||||
self._assume_failed(nodes, failed)
|
||||
|
||||
except socket.gaierror, (errno, msg):
|
||||
# usually errno == -2. See #815.
|
||||
child_host, _ = network.parse_http_host_and_port(child.uri)
|
||||
printerrlog("Unable to contact remote roslaunch at [%s]. This is most likely due to a network misconfiguration with host lookups. Please make sure that you can contact '%s' from this machine"%(child.uri, child_host))
|
||||
self._assume_failed(nodes, failed)
|
||||
|
||||
except Exception, e:
|
||||
printerrlog('error launching on [%s, uri %s]: %s'%(child.name, child.uri, str(e)))
|
||||
self._assume_failed(nodes, failed)
|
||||
|
||||
return succeeded, failed
|
||||
|
|
@ -1,318 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Process handler for launching ssh-based roslaunch child processes.
|
||||
"""
|
||||
|
||||
from __future__ import with_statement
|
||||
|
||||
import os
|
||||
import sys
|
||||
import socket
|
||||
import traceback
|
||||
import xmlrpclib
|
||||
|
||||
from roslaunch.core import printlog, printerrlog
|
||||
import roslaunch.pmon
|
||||
import roslaunch.server
|
||||
|
||||
import logging
|
||||
_logger = logging.getLogger("roslaunch.remoteprocess")
|
||||
|
||||
# #1975 timeout for creating ssh connections
|
||||
TIMEOUT_SSH_CONNECT = 30.
|
||||
|
||||
def ssh_check_known_hosts(ssh, address, port, username=None, logger=None):
|
||||
"""
|
||||
Validation routine for loading the host keys and making sure that
|
||||
they are configured properly for the desired SSH. The behavior of
|
||||
this routine can be modified by the ROSLAUNCH_SSH_UNKNOWN
|
||||
environment variable, which enables the paramiko.AutoAddPolicy.
|
||||
|
||||
@param ssh: paramiko SSH client
|
||||
@type ssh: L{paramiko.SSHClient}
|
||||
@param address: SSH IP address
|
||||
@type address: str
|
||||
@param port: SSH port
|
||||
@type port: int
|
||||
@param username: optional username to include in error message if check fails
|
||||
@type username: str
|
||||
@param logger: (optional) logger to record tracebacks to
|
||||
@type logger: logging.Logger
|
||||
@return: error message if improperly configured, or None
|
||||
@rtype: str
|
||||
"""
|
||||
import paramiko
|
||||
try:
|
||||
try:
|
||||
if os.path.isfile('/etc/ssh/ssh_known_hosts'): #default ubuntu location
|
||||
ssh.load_system_host_keys('/etc/ssh/ssh_known_hosts')
|
||||
except IOError:
|
||||
pass
|
||||
ssh.load_system_host_keys() #default user location
|
||||
except:
|
||||
if logger:
|
||||
logger.error(traceback.format_exc())
|
||||
# as seen in #767, base64 raises generic Error.
|
||||
#
|
||||
# A corrupt pycrypto build can also cause this, though
|
||||
# the cause of the corrupt builds has been fixed.
|
||||
return "cannot load SSH host keys -- your known_hosts file may be corrupt"
|
||||
|
||||
# #1849: paramiko will raise an SSHException with an 'Unknown
|
||||
# server' message if the address is not in the known_hosts
|
||||
# file. This causes a lot of confusion to users, so we try
|
||||
# and diagnose this in advance and offer better guidance
|
||||
|
||||
# - ssh.get_host_keys() does not return the system host keys
|
||||
hk = ssh._system_host_keys
|
||||
override = os.environ.get('ROSLAUNCH_SSH_UNKNOWN', 0)
|
||||
if override == '1':
|
||||
ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy())
|
||||
elif hk.lookup(address) is None:
|
||||
port_str = user_str = ''
|
||||
if port != 22:
|
||||
port_str = "-p %s "%port
|
||||
if username:
|
||||
user_str = username+'@'
|
||||
return """%s is not in your SSH known_hosts file.
|
||||
|
||||
Please manually:
|
||||
ssh %s%s%s
|
||||
|
||||
then try roslaunching again.
|
||||
|
||||
If you wish to configure roslaunch to automatically recognize unknown
|
||||
hosts, please set the environment variable ROSLAUNCH_SSH_UNKNOWN=1"""%(address, user_str, port_str, address)
|
||||
|
||||
|
||||
class SSHChildROSLaunchProcess(roslaunch.server.ChildROSLaunchProcess):
|
||||
"""
|
||||
Process wrapper for launching and monitoring a child roslaunch process over SSH
|
||||
"""
|
||||
def __init__(self, run_id, name, server_uri, env, machine):
|
||||
if machine.ros_root:
|
||||
cmd = os.path.join(machine.ros_root, 'bin', 'roslaunch')
|
||||
else: # assumes user has mapped onto path
|
||||
cmd = 'roslaunch'
|
||||
args = [cmd, '-c', name, '-u', server_uri, '--run_id', run_id]
|
||||
super(SSHChildROSLaunchProcess, self).__init__(name, args, env)
|
||||
self.machine = machine
|
||||
self.ssh = self.sshin = self.sshout = self.ssherr = None
|
||||
self.started = False
|
||||
self.uri = None
|
||||
# self.is_dead is a flag set by is_alive that affects whether or not we
|
||||
# log errors during a stop().
|
||||
self.is_dead = False
|
||||
|
||||
def _ssh_exec(self, command, env, address, port, username=None, password=None):
|
||||
if env:
|
||||
env_command = "env "+' '.join(["%s=%s"%(k,v) for (k, v) in env.iteritems()])
|
||||
command = "%s %s"%(env_command, command)
|
||||
try:
|
||||
# as pycrypto 2.0.1 is EOL, disable it's Python 2.6 deprecation warnings
|
||||
import warnings
|
||||
warnings.filterwarnings("ignore", message="the sha module is deprecated; use the hashlib module instead")
|
||||
warnings.filterwarnings("ignore", message="the md5 module is deprecated; use hashlib instead")
|
||||
|
||||
import Crypto
|
||||
except ImportError, e:
|
||||
_logger.error("cannot use SSH: pycrypto is not installed")
|
||||
return None, "pycrypto is not installed"
|
||||
try:
|
||||
import paramiko
|
||||
except ImportError, e:
|
||||
_logger.error("cannot use SSH: paramiko is not installed")
|
||||
return None, "paramiko is not installed"
|
||||
#load ssh client and connect
|
||||
ssh = paramiko.SSHClient()
|
||||
err_msg = ssh_check_known_hosts(ssh, address, port, username=username, logger=_logger)
|
||||
|
||||
if not err_msg:
|
||||
username_str = '%s@'%username if username else ''
|
||||
try:
|
||||
if not password: #use SSH agent
|
||||
ssh.connect(address, port, username, timeout=TIMEOUT_SSH_CONNECT)
|
||||
else: #use SSH with login/pass
|
||||
ssh.connect(address, port, username, password, timeout=TIMEOUT_SSH_CONNECT)
|
||||
except paramiko.BadHostKeyException:
|
||||
_logger.error(traceback.format_exc())
|
||||
err_msg = "Unable to verify host key for remote computer[%s:%s]"%(address, port)
|
||||
except paramiko.AuthenticationException:
|
||||
_logger.error(traceback.format_exc())
|
||||
err_msg = "Authentication to remote computer[%s%s:%s] failed.\nA common cause of this error is a missing key in your authorized_keys file."%(username_str, address, port)
|
||||
except paramiko.SSHException, e:
|
||||
_logger.error(traceback.format_exc())
|
||||
if str(e).startswith("Unknown server"):
|
||||
pass
|
||||
err_msg = "Unable to establish ssh connection to [%s%s:%s]: %s"%(username_str, address, port, e)
|
||||
except socket.error, e:
|
||||
# #1824
|
||||
if e[0] == 111:
|
||||
err_msg = "network connection refused by [%s:%s]"%(address, port)
|
||||
else:
|
||||
err_msg = "network error connecting to [%s:%s]: %s"%(address, port, str(e))
|
||||
if err_msg:
|
||||
return None, err_msg
|
||||
else:
|
||||
sshin, sshout, ssherr = ssh.exec_command(command)
|
||||
return (ssh, sshin, sshout, ssherr), "executed remotely"
|
||||
|
||||
def start(self):
|
||||
"""
|
||||
Start the remote process. This will create an SSH connection
|
||||
to the remote host.
|
||||
"""
|
||||
self.started = False #won't set to True until we are finished
|
||||
self.ssh = self.sshin = self.sshout = self.ssherr = None
|
||||
try:
|
||||
self.lock.acquire()
|
||||
name = self.name
|
||||
m = self.machine
|
||||
if m.user is not None:
|
||||
printlog("remote[%s]: creating ssh connection to %s:%s, user[%s]"%(name, m.address, m.ssh_port, m.user))
|
||||
else:
|
||||
printlog("remote[%s]: creating ssh connection to %s:%s"%(name, m.address, m.ssh_port))
|
||||
_logger.info("remote[%s]: invoking with ssh exec args [%s], env: %s"%(name, ' '.join(self.args), self.env))
|
||||
sshvals, msg = self._ssh_exec(' '.join(self.args), self.env, m.address, m.ssh_port, m.user, m.password)
|
||||
if sshvals is None:
|
||||
printerrlog("remote[%s]: failed to launch on %s:\n\n%s\n\n"%(name, m.name, msg))
|
||||
return False
|
||||
self.ssh, self.sshin, self.sshout, self.ssherr = sshvals
|
||||
printlog("remote[%s]: ssh connection created"%name)
|
||||
self.started = True
|
||||
return True
|
||||
finally:
|
||||
self.lock.release()
|
||||
|
||||
def getapi(self):
|
||||
"""
|
||||
@return: ServerProxy to remote client XMLRPC server
|
||||
@rtype: L{ServerProxy}
|
||||
"""
|
||||
if self.uri:
|
||||
return xmlrpclib.ServerProxy(self.uri)
|
||||
else:
|
||||
return None
|
||||
|
||||
def is_alive(self):
|
||||
"""
|
||||
@return: True if the process is alive. is_alive needs to be
|
||||
called periodically as it drains the SSH buffer
|
||||
@rtype: bool
|
||||
"""
|
||||
if self.started and not self.ssh:
|
||||
return False
|
||||
elif not self.started:
|
||||
return True #not started is equivalent to alive in our logic
|
||||
s = self.ssherr
|
||||
s.channel.settimeout(0)
|
||||
try:
|
||||
#drain the pipes
|
||||
data = s.read(2048)
|
||||
if not len(data):
|
||||
self.is_dead = True
|
||||
return False
|
||||
# #2012 il8n: ssh *should* be UTF-8, but often isn't
|
||||
# (e.g. Japan)
|
||||
data = data.decode('utf-8')
|
||||
printerrlog("remote[%s]: %s"%(self.name, data))
|
||||
except socket.timeout:
|
||||
pass
|
||||
except IOError:
|
||||
return False
|
||||
except UnicodeDecodeError:
|
||||
# #2012: soft fail, printing is not essential. This occurs
|
||||
# with older machines that don't send utf-8 over ssh
|
||||
pass
|
||||
|
||||
s = self.sshout
|
||||
s.channel.settimeout(0)
|
||||
try:
|
||||
#drain the pipes
|
||||
#TODO: write to log file
|
||||
data = s.read(2048)
|
||||
if not len(data):
|
||||
self.is_dead = True
|
||||
return False
|
||||
# data = data.decode('utf-8')
|
||||
#print "DATA", data
|
||||
except socket.timeout:
|
||||
pass
|
||||
except IOError:
|
||||
return False
|
||||
return True
|
||||
|
||||
def stop(self, errors=[]):
|
||||
"""
|
||||
Terminate this process, including the SSH connection.
|
||||
"""
|
||||
try:
|
||||
self.lock.acquire()
|
||||
if not self.ssh:
|
||||
return
|
||||
|
||||
# call the shutdown API first as closing the SSH connection
|
||||
# won't actually kill the process unless it triggers SIGPIPE
|
||||
try:
|
||||
api = self.getapi()
|
||||
if api is not None:
|
||||
#TODO: probably need a timeout on this
|
||||
api.shutdown()
|
||||
except socket.error:
|
||||
# normal if process is already dead
|
||||
address, port = self.machine.address, self.machine.ssh_port
|
||||
if not self.is_dead:
|
||||
printerrlog("remote[%s]: unable to contact [%s] to shutdown remote processes!"%(self.name, address))
|
||||
else:
|
||||
printlog("remote[%s]: unable to contact [%s] to shutdown cleanly. The remote roslaunch may have exited already."%(self.name, address))
|
||||
except:
|
||||
# temporary: don't really want to log here as this
|
||||
# may occur during shutdown
|
||||
traceback.print_exc()
|
||||
|
||||
_logger.info("remote[%s]: closing ssh connection", self.name)
|
||||
self.sshin.close()
|
||||
self.sshout.close()
|
||||
self.ssherr.close()
|
||||
self.ssh.close()
|
||||
|
||||
self.sshin = None
|
||||
self.sshout = None
|
||||
self.ssherr = None
|
||||
self.ssh = None
|
||||
_logger.info("remote[%s]: ssh connection closed", self.name)
|
||||
finally:
|
||||
self.lock.release()
|
|
@ -1,247 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2009, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Uncategorized utility routines for roslaunch.
|
||||
|
||||
This API should not be considered stable.
|
||||
"""
|
||||
|
||||
import os
|
||||
import time
|
||||
|
||||
from roslib.names import SEP
|
||||
|
||||
import roslaunch.core
|
||||
from rosmaster import DEFAULT_MASTER_PORT
|
||||
|
||||
def check_log_disk_usage():
|
||||
"""
|
||||
Check size of log directory. If high, print warning to user
|
||||
"""
|
||||
try:
|
||||
import rosclean
|
||||
import roslib.rosenv
|
||||
d = roslib.rosenv.get_log_dir()
|
||||
roslaunch.core.printlog("Checking log directory for disk usage. This may take awhile.\nPress Ctrl-C to interrupt")
|
||||
disk_usage = rosclean.get_disk_usage(d)
|
||||
# warn if over a gig
|
||||
if disk_usage > 1073741824:
|
||||
roslaunch.core.printerrlog("WARNING: disk usage in log directory [%s] is over 1GB.\nIt's recommended that you use the 'rosclean' command."%d)
|
||||
else:
|
||||
roslaunch.core.printlog("Done checking log file disk usage. Usage is <1GB.")
|
||||
except:
|
||||
pass
|
||||
|
||||
def resolve_launch_arguments(args):
|
||||
"""
|
||||
Resolve command-line args to roslaunch filenames.
|
||||
@return: resolved filenames
|
||||
@rtype: [str]
|
||||
"""
|
||||
import roslib.packages
|
||||
import roslib.scriptutil
|
||||
|
||||
# strip remapping args for processing
|
||||
args = roslib.scriptutil.myargv(args)
|
||||
|
||||
# user can either specify:
|
||||
# - filename + launch args
|
||||
# - package + relative-filename + launch args
|
||||
if not args:
|
||||
return args
|
||||
resolved_args = None
|
||||
top = args[0]
|
||||
if os.path.isfile(top):
|
||||
resolved_args = [top] + args[1:]
|
||||
elif len(args) == 1:
|
||||
raise roslaunch.core.RLException("[%s] does not exist. please specify a package and launch file"%(top))
|
||||
else:
|
||||
try:
|
||||
resolved = roslib.packages.find_resource(top, args[1])
|
||||
if len(resolved) == 1:
|
||||
resolved = resolved[0]
|
||||
elif len(resolved) > 1:
|
||||
raise roslaunch.core.RLException("multiple files named [%s] in package [%s].\nPlease specify full path instead"%(args[1], top))
|
||||
except roslib.packages.InvalidROSPkgException, e:
|
||||
raise roslaunch.core.RLException("[%s] is not a package or launch file name"%top)
|
||||
if not resolved:
|
||||
raise roslaunch.core.RLException("cannot locate [%s] in package [%s]"%(args[1], top))
|
||||
else:
|
||||
resolved_args = [resolved] + args[2:]
|
||||
return resolved_args
|
||||
|
||||
def _wait_for_master():
|
||||
"""
|
||||
Block until ROS Master is online
|
||||
|
||||
@raise RuntimeError: if unexpected error occurs
|
||||
"""
|
||||
m = roslaunch.core.Master() # get a handle to the default master
|
||||
is_running = m.is_running()
|
||||
if not is_running:
|
||||
roslaunch.core.printlog("roscore/master is not yet running, will wait for it to start")
|
||||
while not is_running:
|
||||
time.sleep(0.1)
|
||||
is_running = m.is_running()
|
||||
if is_running:
|
||||
roslaunch.core.printlog("master has started, initiating launch")
|
||||
else:
|
||||
raise RuntimeError("unknown error waiting for master to start")
|
||||
|
||||
_terminal_name = None
|
||||
|
||||
def _set_terminal(s):
|
||||
import platform
|
||||
if platform.system() in ['FreeBSD', 'Linux', 'Darwin', 'Unix']:
|
||||
try:
|
||||
print '\033]2;%s\007'%(s)
|
||||
except:
|
||||
pass
|
||||
|
||||
def update_terminal_name(ros_master_uri):
|
||||
"""
|
||||
append master URI to the terminal name
|
||||
"""
|
||||
if _terminal_name:
|
||||
_set_terminal(_terminal_name + ' ' + ros_master_uri)
|
||||
|
||||
def change_terminal_name(args, is_core):
|
||||
"""
|
||||
use echo (where available) to change the name of the terminal window
|
||||
"""
|
||||
global _terminal_name
|
||||
_terminal_name = 'roscore' if is_core else ','.join(args)
|
||||
_set_terminal(_terminal_name)
|
||||
|
||||
def get_or_generate_uuid(options_runid, options_wait_for_master):
|
||||
"""
|
||||
@param options_runid: run_id value from command-line or None
|
||||
@type options_runid: str
|
||||
@param options_wait_for_master: the wait_for_master command
|
||||
option. If this is True, it means that we must retrieve the
|
||||
value from the parameter server and need to avoid any race
|
||||
conditions with the roscore being initialized.
|
||||
@type options_wait_for_master: bool
|
||||
"""
|
||||
import roslib.scriptutil
|
||||
# Three possible sources of the run_id:
|
||||
#
|
||||
# - if we're a child process, we get it from options_runid
|
||||
# - if there's already a roscore running, read from the param server
|
||||
# - generate one if we're running the roscore
|
||||
if options_runid:
|
||||
return options_runid
|
||||
|
||||
# #773: Generate a run_id to use if we launch a master
|
||||
# process. If a master is already running, we'll get the
|
||||
# run_id from it instead
|
||||
param_server = roslib.scriptutil.get_param_server()
|
||||
val = None
|
||||
while val is None:
|
||||
try:
|
||||
code, msg, val = param_server.getParam('/roslaunch', '/run_id')
|
||||
if code == 1:
|
||||
return val
|
||||
else:
|
||||
val = None
|
||||
raise RuntimeError("unknown error communicating with Parameter Server: %s"%msg)
|
||||
except:
|
||||
if not options_wait_for_master:
|
||||
val = roslaunch.core.generate_run_id()
|
||||
return val
|
||||
|
||||
def check_roslaunch(f):
|
||||
"""
|
||||
Check roslaunch file for errors, returning error message if check fails. This routine
|
||||
is mainly to support rostest's roslaunch_check.
|
||||
|
||||
@param f: roslaunch file name
|
||||
@type f: str
|
||||
@return: error message or None
|
||||
@rtype: str
|
||||
"""
|
||||
try:
|
||||
import roslaunch.config
|
||||
config = roslaunch.config.load_config_default([f], DEFAULT_MASTER_PORT, verbose=False)
|
||||
except roslaunch.RLException, e:
|
||||
return str(e)
|
||||
|
||||
errors = []
|
||||
# check for missing deps
|
||||
import roslaunch.depends
|
||||
base_pkg, file_deps, missing = roslaunch.depends.roslaunch_deps([f])
|
||||
for pkg, miss in missing.iteritems():
|
||||
if miss:
|
||||
errors.append("Missing manifest dependencies: %s/manifest.xml: %s"%(pkg, ', '.join(miss)))
|
||||
|
||||
# load all node defs
|
||||
nodes = []
|
||||
for filename, rldeps in file_deps.iteritems():
|
||||
nodes.extend(rldeps.nodes)
|
||||
|
||||
# check for missing packages
|
||||
import roslib.packages
|
||||
for pkg, node_type in nodes:
|
||||
try:
|
||||
roslib.packages.get_pkg_dir(pkg, required=True)
|
||||
except:
|
||||
errors.append("cannot find package [%s] for node [%s]"%(pkg, node_type))
|
||||
|
||||
# check for missing nodes
|
||||
for pkg, node_type in nodes:
|
||||
try:
|
||||
if not roslib.packages.find_node(pkg, node_type):
|
||||
errors.append("cannot find node [%s] in package [%s]"%(node_type, pkg))
|
||||
except Exception, e:
|
||||
errors.append("unable to find node [%s/%s]: %s"%(pkg, node_type, str(e)))
|
||||
|
||||
# Check for configuration errors, #2889
|
||||
for err in config.config_errors:
|
||||
errors.append('ROSLaunch config error: %s' % err)
|
||||
|
||||
if errors:
|
||||
return '\n'.join(errors)
|
||||
|
||||
|
||||
def namespaces_of(name):
|
||||
if name is None:
|
||||
raise ValueError('name')
|
||||
if not isinstance(name, basestring):
|
||||
raise TypeError('name')
|
||||
if not name:
|
||||
return [SEP]
|
||||
|
||||
splits = [x for x in name.split(SEP) if x]
|
||||
return ['/'] + ['/'+SEP.join(splits[:i]) for i in xrange(1, len(splits))]
|
|
@ -1,82 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Implementation for roslaunch-logs command-line utility.
|
||||
"""
|
||||
|
||||
import os
|
||||
import sys
|
||||
import time
|
||||
import traceback
|
||||
|
||||
import roslib.rosenv
|
||||
import roslib.scriptutil
|
||||
|
||||
NAME = 'roslaunch-logs'
|
||||
|
||||
def get_run_id():
|
||||
try:
|
||||
param_server = roslib.scriptutil.get_param_server()
|
||||
code, msg, val = param_server.getParam('/roslaunch', '/run_id')
|
||||
if code == 1:
|
||||
return val
|
||||
except: # cannot contact parameter server
|
||||
pass
|
||||
|
||||
def logs_main():
|
||||
from optparse import OptionParser
|
||||
parser = OptionParser(usage="usage: %prog", prog=NAME)
|
||||
options, args = parser.parse_args()
|
||||
if args:
|
||||
parser.error("%s takes no arguments"%NAME)
|
||||
|
||||
log_dir = roslib.rosenv.get_log_dir()
|
||||
if not log_dir:
|
||||
print >> sys.stderr, "Cannot determine ROS log directory"
|
||||
sys.exit(1)
|
||||
|
||||
run_id = get_run_id()
|
||||
if not run_id:
|
||||
# go ahead and print the log directory
|
||||
print >> sys.stderr, "No active roscore"
|
||||
print log_dir
|
||||
sys.exit(2)
|
||||
|
||||
print os.path.join(log_dir, run_id)
|
||||
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
logs_main()
|
|
@ -1,118 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Scripting interface for roslaunch
|
||||
"""
|
||||
|
||||
from roslaunch.core import Node, Test, Master, RLException
|
||||
|
||||
import roslaunch.config
|
||||
import roslaunch.parent
|
||||
import roslaunch.xmlloader
|
||||
|
||||
class ROSLaunch(object):
|
||||
"""
|
||||
ROSLaunchParent represents the main 'parent' roslaunch process. It
|
||||
is responsible for loading the launch files, assigning machines,
|
||||
and then starting up any remote processes. The __main__ method
|
||||
delegates most of runtime to ROSLaunchParent.
|
||||
|
||||
This must be called from the Python Main thread due to signal registration.
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
"""
|
||||
@raise RLException: if fails to initialize
|
||||
"""
|
||||
import rosgraph.masterapi
|
||||
master = rosgraph.masterapi.Master('/roslaunch_script')
|
||||
uuid = master.getParam('/run_id')
|
||||
self.parent = roslaunch.parent.ROSLaunchParent(uuid, [], is_core=False)
|
||||
self.started = False
|
||||
|
||||
def load(self, f):
|
||||
"""
|
||||
Load roslaunch file
|
||||
|
||||
@param f: filename
|
||||
@type f: str
|
||||
"""
|
||||
raise NotImplemented
|
||||
|
||||
def load_str(self, s):
|
||||
"""
|
||||
Load roslaunch string
|
||||
|
||||
@param s: string representation of roslaunch config
|
||||
@type s: str
|
||||
"""
|
||||
raise NotImplemented
|
||||
|
||||
def launch(self, node):
|
||||
"""
|
||||
Launch a roslaunch node instance
|
||||
|
||||
@param node: roslaunch Node instance
|
||||
@type node: roslaunch.Node
|
||||
@return: node process
|
||||
@rtype: roslaunch.Process
|
||||
@raise RLException: if launch fails
|
||||
"""
|
||||
if not self.started:
|
||||
raise RLException("please start ROSLaunch first")
|
||||
elif not isinstance(node, Node):
|
||||
raise ValueError("arg must be of type Node")
|
||||
|
||||
proc, success = self.parent.runner.launch_node(node)
|
||||
if not success:
|
||||
raise RLException("failed to launch %s/%s"%(node.package, node.type))
|
||||
return proc
|
||||
|
||||
def start(self):
|
||||
"""
|
||||
Start roslaunch. This will launch any pre-configured launches and spin up the process monitor thread.
|
||||
"""
|
||||
self.parent.start(auto_terminate=False)
|
||||
self.started = True
|
||||
|
||||
def spin(self):
|
||||
self.parent.spin()
|
||||
|
||||
def spin_once(self):
|
||||
self.parent.spin_once()
|
||||
|
||||
def stop(self):
|
||||
self.parent.shutdown()
|
||||
|
|
@ -1,516 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
XML-RPC servers for parent and children
|
||||
|
||||
Following typical roslib-based XMLRPC code, code is divided into:
|
||||
|
||||
a) Handlers: these actually define and execute the XML-RPC API
|
||||
b) Nodes: these run the XML-RPC server
|
||||
|
||||
In this code you'll find 'Parent' and 'Child' code. The parent node
|
||||
is the original roslaunch process. The child nodes are the child
|
||||
processes it launches in order to handle remote launching (or
|
||||
execution as a different user).
|
||||
"""
|
||||
|
||||
import logging
|
||||
import os
|
||||
import socket
|
||||
import sys
|
||||
import time
|
||||
import traceback
|
||||
import urlparse
|
||||
import xmlrpclib
|
||||
|
||||
import roslib.network as network
|
||||
import roslib.xmlrpc as xmlrpc
|
||||
|
||||
import roslaunch.config
|
||||
from roslaunch.pmon import ProcessListener, Process
|
||||
import roslaunch.xmlloader
|
||||
|
||||
from roslaunch.launch import ROSLaunchRunner
|
||||
from roslaunch.core import RLException, \
|
||||
add_printlog_handler, add_printerrlog_handler, printlog, printerrlog, printlog_bold
|
||||
|
||||
#For using Log message level constants
|
||||
from roslib.msg import Log
|
||||
|
||||
# interface class so that we don't have circular deps
|
||||
class ChildROSLaunchProcess(Process):
|
||||
"""
|
||||
API for remote roslaunch processes
|
||||
"""
|
||||
def __init__(self, name, args, env):
|
||||
super(ChildROSLaunchProcess, self).__init__('roslaunch', name, args, env, False)
|
||||
self.uri = None
|
||||
|
||||
def set_uri(self, uri):
|
||||
self.uri = uri
|
||||
|
||||
class ROSLaunchBaseHandler(xmlrpc.XmlRpcHandler):
|
||||
"""
|
||||
Common XML-RPC API for the roslaunch server and child node
|
||||
"""
|
||||
def __init__(self, pm):
|
||||
self.pm = pm
|
||||
self.logger = logging.getLogger('roslaunch.server')
|
||||
if self.pm is None:
|
||||
raise RLException("cannot create xmlrpc handler: pm is not initialized")
|
||||
|
||||
#TODO: kill process, restart (with optional prefix). list active, list dead. CPU usage
|
||||
|
||||
def list_processes(self):
|
||||
"""
|
||||
@return: code, msg, process list.
|
||||
Process list is two lists, where first list of
|
||||
active process names along with the number of times that
|
||||
process has been spawned. Second list contains dead process
|
||||
names and their spawn count.
|
||||
@rtype: int, str, [[(str, int),], [(str,int),]]
|
||||
"""
|
||||
return 1, "processes on parent machine", self.pm.get_process_names_with_spawn_count()
|
||||
|
||||
def process_info(self, process_name):
|
||||
"""
|
||||
@return: dictionary of metadata about process. Keys vary by implementation
|
||||
@rtype: int, str, dict
|
||||
"""
|
||||
p = self.pm.get_process(process_name)
|
||||
if p is None:
|
||||
return -1, "no process by that name", {}
|
||||
else:
|
||||
return 1, "process info", p.get_info()
|
||||
|
||||
def get_pid(self):
|
||||
"""
|
||||
@return: code, msg, pid
|
||||
@rtype: int, str, int
|
||||
"""
|
||||
|
||||
pid = os.getpid()
|
||||
return 1, str(pid), pid
|
||||
|
||||
def get_node_names(self):
|
||||
"""
|
||||
@return: code, msg, list of node names
|
||||
@rtype: int, str, [str]
|
||||
"""
|
||||
if self.pm is None:
|
||||
return 0, "uninitialized", []
|
||||
return 1, "node names", self.pm.get_active_names()
|
||||
|
||||
def _shutdown(self, reason):
|
||||
"""
|
||||
xmlrpc.XmlRpcHandler API: inform handler of shutdown
|
||||
@param reason: human-readable shutdown reason
|
||||
@type reason: str
|
||||
"""
|
||||
return 1, '', 1
|
||||
|
||||
|
||||
# Uses camel-case network-API naming conventions
|
||||
class ROSLaunchParentHandler(ROSLaunchBaseHandler):
|
||||
"""
|
||||
XML-RPC API for the roslaunch server node
|
||||
"""
|
||||
|
||||
def __init__(self, pm, child_processes, listeners):
|
||||
"""
|
||||
@param child_processes: Map of remote processes so that server can update processes
|
||||
with information as children register. Handler will not modify
|
||||
keys.
|
||||
@type child_processes: {name : ChildROSLaunchProcess}.
|
||||
@param listeners [ProcessListener]: list of
|
||||
listeners to notify when process_died events occur.
|
||||
"""
|
||||
super(ROSLaunchParentHandler, self).__init__(pm)
|
||||
self.child_processes = child_processes
|
||||
self.listeners = listeners
|
||||
|
||||
def register(self, client, uri):
|
||||
"""
|
||||
Registration callback from newly launched roslaunch clients
|
||||
@param client: name of client
|
||||
@type client: str
|
||||
@param uri: XML-RPC URI of client
|
||||
@type uri: str
|
||||
@return: code, msg, ignore
|
||||
@rtype: int, str, int
|
||||
"""
|
||||
if client not in self.child_processes:
|
||||
self.logger.error("Unknown child [%s] registered with server", client)
|
||||
return -1, "unknown child [%s]"%client, 0
|
||||
else:
|
||||
self.logger.info("child [%s] registered with server, uri[%s]", client, uri)
|
||||
self.child_processes[client].set_uri(uri)
|
||||
return 1, "registered", 1
|
||||
|
||||
def list_children(self):
|
||||
"""
|
||||
List the roslaunch child processes.
|
||||
@return int, str, [str]: code, msg, list of the roslaunch children URIS
|
||||
"""
|
||||
return 1, 'roslaunch children', [v.uri for v in self.child_processes.itervalues() if v.uri is not None]
|
||||
|
||||
def process_died(self, process_name, exit_code):
|
||||
"""
|
||||
Inform roslaunch server that a remote process has died
|
||||
@param process_name: name of process that died
|
||||
@type process_name: str
|
||||
@param exit_code: exit code of remote process
|
||||
@type exit_code: int
|
||||
@return: code, msg, ignore
|
||||
@rtype: int, str, int
|
||||
"""
|
||||
for l in self.listeners:
|
||||
try:
|
||||
l.process_died(process_name, exit_code)
|
||||
except:
|
||||
self.logger.error(traceback.format_exc())
|
||||
return 1, '', 0
|
||||
|
||||
def log(self, client, level, message):
|
||||
"""
|
||||
Report a log message to the server
|
||||
@param client: name of client
|
||||
@type client: str
|
||||
@param level: log level (uses roslib.msg.Log levels)
|
||||
@type level: int
|
||||
@param message: message to log
|
||||
@type message: str
|
||||
"""
|
||||
try:
|
||||
if level >= Log.ERROR:
|
||||
printerrlog("[%s]: %s"%(client, message))
|
||||
else:
|
||||
#hack due to the fact that we only have one INFO level
|
||||
if 'started with pid' in message:
|
||||
printlog_bold("[%s]: %s"%(client, message))
|
||||
else:
|
||||
printlog("[%s]: %s"%(client, message))
|
||||
except:
|
||||
# can't trust the logging system at this point, so just dump to screen
|
||||
traceback.print_exc()
|
||||
return 1, '', 1
|
||||
|
||||
class ROSLaunchChildHandler(ROSLaunchBaseHandler):
|
||||
"""
|
||||
XML-RPC API implementation for child roslaunches
|
||||
NOTE: the client handler runs a process monitor so that
|
||||
it can track processes across requests
|
||||
"""
|
||||
|
||||
def __init__(self, run_id, name, server_uri, pm):
|
||||
"""
|
||||
@param server_uri: XML-RPC URI of server
|
||||
@type server_uri: str
|
||||
@param pm: process monitor to use
|
||||
@type pm: L{ProcessMonitor}
|
||||
@raise RLException: If parameters are invalid
|
||||
"""
|
||||
super(ROSLaunchChildHandler, self).__init__(pm)
|
||||
if server_uri is None:
|
||||
raise RLException("server_uri is not initialized")
|
||||
self.run_id = run_id
|
||||
|
||||
# parse the URI to make sure it's valid
|
||||
_, urlport = network.parse_http_host_and_port(server_uri)
|
||||
if urlport <= 0:
|
||||
raise RLException("ERROR: roslaunch server URI is not a valid XML-RPC URI. Value is [%s]"%m.uri)
|
||||
|
||||
self.name = name
|
||||
self.pm = pm
|
||||
self.server_uri = server_uri
|
||||
self.server = xmlrpclib.ServerProxy(server_uri)
|
||||
|
||||
def _shutdown(self, reason):
|
||||
"""
|
||||
xmlrpc.XmlRpcHandler API: inform handler of shutdown
|
||||
@param reason: human-readable shutdown reason
|
||||
@type reason: str
|
||||
"""
|
||||
if self.pm is not None:
|
||||
self.pm.shutdown()
|
||||
self.pm.join()
|
||||
self.pm = None
|
||||
|
||||
def shutdown(self):
|
||||
"""
|
||||
@return: code, msg, ignore
|
||||
@rtype: int, str, int
|
||||
"""
|
||||
self._shutdown("external call")
|
||||
return 1, "success", 1
|
||||
|
||||
def _log(self, level, message):
|
||||
"""
|
||||
log message to log file and roslaunch server
|
||||
@param level: log level
|
||||
@type level: int
|
||||
@param message: message to log
|
||||
@type message: str
|
||||
"""
|
||||
try:
|
||||
if self.logger is not None:
|
||||
self.logger.debug(message)
|
||||
if self.server is not None:
|
||||
self.server.log(str(self.name), level, str(message))
|
||||
except:
|
||||
self.logger.error(traceback.format_exc())
|
||||
|
||||
def launch(self, launch_xml):
|
||||
"""
|
||||
Launch the roslaunch XML file. Because this is a child
|
||||
roslaunch, it will not set parameters nor manipulate the
|
||||
master. Call blocks until launch is complete
|
||||
@param xml: roslaunch XML file to launch
|
||||
@type xml: str
|
||||
@return: code, msg, [ [ successful launches], [failed launches] ]
|
||||
@rtype: int, str, [ [str], [str] ]
|
||||
"""
|
||||
if self.pm is None:
|
||||
return 0, "uninitialized", -1
|
||||
|
||||
rosconfig = roslaunch.config.ROSLaunchConfig()
|
||||
try:
|
||||
roslaunch.xmlloader.XmlLoader().load_string(launch_xml, rosconfig)
|
||||
except roslaunch.xmlloader.XmlParseException, e:
|
||||
return -1, "ERROR: %s"%e, [[], []]
|
||||
|
||||
# check environment settings in config
|
||||
rosconfig.validate()
|
||||
|
||||
# won't actually do anything other than local, but still required
|
||||
rosconfig.assign_machines()
|
||||
|
||||
try:
|
||||
# roslaunch clients try to behave like normal roslaunches as much as possible. It's
|
||||
# mainly the responsibility of the roslaunch server to not give us any XML that might
|
||||
# cause conflict (e.g. master tags, param tags, etc...).
|
||||
self._log(Log.INFO, "launching nodes...")
|
||||
runner = ROSLaunchRunner(self.run_id, rosconfig, server_uri=self.server_uri, pmon=self.pm)
|
||||
succeeded, failed = runner.launch()
|
||||
self._log(Log.INFO, "... done launching nodes")
|
||||
# enable the process monitor to exit of all processes die
|
||||
self.pm.registrations_complete()
|
||||
return 1, "launched", [ succeeded, failed ]
|
||||
except Exception, e:
|
||||
return 0, "ERROR: %s"%traceback.format_exc(), [[], []]
|
||||
|
||||
_STARTUP_TIMEOUT = 5.0 #seconds
|
||||
|
||||
class ROSLaunchNode(xmlrpc.XmlRpcNode):
|
||||
"""
|
||||
Base XML-RPC server for roslaunch parent/child processes
|
||||
"""
|
||||
|
||||
def __init__(self, handler):
|
||||
"""
|
||||
@param handler: xmlrpc api handler
|
||||
@type handler: L{ROSLaunchBaseHandler}
|
||||
"""
|
||||
super(ROSLaunchNode, self).__init__(0, handler)
|
||||
|
||||
def start(self):
|
||||
"""
|
||||
Startup roslaunch server XML-RPC services
|
||||
@raise RLException: if server fails to start
|
||||
"""
|
||||
logger = logging.getLogger('roslaunch.server')
|
||||
logger.info("starting roslaunch XML-RPC server")
|
||||
super(ROSLaunchNode, self).start()
|
||||
|
||||
# wait for node thread to initialize
|
||||
timeout_t = time.time() + _STARTUP_TIMEOUT
|
||||
logger.info("waiting for roslaunch XML-RPC server to initialize")
|
||||
while not self.uri and time.time() < timeout_t:
|
||||
time.sleep(0.01)
|
||||
if not self.uri:
|
||||
raise RLException("XML-RPC initialization failed")
|
||||
|
||||
# Make sure our xmlrpc server is actually up. We've seen very
|
||||
# odd cases where remote nodes are unable to contact the
|
||||
# server but have been unable to prove this is the cause.
|
||||
server_up = False
|
||||
while not server_up and time.time() < timeout_t:
|
||||
try:
|
||||
code, msg, val = xmlrpclib.ServerProxy(self.uri).get_pid()
|
||||
if val != os.getpid():
|
||||
raise RLException("Server at [%s] did not respond with correct PID. There appears to be something wrong with the networking configuration"%self.uri)
|
||||
server_up = True
|
||||
except IOError:
|
||||
# presumably this can occur if we call in a small time
|
||||
# interval between the server socket port being
|
||||
# assigned and the XMLRPC server initializing, but it
|
||||
# is highly unlikely and unconfirmed
|
||||
time.sleep(0.1)
|
||||
except socket.error, (errno, msg):
|
||||
if errno == 113:
|
||||
p = urlparse.urlparse(self.uri)
|
||||
raise RLException("Unable to contact the address [%s], which should be local.\nThis is generally caused by:\n * bad local network configuration\n * bad ROS_IP environment variable\n * bad ROS_HOSTNAME environment variable\nCan you ping %s?"%(self.uri, p.hostname))
|
||||
else:
|
||||
time.sleep(0.1)
|
||||
if not server_up:
|
||||
raise RLException("Unable to contact my own XML-RPC server, this is a highly unusual error and should be reported immediately.\nMy URI is [%s]"%self.uri)
|
||||
printlog_bold("started roslaunch server %s"%self.uri)
|
||||
|
||||
def run(self):
|
||||
"""
|
||||
run() should not be called by higher-level code. ROSLaunchNode
|
||||
overrides underlying xmlrpc.XmlRpcNode implementation in order
|
||||
to log errors.
|
||||
"""
|
||||
try:
|
||||
super(ROSLaunchNode, self).run()
|
||||
except:
|
||||
logging.getLogger("roslaunch.remote").error(traceback.format_exc())
|
||||
print >> sys.stderr, "ERROR: failed to launch XML-RPC server for roslaunch"
|
||||
|
||||
class ROSLaunchParentNode(ROSLaunchNode):
|
||||
"""
|
||||
XML-RPC server for parent roslaunch.
|
||||
"""
|
||||
|
||||
def __init__(self, rosconfig, pm):
|
||||
"""
|
||||
@param config: ROSConfig launch configuration
|
||||
@type config: L{ROSConfig}
|
||||
@param pm: process monitor
|
||||
@type pm: L{ProcessMonitor}
|
||||
"""
|
||||
self.rosconfig = rosconfig
|
||||
self.listeners = []
|
||||
self.child_processes = {} #{ child-name : ChildROSLaunchProcess}.
|
||||
|
||||
if pm is None:
|
||||
raise RLException("cannot create parent node: pm is not initialized")
|
||||
handler = ROSLaunchParentHandler(pm, self.child_processes, self.listeners)
|
||||
super(ROSLaunchParentNode, self).__init__(handler)
|
||||
|
||||
def add_child(self, name, p):
|
||||
"""
|
||||
@param name: child roslaunch's name. NOTE: \a name is not
|
||||
the same as the machine config key.
|
||||
@type name: str
|
||||
@param p: process handle of child
|
||||
@type p: L{Process}
|
||||
"""
|
||||
self.child_processes[name] = p
|
||||
|
||||
def add_process_listener(self, l):
|
||||
"""
|
||||
Listen to events about remote processes dying. Not
|
||||
threadsafe. Must be called before processes started.
|
||||
@param l: Process listener
|
||||
@type l: L{ProcessListener}
|
||||
"""
|
||||
self.listeners.append(l)
|
||||
|
||||
class _ProcessListenerForwarder(ProcessListener):
|
||||
"""
|
||||
Simple listener that forwards ProcessListener events to a roslaunch server
|
||||
"""
|
||||
def __init__(self, server):
|
||||
self.server = server
|
||||
def process_died(self, process_name, exit_code):
|
||||
try:
|
||||
self.server.process_died(process_name, exit_code)
|
||||
except Exception, e:
|
||||
logging.getLogger("roslaunch.remote").error(traceback.format_exc())
|
||||
|
||||
class ROSLaunchChildNode(ROSLaunchNode):
|
||||
"""
|
||||
XML-RPC server for roslaunch child processes
|
||||
"""
|
||||
|
||||
def __init__(self, run_id, name, server_uri, pm):
|
||||
"""
|
||||
## Startup roslaunch remote client XML-RPC services. Blocks until shutdown
|
||||
## @param name: name of remote client
|
||||
## @type name: str
|
||||
## @param server_uri: XML-RPC URI of roslaunch server
|
||||
## @type server_uri: str
|
||||
## @return: XML-RPC URI
|
||||
## @rtype: str
|
||||
"""
|
||||
self.logger = logging.getLogger("roslaunch.server")
|
||||
self.run_id = run_id
|
||||
self.name = name
|
||||
self.server_uri = server_uri
|
||||
self.pm = pm
|
||||
|
||||
if self.pm is None:
|
||||
raise RLException("cannot create child node: pm is not initialized")
|
||||
handler = ROSLaunchChildHandler(self.run_id, self.name, self.server_uri, self.pm)
|
||||
super(ROSLaunchChildNode, self).__init__(handler)
|
||||
|
||||
def _register_with_server(self):
|
||||
"""
|
||||
Register child node with server
|
||||
"""
|
||||
name = self.name
|
||||
self.logger.info("attempting to register with roslaunch parent [%s]"%self.server_uri)
|
||||
try:
|
||||
server = xmlrpclib.ServerProxy(self.server_uri)
|
||||
code, msg, _ = server.register(name, self.uri)
|
||||
if code != 1:
|
||||
raise RLException("unable to register with roslaunch server: %s"%msg)
|
||||
except Exception, e:
|
||||
self.logger.error("Exception while registering with roslaunch parent [%s]: %s"%(self.server_uri, traceback.format_exc(e)))
|
||||
# fail
|
||||
raise RLException("Exception while registering with roslaunch parent [%s]: %s"%(self.server_uri, traceback.format_exc(e)))
|
||||
|
||||
self.logger.debug("child registered with server")
|
||||
|
||||
# register printlog handler so messages are funneled to remote
|
||||
def serverlog(msg):
|
||||
server.log(name, Log.INFO, msg)
|
||||
def servererrlog(msg):
|
||||
server.log(name, Log.ERROR, msg)
|
||||
add_printlog_handler(serverlog)
|
||||
add_printerrlog_handler(servererrlog)
|
||||
|
||||
# register process listener to forward process death events to main server
|
||||
self.pm.add_process_listener(_ProcessListenerForwarder(server))
|
||||
|
||||
def start(self):
|
||||
"""
|
||||
Initialize child. Must be called before run
|
||||
"""
|
||||
self.logger.info("starting roslaunch child process [%s], server URI is [%s]", self.name, self.server_uri)
|
||||
super(ROSLaunchChildNode, self).start()
|
||||
self._register_with_server()
|
|
@ -1,759 +0,0 @@
|
|||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# * Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# * Redistributions in binary form must reproduce the above
|
||||
# copyright notice, this list of conditions and the following
|
||||
# disclaimer in the documentation and/or other materials provided
|
||||
# with the distribution.
|
||||
# * Neither the name of Willow Garage, Inc. nor the names of its
|
||||
# contributors may be used to endorse or promote products derived
|
||||
# from this software without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
Roslaunch XML file parser.
|
||||
"""
|
||||
|
||||
from __future__ import with_statement
|
||||
|
||||
import itertools
|
||||
import os
|
||||
import sys
|
||||
|
||||
from xml.dom.minidom import parse, parseString
|
||||
from xml.dom import Node as DomNode #avoid aliasing
|
||||
|
||||
from roslib.names import make_global_ns, ns_join, is_global, is_private, PRIV_NAME
|
||||
import roslib.substitution_args
|
||||
|
||||
from roslaunch.core import Param, Node, Test, Machine, RLException, get_ros_package_path
|
||||
import roslaunch.loader
|
||||
|
||||
# use in our namespace
|
||||
SubstitutionException = roslib.substitution_args.SubstitutionException
|
||||
ArgException = roslib.substitution_args.ArgException
|
||||
|
||||
NS='ns'
|
||||
CLEAR_PARAMS='clear_params'
|
||||
|
||||
def _get_text(tag):
|
||||
buff = ''
|
||||
for t in tag.childNodes:
|
||||
if t.nodeType in [t.TEXT_NODE, t.CDATA_SECTION_NODE]:
|
||||
buff += t.data
|
||||
return buff
|
||||
|
||||
def ifunless_test(obj, tag, context):
|
||||
"""
|
||||
@return True: if tag should be processed according to its if/unless attributes
|
||||
"""
|
||||
if_val, unless_val = obj.opt_attrs(tag, context, ['if', 'unless'])
|
||||
if if_val is not None and unless_val is not None:
|
||||
raise XmlParseException("cannot set both 'if' and 'unless' on the same tag")
|
||||
if if_val is not None:
|
||||
if_val = roslaunch.loader.convert_value(if_val, 'bool')
|
||||
if if_val:
|
||||
return True
|
||||
elif unless_val is not None:
|
||||
unless_val = roslaunch.loader.convert_value(unless_val, 'bool')
|
||||
if not unless_val:
|
||||
return True
|
||||
else:
|
||||
return True
|
||||
return False
|
||||
|
||||
def ifunless(f):
|
||||
"""
|
||||
Decorator for evaluating whether or not tag function should run based on if/unless attributes
|
||||
"""
|
||||
def call(*args, **kwds):
|
||||
#TODO: logging, as well as check for verbose in kwds
|
||||
if ifunless_test(args[0], args[1], args[2]):
|
||||
return f(*args, **kwds)
|
||||
return call
|
||||
|
||||
# This code has gotten a bit crufty as roslaunch has grown far beyond
|
||||
# its original spec. It needs to be far more generic than it is in
|
||||
# order to not replicate bugs in multiple places.
|
||||
|
||||
class XmlParseException(RLException):
|
||||
"""Error with the XML syntax (e.g. invalid attribute/value combinations)"""
|
||||
pass
|
||||
|
||||
def _bool_attr(v, default, label):
|
||||
"""
|
||||
Validate boolean xml attribute.
|
||||
@param v: parameter value or None if no value provided
|
||||
@type v: any
|
||||
@param default: default value
|
||||
@type default: bool
|
||||
@param label: parameter name/label
|
||||
@type label: str
|
||||
@return: boolean value for attribute
|
||||
@rtype: bool
|
||||
@raise XmlParseException: if v is not in correct range or is empty.
|
||||
"""
|
||||
if v is None:
|
||||
return default
|
||||
if v.lower() == 'true':
|
||||
return True
|
||||
elif v.lower() == 'false':
|
||||
return False
|
||||
elif not v:
|
||||
raise XmlParseException("bool value for %s must be non-empty"%(label))
|
||||
else:
|
||||
raise XmlParseException("invalid bool value for %s: %s"%(label, v))
|
||||
|
||||
# maps machine 'default' attribute to Machine default property
|
||||
_is_default = {'true': True, 'false': False, 'never': False }
|
||||
# maps machine 'default' attribute to Machine assignable property
|
||||
_assignable = {'true': True, 'false': True, 'never': False }
|
||||
|
||||
# NOTE: code is currently in a semi-refactored state. I'm slowly
|
||||
# migrating common routines into the Loader class in the hopes it will
|
||||
# make it easier to write alternate loaders and also test.
|
||||
class XmlLoader(roslaunch.loader.Loader):
|
||||
"""
|
||||
Parser for roslaunch XML format. Loads parsed representation into ROSConfig model.
|
||||
"""
|
||||
|
||||
def __init__(self, resolve_anon=True):
|
||||
"""
|
||||
@param resolve_anon: If True (default), will resolve $(anon foo). If
|
||||
false, will leave these args as-is.
|
||||
@type resolve_anon: bool
|
||||
"""
|
||||
# store the root XmlContext so that outside code can access it
|
||||
self.root_context = None
|
||||
self.resolve_anon = resolve_anon
|
||||
|
||||
def resolve_args(self, args, context):
|
||||
"""
|
||||
Wrapper around roslib.substitution_args.resolve_args to set common parameters
|
||||
"""
|
||||
# resolve_args gets called a lot, so we optimize by testing for dollar sign before resolving
|
||||
if args and '$' in args:
|
||||
return roslib.substitution_args.resolve_args(args, context=context.resolve_dict, resolve_anon=self.resolve_anon)
|
||||
else:
|
||||
return args
|
||||
|
||||
def opt_attrs(self, tag, context, attrs):
|
||||
"""
|
||||
Helper routine for fetching and resolving optional tag attributes
|
||||
@param tag DOM tag
|
||||
@param context LoaderContext
|
||||
@param attrs (str): list of attributes to resolve
|
||||
"""
|
||||
def tag_value(tag, a):
|
||||
if tag.hasAttribute(a):
|
||||
# getAttribute returns empty string for non-existent
|
||||
# attributes, which makes it impossible to distinguish
|
||||
# with actual empty values
|
||||
return tag.getAttribute(a)
|
||||
else:
|
||||
return None
|
||||
return [self.resolve_args(tag_value(tag,a), context) for a in attrs]
|
||||
|
||||
def reqd_attrs(self, tag, context, attrs):
|
||||
"""
|
||||
Helper routine for fetching and resolving required tag attributes
|
||||
@param tag: DOM tag
|
||||
@param attrs: list of attributes to resolve
|
||||
@type attrs: (str)
|
||||
@raise KeyError: if required attribute is missing
|
||||
"""
|
||||
return [self.resolve_args(tag.attributes[a].value, context) for a in attrs]
|
||||
|
||||
def _check_attrs(self, tag, context, ros_config, attrs):
|
||||
tag_attrs = tag.attributes.keys()
|
||||
for t_a in tag_attrs:
|
||||
if not t_a in attrs and not t_a in ['if', 'unless']:
|
||||
ros_config.add_config_error("[%s] unknown <%s> attribute '%s'"%(context.filename, tag.tagName, t_a))
|
||||
#print >> sys.stderr, "WARNING:
|
||||
|
||||
MASTER_ATTRS = ('type', 'uri', 'auto')
|
||||
@ifunless
|
||||
def _master_tag(self, tag, context, ros_config):
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.MASTER_ATTRS)
|
||||
try:
|
||||
return self.create_master(*self.opt_attrs(tag, context, ('type', 'uri', 'auto')))
|
||||
except ValueError, e:
|
||||
raise XmlParseException("invalid <master> tag: %s"%str(e))
|
||||
|
||||
# 'ns' attribute is now deprecated and is an alias for
|
||||
# 'param'. 'param' is required if the value is a non-dictionary
|
||||
# type
|
||||
ROSPARAM_OPT_ATTRS = ('command', 'ns', 'file', 'param')
|
||||
@ifunless
|
||||
def _rosparam_tag(self, tag, context, ros_config, verbose=True):
|
||||
try:
|
||||
cmd, ns, file, param = self.opt_attrs(tag, context, (XmlLoader.ROSPARAM_OPT_ATTRS))
|
||||
# ns atribute is a bit out-moded and is only left in for backwards compatibility
|
||||
param = ns_join(ns or '', param or '')
|
||||
|
||||
# load is the default command
|
||||
cmd = cmd or 'load'
|
||||
|
||||
self.load_rosparam(context, ros_config, cmd, param, file, _get_text(tag), verbose=verbose)
|
||||
|
||||
except ValueError, e:
|
||||
raise roslaunch.loader.LoadException("error loading <rosparam> tag: \n\t"+str(e)+"\nXML is %s"%tag.toxml())
|
||||
|
||||
PARAM_ATTRS = ('name', 'value', 'type', 'value', 'textfile', 'binfile', 'command')
|
||||
@ifunless
|
||||
def _param_tag(self, tag, context, ros_config, force_local=False, verbose=True):
|
||||
"""
|
||||
@param force_local: if True, param must be added to context instead of ros_config
|
||||
@type force_local: bool
|
||||
"""
|
||||
try:
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.PARAM_ATTRS)
|
||||
|
||||
# compute name and value
|
||||
ptype = (tag.getAttribute('type') or 'auto').lower().strip()
|
||||
|
||||
vals = self.opt_attrs(tag, context, ('value', 'textfile', 'binfile', 'command'))
|
||||
if len([v for v in vals if v is not None]) != 1:
|
||||
raise XmlParseException(
|
||||
"<param> tag must have one and only one of value/textfile/binfile.")
|
||||
|
||||
# compute name. if name is a tilde name, it is placed in
|
||||
# the context. otherwise it is placed in the ros config.
|
||||
name = self.resolve_args(tag.attributes['name'].value.strip(), context)
|
||||
value = self.param_value(verbose, name, ptype, *vals)
|
||||
|
||||
if is_private(name) or force_local:
|
||||
p = Param(name, value)
|
||||
context.add_param(p)
|
||||
else:
|
||||
p = Param(ns_join(context.ns, name), value)
|
||||
ros_config.add_param(Param(ns_join(context.ns, name), value), filename=context.filename, verbose=verbose)
|
||||
return p
|
||||
|
||||
except KeyError, e:
|
||||
raise XmlParseException(
|
||||
"<param> tag is missing required attribute: %s. \n\nParam xml is %s"%(e, tag.toxml()))
|
||||
except ValueError, e:
|
||||
raise XmlParseException(
|
||||
"Invalid <param> tag: %s. \n\nParam xml is %s"%(e, tag.toxml()))
|
||||
|
||||
ARG_ATTRS = ('name', 'value', 'default')
|
||||
@ifunless
|
||||
def _arg_tag(self, tag, context, ros_config, verbose=True):
|
||||
"""
|
||||
Process an <arg> tag.
|
||||
"""
|
||||
try:
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.ARG_ATTRS)
|
||||
(name,) = self.reqd_attrs(tag, context, ('name',))
|
||||
value, default = self.opt_attrs(tag, context, ('value', 'default'))
|
||||
|
||||
if value is not None and default is not None:
|
||||
raise XmlParseException(
|
||||
"<arg> tag must have one and only one of value/default.")
|
||||
|
||||
context.add_arg(name, value=value, default=default)
|
||||
|
||||
except roslib.substitution_args.ArgException, e:
|
||||
raise XmlParseException(
|
||||
"arg '%s' is not defined. \n\nArg xml is %s"%(e, tag.toxml()))
|
||||
except Exception, e:
|
||||
raise XmlParseException(
|
||||
"Invalid <arg> tag: %s. \n\nArg xml is %s"%(e, tag.toxml()))
|
||||
|
||||
def _test_attrs(self, tag, context):
|
||||
"""
|
||||
Process attributes of <test> tag not present in <node>
|
||||
@return: test_name, time_limit
|
||||
@rtype: str, int
|
||||
"""
|
||||
for attr in ['respawn', 'output']:
|
||||
if tag.hasAttribute(attr):
|
||||
raise XmlParseException("<test> tags cannot have '%s' attribute"%attr)
|
||||
|
||||
test_name = self.resolve_args(tag.attributes['test-name'].value, context)
|
||||
time_limit = self.resolve_args(tag.getAttribute('time-limit'), context)
|
||||
retry = self.resolve_args(tag.getAttribute('retry'), context)
|
||||
if time_limit:
|
||||
try:
|
||||
time_limit = float(time_limit)
|
||||
except ValueError:
|
||||
raise XmlParseException("'time-limit' must be a number: [%s]"%time_limit)
|
||||
if time_limit <= 0.0:
|
||||
raise XmlParseException("'time-limit' must be a positive number")
|
||||
if retry:
|
||||
try:
|
||||
retry = int(retry)
|
||||
except ValueError:
|
||||
raise XmlParseException("'retry' must be a number: [%s]"%retry)
|
||||
|
||||
return test_name, time_limit, retry
|
||||
|
||||
NODE_ATTRS = ['pkg', 'type', 'machine', 'name', 'args', 'output', 'respawn', 'cwd', NS, CLEAR_PARAMS, 'launch-prefix', 'required']
|
||||
TEST_ATTRS = NODE_ATTRS + ['test-name','time-limit', 'retry']
|
||||
|
||||
@ifunless
|
||||
def _node_tag(self, tag, context, ros_config, default_machine, is_test=False, verbose=True):
|
||||
"""
|
||||
Process XML <node> or <test> tag
|
||||
@param tag: DOM node
|
||||
@type tag: Node
|
||||
@param context: namespace context
|
||||
@type context: L{LoaderContext}
|
||||
@param params: ROS parameter list
|
||||
@type params: [L{Param}]
|
||||
@param clear_params: list of ROS parameter names to clear before setting parameters
|
||||
@type clear_params: [str]
|
||||
@param default_machine: default machine to assign to node
|
||||
@type default_machine: str
|
||||
@param is_test: if set, will load as L{Test} object instead of L{Node} object
|
||||
@type is_test: bool
|
||||
"""
|
||||
try:
|
||||
if is_test:
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.TEST_ATTRS)
|
||||
(name,) = self.opt_attrs(tag, context, ('name',))
|
||||
test_name, time_limit, retry = self._test_attrs(tag, context)
|
||||
if not name:
|
||||
name = test_name
|
||||
else:
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.NODE_ATTRS)
|
||||
(name,) = self.reqd_attrs(tag, context, ('name',))
|
||||
|
||||
if not roslib.names.is_legal_name(name):
|
||||
ros_config.add_config_error("WARN: illegal <node> name '%s'.\nhttp://ros.org/wiki/Names\nThis will likely cause problems with other ROS tools.\nNode xml is %s"%(name, tag.toxml()))
|
||||
|
||||
child_ns = self._ns_clear_params_attr('node', tag, context, ros_config, node_name=name)
|
||||
param_ns = child_ns.child(name)
|
||||
|
||||
# required attributes
|
||||
pkg, node_type = self.reqd_attrs(tag, context, ('pkg', 'type'))
|
||||
|
||||
# optional attributes
|
||||
machine, args, output, respawn, cwd, launch_prefix, required = \
|
||||
self.opt_attrs(tag, context, ('machine', 'args', 'output', 'respawn', 'cwd', 'launch-prefix', 'required'))
|
||||
if tag.hasAttribute('machine') and not len(machine.strip()):
|
||||
raise XmlParseException("<node> 'machine' must be non-empty: [%s]"%machine)
|
||||
if not machine and default_machine:
|
||||
machine = default_machine.name
|
||||
# validate respawn, required
|
||||
required, respawn = [_bool_attr(*rr) for rr in ((required, False, 'required'),\
|
||||
(respawn, False, 'respawn'))]
|
||||
|
||||
# each node gets its own copy of <remap> arguments, which
|
||||
# it inherits from its parent
|
||||
remap_context = context.child('')
|
||||
|
||||
# nodes can have individual env args set in addition to
|
||||
# the ROS-specific ones.
|
||||
for t in [c for c in tag.childNodes if c.nodeType == DomNode.ELEMENT_NODE]:
|
||||
tag_name = t.tagName.lower()
|
||||
if tag_name == 'remap':
|
||||
remap_context.add_remap(self._remap_tag(t, context, ros_config))
|
||||
elif tag_name == 'param':
|
||||
self._param_tag(t, param_ns, ros_config, force_local=True, verbose=verbose)
|
||||
elif tag_name == 'rosparam':
|
||||
self._rosparam_tag(t, param_ns, ros_config, verbose=verbose)
|
||||
elif tag_name == 'env':
|
||||
self._env_tag(t, context, ros_config)
|
||||
else:
|
||||
ros_config.add_config_error("WARN: unrecognized '%s' tag in <node> tag. Node xml is %s"%(t.tagName, tag.toxml()))
|
||||
|
||||
# #1036 evaluate all ~params in context
|
||||
# TODO: can we get rid of force_local (above), remove this for loop, and just rely on param_tag logic instead?
|
||||
for p in itertools.chain(context.params, param_ns.params):
|
||||
pkey = p.key
|
||||
if is_private(pkey):
|
||||
# strip leading ~, which is optional/inferred
|
||||
pkey = pkey[1:]
|
||||
pkey = param_ns.ns + pkey
|
||||
ros_config.add_param(Param(pkey, p.value), verbose=verbose)
|
||||
|
||||
if not is_test:
|
||||
return Node(pkg, node_type, name=name, namespace=child_ns.ns, machine_name=machine,
|
||||
args=args, respawn=respawn,
|
||||
remap_args=remap_context.remap_args(), env_args=context.env_args,
|
||||
output=output, cwd=cwd, launch_prefix=launch_prefix,
|
||||
required=required, filename=context.filename)
|
||||
else:
|
||||
return Test(test_name, pkg, node_type, name=name, namespace=child_ns.ns,
|
||||
machine_name=machine, args=args,
|
||||
remap_args=remap_context.remap_args(), env_args=context.env_args,
|
||||
time_limit=time_limit, cwd=cwd, launch_prefix=launch_prefix,
|
||||
retry=retry, filename=context.filename)
|
||||
except KeyError, e:
|
||||
raise XmlParseException(
|
||||
"<%s> tag is missing required attribute: %s. Node xml is %s"%(tag.tagName, e, tag.toxml()))
|
||||
except XmlParseException, e:
|
||||
raise XmlParseException(
|
||||
"Invalid <node> tag: %s. \n\nNode xml is %s"%(e, tag.toxml()))
|
||||
except ValueError, e:
|
||||
raise XmlParseException(
|
||||
"Invalid <node> tag: %s. \n\nNode xml is %s"%(e, tag.toxml()))
|
||||
|
||||
MACHINE_ATTRS = ('name', 'address', 'ros-root', 'ros-package-path', 'ros-ip', 'ros-host-name',
|
||||
'ssh-port', 'user', 'password', 'default', 'timeout')
|
||||
@ifunless
|
||||
def _machine_tag(self, tag, context, ros_config, verbose=True):
|
||||
try:
|
||||
# clone context as <machine> tag sets up its own env args
|
||||
context = context.child(None)
|
||||
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.MACHINE_ATTRS)
|
||||
# required attributes
|
||||
name, address = self.reqd_attrs(tag, context, ('name', 'address'))
|
||||
|
||||
# optional attributes
|
||||
attrs = self.opt_attrs(tag, context,
|
||||
('ros-root', 'ros-package-path', 'ros-ip', 'ros-host-name',
|
||||
'ssh-port', 'user', 'password', 'default', 'timeout'))
|
||||
rosroot, ros_package_path, ros_ip, ros_host_name, \
|
||||
ssh_port, user, password, default, timeout = attrs
|
||||
|
||||
# DEPRECATED: remove in ROS 0.11 if possible
|
||||
if ros_host_name and ros_ip:
|
||||
raise XmlParseException("only one of 'ros-host-name' or 'ros-ip' may be set")
|
||||
if ros_ip:
|
||||
ros_config.add_config_error("WARN: ros-ip in <machine> tags is now deprecated. Use <env> tags instead")
|
||||
if ros_host_name:
|
||||
ros_config.add_config_error("WARN: ros-host-name in <machine> tags is now deprecated. Use <env> tags instead")
|
||||
|
||||
ros_host_name = ros_host_name or ros_ip #alias
|
||||
|
||||
if not ros_package_path:
|
||||
# the default vale of ros_package_path is dependent on
|
||||
# ros-root. If user has set ros-root they must also
|
||||
# explicitly set ros-package-path. If neither is set,
|
||||
# they default to the environment.
|
||||
if rosroot:
|
||||
ros_package_path = ''
|
||||
else:
|
||||
ros_package_path = get_ros_package_path()
|
||||
if not rosroot:
|
||||
try:
|
||||
rosroot = os.environ['ROS_ROOT']
|
||||
except KeyError, e:
|
||||
pass
|
||||
ssh_port = int(ssh_port or '22')
|
||||
|
||||
# check for default switch
|
||||
default = (default or 'false').lower()
|
||||
try:
|
||||
assignable = _assignable[default]
|
||||
is_default = _is_default[default]
|
||||
except KeyError, e:
|
||||
raise XmlParseException("Invalid value for 'attribute': %s"%default)
|
||||
|
||||
# load env args
|
||||
for t in [c for c in tag.childNodes if c.nodeType == DomNode.ELEMENT_NODE]:
|
||||
if t.tagName == 'env':
|
||||
self._env_tag(t, context, ros_config)
|
||||
else:
|
||||
ros_config.add_config_error("unrecognized '%s' tag in <%s> tag"%(t.tagName, tag.tagName))
|
||||
# cast timeout to float. make sure timeout wasn't an empty string or negative
|
||||
if timeout:
|
||||
try:
|
||||
timeout = float(timeout)
|
||||
except ValueError:
|
||||
raise XmlParseException("'timeout' be a number: [%s]"%timeout)
|
||||
elif timeout == '':
|
||||
raise XmlParseException("'timeout' cannot be empty")
|
||||
if timeout is not None and timeout <= 0.:
|
||||
raise XmlParseException("'timeout' be a positive number: [%s]"%timeout)
|
||||
|
||||
#TODO: change Machine representation to use an environment
|
||||
# dictionary instead of the umpteen ROS environment
|
||||
# variable settings.
|
||||
m = Machine(name, rosroot, ros_package_path, address,
|
||||
ros_ip=ros_host_name, ssh_port=ssh_port, user=user, password=password,
|
||||
assignable=assignable, env_args=context.env_args, timeout=timeout)
|
||||
return (m, is_default)
|
||||
except KeyError, e:
|
||||
raise XmlParseException("<machine> tag is missing required attribute: %s"%e)
|
||||
except SubstitutionException, e:
|
||||
raise XmlParseException(
|
||||
"%s. \n\nMachine xml is %s"%(e, tag.toxml()))
|
||||
except RLException, e:
|
||||
raise XmlParseException(
|
||||
"%s. \n\nMachine xml is %s"%(e, tag.toxml()))
|
||||
|
||||
REMAP_ATTRS = ('from', 'to')
|
||||
@ifunless
|
||||
def _remap_tag(self, tag, context, ros_config):
|
||||
try:
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.REMAP_ATTRS)
|
||||
return self.reqd_attrs(tag, context, XmlLoader.REMAP_ATTRS)
|
||||
except KeyError, e:
|
||||
raise XmlParseException("<remap> tag is missing required from/to attributes: %s"%tag.toxml())
|
||||
|
||||
ENV_ATTRS = ('name', 'value')
|
||||
@ifunless
|
||||
def _env_tag(self, tag, context, ros_config):
|
||||
try:
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.ENV_ATTRS)
|
||||
self.load_env(context, ros_config, *self.reqd_attrs(tag, context, XmlLoader.ENV_ATTRS))
|
||||
except ValueError, e:
|
||||
raise XmlParseException("Invalid <env> tag: %s. \nXML is %s"%(str(e), tag.toxml()))
|
||||
except KeyError, e:
|
||||
raise XmlParseException("<env> tag is missing required name/value attributes: %s"%tag.toxml())
|
||||
|
||||
def _ns_clear_params_attr(self, tag_name, tag, context, ros_config, node_name=None, include_filename=None):
|
||||
"""
|
||||
Common processing routine for xml tags with NS and CLEAR_PARAMS attributes
|
||||
|
||||
@param tag: DOM Node
|
||||
@type tag: Node
|
||||
@param context: current namespace context
|
||||
@type context: LoaderContext
|
||||
@param clear_params: list of params to clear
|
||||
@type clear_params: [str]
|
||||
@param node_name: name of node (for use when tag_name == 'node')
|
||||
@type node_name: str
|
||||
@param include_filename: <include> filename if this is an <include> tag. If specified, context will use include rules.
|
||||
@type include_filename: str
|
||||
@return: loader context
|
||||
@rtype: L{LoaderContext}
|
||||
"""
|
||||
if tag.hasAttribute(NS):
|
||||
ns = self.resolve_args(tag.getAttribute(NS), context)
|
||||
if not ns:
|
||||
raise XmlParseException("<%s> tag has an empty '%s' attribute"%(tag_name, NS))
|
||||
else:
|
||||
ns = None
|
||||
if include_filename is not None:
|
||||
child_ns = context.include_child(ns, include_filename)
|
||||
else:
|
||||
child_ns = context.child(ns)
|
||||
clear_p = self.resolve_args(tag.getAttribute(CLEAR_PARAMS), context)
|
||||
if clear_p:
|
||||
clear_p = _bool_attr(clear_p, False, 'clear_params')
|
||||
if clear_p:
|
||||
if tag_name == 'node':
|
||||
if not node_name:
|
||||
raise XmlParseException("<%s> tag must have a 'name' attribute to use '%s' attribute"%(tag_name, CLEAR_PARAMS))
|
||||
# use make_global_ns to give trailing slash in order to be consistent with XmlContext.ns
|
||||
ros_config.add_clear_param(make_global_ns(ns_join(child_ns.ns, node_name)))
|
||||
else:
|
||||
if not ns:
|
||||
raise XmlParseException("'ns' attribute must be set in order to use 'clear_params'")
|
||||
ros_config.add_clear_param(child_ns.ns)
|
||||
return child_ns
|
||||
|
||||
@ifunless
|
||||
def _launch_tag(self, tag, ros_config, filename=None):
|
||||
# #2499
|
||||
deprecated = tag.getAttribute('deprecated')
|
||||
if deprecated:
|
||||
if filename:
|
||||
ros_config.add_config_error("[%s] DEPRECATED: %s"%(filename, deprecated))
|
||||
else:
|
||||
ros_config.add_config_error("Deprecation Warning: "+deprecated)
|
||||
|
||||
INCLUDE_ATTRS = ('file', NS, CLEAR_PARAMS)
|
||||
@ifunless
|
||||
def _include_tag(self, tag, context, ros_config, default_machine, is_core, verbose):
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.INCLUDE_ATTRS)
|
||||
inc_filename = self.resolve_args(tag.attributes['file'].value, context)
|
||||
|
||||
child_ns = self._ns_clear_params_attr(tag.tagName, tag, context, ros_config, include_filename=inc_filename)
|
||||
|
||||
for t in [c for c in tag.childNodes if c.nodeType == DomNode.ELEMENT_NODE]:
|
||||
tag_name = t.tagName.lower()
|
||||
if tag_name == 'env':
|
||||
self._env_tag(t, child_ns, ros_config)
|
||||
elif tag_name == 'arg':
|
||||
self._arg_tag(t, child_ns, ros_config, verbose=verbose)
|
||||
else:
|
||||
print >> sys.stderr, \
|
||||
"WARN: unrecognized '%s' tag in <%s> tag"%(t.tagName, tag.tagName)
|
||||
|
||||
# setup arg passing
|
||||
roslaunch.loader.process_include_args(child_ns)
|
||||
|
||||
try:
|
||||
launch = self._parse_launch(inc_filename, verbose=verbose)
|
||||
self._launch_tag(launch, ros_config, filename=inc_filename)
|
||||
default_machine = \
|
||||
self._recurse_load(ros_config, launch.childNodes, child_ns, \
|
||||
default_machine, is_core, verbose)
|
||||
|
||||
# check for unused args
|
||||
roslaunch.loader.post_process_include_args(child_ns)
|
||||
|
||||
except ArgException, e:
|
||||
raise XmlParseException("included file [%s] requires the '%s' arg to be set"%(inc_filename, str(e)))
|
||||
except XmlParseException, e:
|
||||
raise XmlParseException("while processing %s:\n%s"%(inc_filename, str(e)))
|
||||
if verbose:
|
||||
print "... done importing include file [%s]"%inc_filename
|
||||
return default_machine
|
||||
|
||||
GROUP_ATTRS = (NS, CLEAR_PARAMS)
|
||||
def _recurse_load(self, ros_config, tags, context, default_machine, is_core, verbose):
|
||||
"""
|
||||
@return: new default machine for current context
|
||||
@rtype: L{Machine}
|
||||
"""
|
||||
for tag in [t for t in tags if t.nodeType == DomNode.ELEMENT_NODE]:
|
||||
name = tag.tagName
|
||||
if name == 'group':
|
||||
if ifunless_test(self, tag, context):
|
||||
self._check_attrs(tag, context, ros_config, XmlLoader.GROUP_ATTRS)
|
||||
child_ns = self._ns_clear_params_attr(name, tag, context, ros_config)
|
||||
default_machine = \
|
||||
self._recurse_load(ros_config, tag.childNodes, child_ns, \
|
||||
default_machine, is_core, verbose)
|
||||
elif name == 'node':
|
||||
# clone the context so that nodes' env does not pollute global env
|
||||
n = self._node_tag(tag, context.child(''), ros_config, default_machine, verbose=verbose)
|
||||
if n is not None:
|
||||
ros_config.add_node(n, core=is_core, verbose=verbose)
|
||||
elif name == 'test':
|
||||
# clone the context so that nodes' env does not pollute global env
|
||||
t = self._node_tag(tag, context.child(''), ros_config, default_machine, is_test=True, verbose=verbose)
|
||||
if t is not None:
|
||||
ros_config.add_test(t, verbose=verbose)
|
||||
elif name == 'param':
|
||||
self._param_tag(tag, context, ros_config, verbose=verbose)
|
||||
elif name == 'remap':
|
||||
try:
|
||||
r = self._remap_tag(tag, context, ros_config)
|
||||
if r is not None:
|
||||
context.add_remap(r)
|
||||
except RLException, e:
|
||||
raise XmlParseException("Invalid <remap> tag: %s.\nXML is %s"%(str(e), tag.toxml()))
|
||||
elif name == 'machine':
|
||||
val = self._machine_tag(tag, context, ros_config, verbose=verbose)
|
||||
if val is not None:
|
||||
(m, is_default) = val
|
||||
if is_default:
|
||||
default_machine = m
|
||||
ros_config.add_machine(m, verbose=verbose)
|
||||
elif name == 'rosparam':
|
||||
self._rosparam_tag(tag, context, ros_config, verbose=verbose)
|
||||
elif name == 'master':
|
||||
pass #handled non-recursively
|
||||
elif name == 'include':
|
||||
val = self._include_tag(tag, context, ros_config, default_machine, is_core, verbose)
|
||||
if val is not None:
|
||||
default_machine = val
|
||||
elif name == 'env':
|
||||
self._env_tag(tag, context, ros_config)
|
||||
elif name == 'arg':
|
||||
self._arg_tag(tag, context, ros_config, verbose=verbose)
|
||||
else:
|
||||
ros_config.add_config_error("unrecognized tag "+tag.tagName)
|
||||
return default_machine
|
||||
|
||||
def _load_launch(self, launch, ros_config, is_core=False, filename=None, argv=None, verbose=True):
|
||||
"""
|
||||
subroutine of launch for loading XML DOM into config. Load_launch assumes that it is
|
||||
creating the root XmlContext, and is thus affected by command-line arguments.
|
||||
@param launch: DOM node of the root <launch> tag in the file
|
||||
@type launch: L{Node}
|
||||
@param ros_config: launch configuration to load XML file into
|
||||
@type ros_config: L{ROSLaunchConfig}
|
||||
@param is_core: (optional) if True, load file using ROS core rules. Default False.
|
||||
@type is_core: bool
|
||||
@param filename: (optional) name of file being loaded
|
||||
@type filename: str
|
||||
@param verbose: (optional) print verbose output. Default False.
|
||||
@type verbose: bool
|
||||
@param argv: (optional) command-line args. Default sys.argv.
|
||||
"""
|
||||
# The <master> tag is special as we only only process a single
|
||||
# tag in the top-level file. We ignore master tags in
|
||||
# included files.
|
||||
|
||||
if argv is None:
|
||||
argv = sys.argv
|
||||
|
||||
self._launch_tag(launch, ros_config, filename)
|
||||
master_tags = launch.getElementsByTagName('master')
|
||||
self.root_context = roslaunch.loader.LoaderContext('', filename)
|
||||
roslaunch.loader.load_sysargs_into_context(self.root_context, argv)
|
||||
|
||||
#TODO: need to warn user about unused parameters
|
||||
|
||||
if len(master_tags) > 1:
|
||||
raise XmlParseException("multiple <master> tags in top-level xml file not allowed")
|
||||
elif len(master_tags) == 1:
|
||||
ros_config.set_master(self._master_tag(master_tags[0], self.root_context, ros_config))
|
||||
self._recurse_load(ros_config, launch.childNodes, self.root_context, None, is_core, verbose)
|
||||
|
||||
def _parse_launch(self, filename, verbose):
|
||||
try:
|
||||
if verbose:
|
||||
print "... loading XML file [%s]"%filename
|
||||
root = parse(filename).getElementsByTagName('launch')
|
||||
except Exception, e:
|
||||
raise XmlParseException("Invalid roslaunch XML syntax: %s"%e)
|
||||
if len(root) != 1:
|
||||
raise XmlParseException("Invalid roslaunch XML syntax: no root <launch> tag")
|
||||
return root[0]
|
||||
|
||||
def load(self, filename, ros_config, core=False, argv=None, verbose=True):
|
||||
"""
|
||||
load XML file into launch configuration
|
||||
@param filename: XML config file to load
|
||||
@type filename: str
|
||||
@param ros_config: launch configuration to load XML file into
|
||||
@type ros_config: L{ROSLaunchConfig}
|
||||
@param core: if True, load file using ROS core rules
|
||||
@type core: bool
|
||||
@param argv: override command-line arguments (mainly for arg testing)
|
||||
@type argv: [str]
|
||||
"""
|
||||
try:
|
||||
launch = self._parse_launch(filename, verbose)
|
||||
self._load_launch(launch, ros_config, is_core=core, filename=filename, argv=argv, verbose=verbose)
|
||||
except ArgException, e:
|
||||
raise XmlParseException("[%s] requires the '%s' arg to be set"%(filename, str(e)))
|
||||
except SubstitutionException, e:
|
||||
raise XmlParseException(str(e))
|
||||
|
||||
def load_string(self, xml_text, ros_config, core=False, verbose=True):
|
||||
"""
|
||||
Load XML text into launch configuration
|
||||
@param xml_text: XML configuration
|
||||
@type xml_text: str
|
||||
@param ros_config: launch configuration to load XML file into
|
||||
@type ros_config: L{ROSLaunchConfig}
|
||||
@param core: if True, load file using ROS core rules
|
||||
@type core: bool
|
||||
"""
|
||||
try:
|
||||
if verbose:
|
||||
print "... loading XML"
|
||||
root = parseString(xml_text).getElementsByTagName('launch')
|
||||
except Exception, e:
|
||||
import traceback
|
||||
import logging
|
||||
logging.getLogger('roslaunch').error("Invalid roslaunch XML syntax:\nstring[%s]\ntraceback[%s]"%(xml_text, traceback.format_exc()))
|
||||
raise XmlParseException("Invalid roslaunch XML syntax: %s"%e)
|
||||
|
||||
if len(root) != 1:
|
||||
raise XmlParseException("Invalid roslaunch XML syntax: no root <launch> tag")
|
||||
self._load_launch(root[0], ros_config, core, filename='string', verbose=verbose)
|
Loading…
Reference in New Issue