From 7111bcdbe799dcef790cc99bf8c38c4241a8a69b Mon Sep 17 00:00:00 2001 From: "Isaac I.Y. Saito" <130s@2000.jukuin.keio.ac.jp> Date: Fri, 28 Apr 2017 22:00:27 -0700 Subject: [PATCH] [ros_bridge][py] Accept a list of custom RTCs to activate (fix #308). This requires the upstream change https://github.com/start-jsk/rtmros_hironx/pull/497 --- nextage_ros_bridge/script/nextage.py | 9 ++++++++- .../src/nextage_ros_bridge/nextage_client.py | 4 ++-- 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/nextage_ros_bridge/script/nextage.py b/nextage_ros_bridge/script/nextage.py index 48a58c22..de8253bc 100755 --- a/nextage_ros_bridge/script/nextage.py +++ b/nextage_ros_bridge/script/nextage.py @@ -50,6 +50,9 @@ ' this script, but can use RTM. To use ROS, do not forget' \ ' to run rosbridge. How to do so? --> http://wiki.ros.org/rtmros_nextage/Tutorials/Operating%20Hiro%2C%20NEXTAGE%20OPEN' +# The default RTCs for Hironx +RTC_LIST = 'seq, sh, fk, el, log' + if __name__ == '__main__': parser = argparse.ArgumentParser(description='hiro command line interpreters') parser.add_argument('--host', help='corba name server hostname') @@ -59,6 +62,8 @@ parser.add_argument('--dio_ver', help="Version of digital I/O. Only users " "whose robot was shipped before Aug 2014 need to " "define this, and the value should be '0.4.2'.") + parser.add_argument('--rtcs', help="RT components to activate. If nothing passed then default value will be used. Example: '{}'".format(RTC_LIST)) + args, unknown = parser.parse_known_args() if args.host: @@ -69,6 +74,8 @@ args.robot = "RobotHardware0" if args.host else "HiroNX(Robot)0" if not args.modelfile: args.modelfile = "/opt/jsk/etc/NEXTAGE/model/main.wrl" if args.host else "" + if not args.rtcs: + args.rtcs = RTC_LIST # support old style format if len(unknown) >= 2: @@ -80,7 +87,7 @@ # them to specifically tell what robot they're using (eg. hiro, nxc). # This is backward compatible so that users can still keep using `nxc`. # See http://code.google.com/p/rtm-ros-robotics/source/detail?r=6926 - robot.init(robotname=args.robot, url=args.modelfile) + robot.init(robotname=args.robot, url=args.modelfile, rtcs=args.rtcs) if args.dio_ver: robot.set_hand_version(args.dio_ver) diff --git a/nextage_ros_bridge/src/nextage_ros_bridge/nextage_client.py b/nextage_ros_bridge/src/nextage_ros_bridge/nextage_client.py index 61a53bb0..87b6bb64 100755 --- a/nextage_ros_bridge/src/nextage_ros_bridge/nextage_client.py +++ b/nextage_ros_bridge/src/nextage_ros_bridge/nextage_client.py @@ -95,7 +95,7 @@ def __init__(self): self.configurator_name = "gazebo(Nextage)" self.set_hand_version(self.HAND_VER_0_5_1) - def init(self, robotname="HiroNX(Robot)0", url=""): + def init(self, robotname="HiroNX(Robot)0", url="", rtcs=None): ''' Calls init from its superclass, which tries to connect RTCManager, looks for ModelLoader, and starts necessary RTC components. Also runs @@ -106,7 +106,7 @@ def init(self, robotname="HiroNX(Robot)0", url=""): @type url: str ''' if not self.use_gazebo: - HIRONX.init(self, robotname=robotname, url=url) + HIRONX.init(self, robotname=robotname, url=url, rtcs=rtcs) def get_hand_version(self): '''