def for_container( cls, container: str, config: 'Config', ) -> 'Observer': """Constructs an Observer for a given running container. Parameters ---------- container: str The image id or name of a container running a ROS system. config: Config A description of the configuration used by the running container. Returns ------- Observer An observer that is appropriate for the kind of ROS system that is running in the container. """ rsw = roswire.ROSWire() app = rsw.app(config.image, config.sources) instance = app.attach(container, require_description=True) observer = cls._build_observer(app, config, instance) return observer
def main() -> None: args = parse_args() logger = logging.getLogger() logger.setLevel(logging.DEBUG) fh = logging.FileHandler(filename=args.log_fn) format_str = "%(asctime)s:%(levelname)s:%(name)s: %(message)s" date_str = '%m/%d/%Y %I:%M:%S %p' fh_formatter = logging.Formatter(fmt=format_str, datefmt=date_str) fh.setFormatter(fh_formatter) logger.addHandler(fh) #logging.basicConfig(filename=args.log_fn, level=logging.DEBUG, # format=format_str, datefmt=date_str) # TODO: # add boilerplate python default logging or use loguru to attach to the correct #logger.remove() #logger.enable('roswire') #logger.add(args.log_fn, level='INFO', format="{time:MM/DD/YYYY HH:mm:ss}:{level}:{name} {message}") rsw = roswire.ROSWire() docker_image = get_docker_image(args) mutations = get_mutations(args) missions = [convert_mission(fn) for fn in args.mission_files] cursor, conn = access_bag_db(args.db_fn) home = dict((('lat', args.home_lat), ('long', args.home_long), ('alt', args.home_alt))) run_experiments(rsw, docker_image, mutations, args.mission_files, args.mutate, args.context, args.baseline_iterations, cursor, conn, home, args.use_dronekit, args.use_mavproxy) conn.close()
def for_config(cls, config: Config) -> Iterator['Interpreter']: """Constructs an interpreter for a given configuration""" rsw = roswire.ROSWire() # TODO don't maintain multiple instances with rsw.launch(config.image, config.sources, environment=config.environment) as app: with Interpreter(config, app) as interpreter: yield interpreter
def __attrs_post_init__(self) -> None: object.__setattr__(self, 'sources', tuple(self.sources)) object.__setattr__(self, 'launches', tuple(self.launches)) environment = MappingProxyType(dict(self.environment)) object.__setattr__(self, 'environment', environment) # TODO allow this context to be passed in rsw = roswire.ROSWire() app = roswire.App(roswire=rsw, image=self.image, sources=self.sources) object.__setattr__(self, 'app', app)
def main(): # setup logging log_to_stdout = logging.StreamHandler() log_to_stdout.setLevel(logging.DEBUG) logging.getLogger('roswire').addHandler(log_to_stdout) rsw = roswire.ROSWire() # builds a description of the ROS application desc = rsw.descriptions.load(NAME_IMAGE) db_type = desc.types db_fmt = desc.formats print(desc) # launch a container for the ROS application with rsw.launch(NAME_IMAGE) as sut: # do some fun things with the file system # sut.files.read('/foo/bar') # sut.files.write('/foo/bar', 'blah') # optionally, build via catkin catkin = sut.catkin(DIR_ROS_WS) # catkin.clean() catkin.build() # launch the ROS master inside the container with sut.roscore() as roscore: # start ArduPilot SITL cmd = \ '/ros_ws/src/ArduPilot/build/sitl/bin/arducopter --model copter' sut.shell.non_blocking_execute(cmd) # launch MAVROS and connect to SITL roscore.launch('/ros_ws/src/mavros/mavros/launch/apm.launch', args={'fcu_url': 'tcp://127.0.0.1:5760@5760'}) time.sleep(10) # check that /mavros exists assert '/mavros' in roscore.nodes # import message type from mavros SetModeRequest = db_type['mavros_msgs/SetModeRequest'] message = SetModeRequest(base_mode=64, custom_mode='') response = roscore.services['/mavros/set_mode'].call(message) assert response.response # let's record to a rosbag! with roscore.record('some_local_path') as recorder: time.sleep(10)
def _app(name: str) -> roswire.App: rsw = roswire.ROSWire() filepath = os.path.join(DIR_HERE, "apps", f"{name}.yml") # ensure that the image for the app has been downloaded docker_client = docker.from_env() with open(filepath, "r") as f: contents = yaml.safe_load(f) image: str = contents["image"] try: docker_client.images.get(image) except docker.errors.ImageNotFound: logger.debug(f"downloading Docker image for testing: {image}") docker_client.images.pull(image) logger.debug(f"downloaded Docker image for testing: {image}") return rsw.load(filepath)
def main() -> None: args = parse_args() logger = logging.getLogger() logger.setLevel(logging.DEBUG) fh = logging.FileHandler(filename=args.log_fn) ch = logging.StreamHandler() format_str = "%(asctime)s:%(levelname)s:%(name)s: %(message)s" date_str = "%m/%d/%Y %I:%M%S %p" fh_formatter = logging.Formatter(fmt=format_str, datefmt=date_str) fh.setFormatter(fh_formatter) ch.setFormatter(fh_formatter) logger.addHandler(ch) logger.addHandler(fh) # Set up the bag database cursor, conn = access_bag_db(args.db_fn) if not args.rosrunner_yaml_dir: rosrunner_yaml_fns = args.rosrunner_yaml else: all_dir_fns = os.listdir(args.rosrunner_yaml_dir) rosrunner_yaml_fns = [ os.path.join(args.rosrunner_yaml_dir, x) for x in all_dir_fns if x.endswith(".yaml") or x.endswith(".yml")] print(rosrunner_yaml_fns) num_param_fns = len(rosrunner_yaml_fns) for param_fn, index in zip(rosrunner_yaml_fns, range(1, num_param_fns + 1)): logger.info(f"Param_fn: {param_fn} ({index}/{num_param_fns})") # Warm up the docker image rsw = roswire.ROSWire() docker_image = get_from_yaml(param_fn, "image") sources = get_from_yaml(param_fn, "sources") logging.debug(f"Image: {docker_image}") logging.debug(f"Sources: {sources}") param_fn_sha = file_hash(param_fn) # Run the image with ROSRunner run_experiments(cursor=cursor, conn=conn, param_fn=param_fn, docker_image=docker_image, sources=sources, topic_regex=args.topic_regex, num_iter=args.baseline_iterations, delay_fn=param_fn, delay_sha=param_fn_sha)
def for_image( cls, config: 'Config', start_script: t.Optional[str] = None) -> t.Iterator['Observer']: """Constructs an observer by starting an instance of an image Parameters ---------- config: Config A description of the configuration used by the running container. Will contain the image name, sources, and environment variables to run start_script: str An optional script (on the container) to run after instance cretion Returns ------- Observer An observer that is appropriate for the kind of ROS system that is running in the container. """ rsw = roswire.ROSWire() app = rsw.app(config.image, config.sources) with app.launch(environment=config.environment) as instance: observer = cls._build_observer(app, config, instance) script: t.Optional[Popen] = None try: if start_script: logger.debug("Starting the container") cmd = start_script script = instance.shell.popen(cmd) time.sleep(5) if script.returncode and script.returncode != 1: for line in script.stream: logger.error(line) raise ExecutionError("Could not run start script") yield observer finally: if start_script and script: script.terminate()
def run_experiments(*, cursor, conn, param_fn: str, docker_image, sources, topic_regex, num_iter=1, delay_fn: str="None", delay_sha: str="None"): rsw = roswire.ROSWire() description = rsw.descriptions.load_or_build(docker_image, sources) docker_image_sha = description.sha256 # Note: this assumes that the mission file is the first file copied # to the container mission_fn = get_from_yaml(param_fn, "files")[0]["host"] mission_sha = file_hash(mission_fn) for i in range(num_iter): bag_fn = f"{get_bag_fn()}.bag" run_one_experiment(sources, cursor, conn, outbag=bag_fn, docker_image=docker_image, docker_image_sha=docker_image_sha, param_fn=param_fn, mission_sha=mission_sha, mission_fn=mission_fn, topic_regex=topic_regex, delay_fn=delay_fn, delay_sha=delay_sha)
import time from loguru import logger import roswire # enable logging logger.enable('roswire') # first, we create a new ROSWire session rsw = roswire.ROSWire() # we then launch a container for a given robot. # once the end of the given context is reached, including the event where an # exception occurs, the container will be automatically destroyed. image = 'therobotcooperative/turtlebot3' sources = ['/opt/ros/kinetic/setup.bash', '/ros_ws/devel/setup.bash'] environment = {'TURTLEBOT3_MODEL': 'burger'} with rsw.launch(image, sources, environment=environment) as system: # we then launch ROS inside the container # again, once the end of the context is reached, ROS is killed. with system.roscore() as ros: # let's bring up the application ros.roslaunch('turtlebot3_house.launch', package='turtlebot3_gazebo', args={'gui': 'false'}) # we need to wait for the nodes to finish their initialisation time.sleep(30)
def test_description(): NAME_IMAGE = "hello-world" rsw = roswire.ROSWire() desc = rsw.descriptions.build(NAME_IMAGE, save=False) assert set(desc.packages) == { "nodelet_core", "ros_core", "ros_comm", "ros_base", "ros_tutorials", "common_tutorials", "roscpp_core", "bond_core", "ros", "common_msgs", "actionlib", "actionlib_msgs", "actionlib_tutorials", "angles", "bond", "bondcpp", "bondpy", "catkin", "class_loader", "cmake_modules", "cpp_common", "diagnostic_msgs", "dynamic_reconfigure", "gencpp", "genlisp", "genmsg", "genpy", "geometry_msgs", "message_filters", "message_generation", "message_runtime", "mk", "nav_msgs", "nodelet", "nodelet_topic_tools", "nodelet_tutorial_math", "pluginlib", "pluginlib_tutorials", "rosbag", "rosbag_migration_rule", "rosbag_storage", "rosbash", "rosboost_cfg", "rosbuild", "rosclean", "rosconsole", "rosconsole_bridge", "roscpp", "roscpp_serialization", "roscpp_traits", "roscpp_tutorials", "roscreate", "rosgraph", "rosgraph_msgs", "roslang", "roslaunch", "roslib", "roslisp", "roslz4", "rosmake", "rosmaster", "rosmsg", "rosnode", "rosout", "rospack", "rosparam", "rospy", "rospy_tutorials", "rosservice", "rostest", "rostime", "rostopic", "rosunit", "roswtf", "sensor_msgs", "shape_msgs", "smclib", "std_msgs", "std_srvs", "stereo_msgs", "topic_tools", "trajectory_msgs", "turtle_actionlib", "turtlesim", "visualization_msgs", "xmlrpcpp", }