diff --git a/backend/CMakeLists.txt b/backend/CMakeLists.txt index 7d402c911..8f70496f6 100644 --- a/backend/CMakeLists.txt +++ b/backend/CMakeLists.txt @@ -125,22 +125,6 @@ install(TARGETS simulation_runner ARCHIVE DESTINATION lib ) -# ---------------------------------------- -# Automotive demo -# -add_executable(automotive-demo - automotive_demo.cc - system.h -) - -target_link_libraries(automotive-demo - simulation_runner - automotive_simulator - ${drake_LIBRARIES} -) - -install(TARGETS automotive-demo RUNTIME DESTINATION bin) - delphyne_install_includes( ${PROJECT_NAME}${PROJECT_MAJOR_VERSION}/${PROJECT_NAME}/backend system.h diff --git a/backend/automotive_demo.cc b/backend/automotive_demo.cc deleted file mode 100644 index 7908b8f8a..000000000 --- a/backend/automotive_demo.cc +++ /dev/null @@ -1,186 +0,0 @@ -// Copyright 2017 Toyota Research Institute - -#include -#include -#include - -#include "backend/automotive_simulator.h" -#include "backend/road_builder.h" -#include "backend/simulation_runner.h" - -#include -#include -#include -#include -#include - -namespace delphyne { -namespace { - -drake::automotive::Curve2 MakeCurve(double radius, double inset) { - // TODO(jwnimmer-tri) This function will be rewritten once we have - // proper splines. Don't try too hard to understand it. Run the - // demo to see it first, and only then try to understand the code. - - typedef drake::automotive::Curve2::Point2 Point2d; - std::vector waypoints; - - // Start (0, +i). - // Straight right to (+r, +i). - // Loop around (+i, +r). - // Straight back to (+i, 0). - waypoints.push_back({0.0, inset}); - for (int theta_deg = -90; theta_deg <= 180; ++theta_deg) { - const Point2d center{radius, radius}; - const double theta = theta_deg * M_PI / 180.0; - const Point2d direction{std::cos(theta), std::sin(theta)}; - waypoints.push_back(center + (direction * (radius - inset))); - } - waypoints.push_back({inset, 0.0}); - - // Start (+i, 0). - // Straight down to (+i, -r). - // Loop around (-r, +i). - // Straight back to start (implicitly via segment to waypoints[0]). - for (int theta_deg = 0; theta_deg >= -270; --theta_deg) { - const Point2d center{-radius, -radius}; - const double theta = theta_deg * M_PI / 180.0; - const Point2d direction{std::cos(theta), std::sin(theta)}; - waypoints.push_back(center + (direction * (radius + inset))); - } - - // Many copies. - const int kNumCopies = 100; - std::vector looped_waypoints; - for (int copies = 0; copies < kNumCopies; ++copies) { - std::copy(waypoints.begin(), waypoints.end(), - std::back_inserter(looped_waypoints)); - } - looped_waypoints.push_back(waypoints.front()); - - return drake::automotive::Curve2(looped_waypoints); -} - -std::tuple, double, double> -CreateTrajectoryParams(int index) { - // The possible curves to trace (lanes). - static const std::vector> curves{ - MakeCurve(40.0, 0.0), // BR - MakeCurve(40.0, 4.0), // BR - MakeCurve(40.0, 8.0), - }; - - // Magic car placement to make a good visual demo. - const auto& curve = curves[index % curves.size()]; - const double start_time = (index / curves.size()) * 0.8; - const double kSpeed = 2.0; - return std::make_tuple(curve, kSpeed, start_time); -} - -// The distance between the coordinates of consecutive rows of railcars and -// other controlled cars (e.g. MOBIL) on a dragway. 5 m ensures a gap between -// consecutive rows of Prius vehicles. It was empirically chosen. -constexpr double kRailcarRowSpacing{5}; -constexpr double kControlledCarRowSpacing{5}; - -const drake::maliput::api::RoadGeometry* AddDragway( - delphyne::AutomotiveSimulator* simulator) { - const double kMaximumHeight = 5.0; // meters - const int kNumDragwayLanes = 3; - const double kDragwayLength = 100.0; // meters - const double kDragwayLaneWidth = 3.7; // meters - const double kDragwayShoulderWidth = 3.0; // meters - - auto road_builder = - std::make_unique>(simulator); - return road_builder->AddDragway("Automotive Demo Dragway", kNumDragwayLanes, - kDragwayLength, kDragwayLaneWidth, - kDragwayShoulderWidth, kMaximumHeight); -} - -int main(int argc, char* argv[]) { - // Instantiates a simulator. - auto simulator = std::make_unique>(); - - // Adds a Loadable Prius Simple car. - auto state2 = std::make_unique>(); - state2->set_y(4.0); - std::map simple_params; - if (simulator->AddLoadableAgent("simple-car", simple_params, "1", - std::move(state2)) < 0) { - return 1; - } - - // Add a Loadable Prius Trajectory Car. - const auto& params = CreateTrajectoryParams(0); - std::map traj_params; - traj_params["curve"] = std::get<0>(params); - auto state3 = - std::make_unique>(); - state3->set_speed(std::get<1>(params)); - state3->set_position(std::get<2>(params)); - if (simulator->AddLoadableAgent("trajectory-car", traj_params, - "TrajectoryCar0", std::move(state3)) < 0) { - return 1; - } - - // Add a Loadable MOBIL Simple Car - auto road_geometry = AddDragway(simulator.get()); - const drake::maliput::dragway::RoadGeometry* dragway_road_geometry = - dynamic_cast(road_geometry); - - auto state4 = std::make_unique>(); - - const int lane_index = 0; - const int row = 0; - const double x_offset = kControlledCarRowSpacing * row; - const drake::maliput::api::Lane* lane = - dragway_road_geometry->junction(0)->segment(0)->lane(lane_index); - if (x_offset >= lane->length()) { - throw std::runtime_error( - "Ran out of lane length to add new MOBIL-controlled SimpleCars."); - } - const double y_offset = lane->ToGeoPosition({0., 0., 0.}).y(); - state4->set_x(x_offset); - state4->set_y(y_offset); - std::map mobil_params; - mobil_params["road"] = road_geometry; - mobil_params["initial_with_s"] = true; - if (simulator->AddLoadableAgent("mobil-car", mobil_params, "MOBIL0", - std::move(state4)) < 0) { - return 1; - } - - // Add a loadable Maliput Railcar - auto state5 = - std::make_unique>(); - drake::automotive::LaneDirection lane_direction(lane); - drake::automotive::MaliputRailcarParams start_params; - start_params.set_r(0); - start_params.set_h(0); - std::map maliput_params; - maliput_params["road"] = road_geometry; - maliput_params["lane_direction"] = &lane_direction; - maliput_params["start_params"] = &start_params; - state5->set_s(0.0); - state5->set_speed(1.0); - maliput_params["initial_with_s"] = true; - if (simulator->AddLoadableAgent("rail-car", maliput_params, "Maliput0", - std::move(state5)) < 0) { - return 1; - } - - // Instantiates the simulator runner and starts it. - const double kTimeStep = 0.001; - delphyne::SimulatorRunner prius_sim_runner(std::move(simulator), kTimeStep); - prius_sim_runner.Start(); - - // Zzzzzz. - delphyne::WaitForShutdown(); - return 0; -} - -} // namespace -} // namespace delphyne - -int main(int argc, char* argv[]) { return delphyne::main(argc, argv); } diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index fad36970f..e7a7eec1c 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -16,9 +16,8 @@ install( install( PROGRAMS - examples/demo_launcher.py + examples/all_cars_in_dragway.py examples/keyboard_controlled_simulation.py - examples/loadable_agent_simulation.py examples/railcar_in_multilane.py examples/realtime_rate_changer.py examples/road_loading.py diff --git a/python/delphyne/simulation_utils.py b/python/delphyne/simulation_utils.py index f5167c5a0..7674d687d 100644 --- a/python/delphyne/simulation_utils.py +++ b/python/delphyne/simulation_utils.py @@ -13,10 +13,14 @@ from contextlib import contextmanager from delphyne.bindings import ( - AutomotiveSimulator + Any, + AutomotiveSimulator, + MaliputRailcarParams, + MaliputRailcarState ) from delphyne.launcher import Launcher from pydrake.automotive import ( + LaneDirection, SimpleCarState ) @@ -69,11 +73,7 @@ def build_simple_car_simulator(initial_positions=None): simulator = AutomotiveSimulator() car_id = 0 for car_position in initial_positions: - state = SimpleCarState() - state.set_y(car_position[0]) - state.set_x(car_position[1]) - simulator.AddLoadableAgent("simple-car", {}, str(car_id), state) - + add_simple_car(simulator, car_id, car_position[1], car_position[0]) car_id += 1 return simulator @@ -102,3 +102,60 @@ def launch_visualizer(launcher, layout_filename): layout_path = os.path.join(get_delphyne_resource_root(), layout_filename) teleop_config = layout_key + layout_path launcher.launch([ign_visualizer, teleop_config]) + + +def add_simple_car(simulator, robot_id, position_x=0, position_y=0): + """Instantiates a new Simple Prius Car + and adds it to the simulation. + """ + # Creates the initial car state for the simple car. + simple_car_state = SimpleCarState() + simple_car_state.set_x(position_x) + simple_car_state.set_y(position_y) + # Instantiates a Loadable Simple Car + simulator.AddLoadableAgent( + "simple-car", {}, str(robot_id), simple_car_state) + + +def add_mobil_car(simulator, robot_id, road, position_x=0, position_y=0): + """Instantiates a new MOBIL Car and adds + it to the simulation. + """ + # Creates the initial car state for the MOBIL car. + mobil_car_state = SimpleCarState() + mobil_car_state.set_x(position_x) + mobil_car_state.set_y(position_y) + mobil_params = { + "initial_with_s": Any(True), + "road": Any(road) + } + # Instantiates a Loadable MOBIL Car. + simulator.AddLoadableAgent( + "mobil-car", mobil_params, str(robot_id), mobil_car_state) + + +def add_maliput_railcar(simulator, robot_id, road, s_coordinate=0, speed=0): + """Instantiates a new Maliput Railcar and adds + it to the simulation. + """ + # Defines the lane that will be used by the dragway car. + lane = road.junction(0).segment(0).lane(1) + # Creates the initial car state for the Railcar. + maliput_car_state = MaliputRailcarState() + maliput_car_state.s = s_coordinate + maliput_car_state.speed = speed + lane_direction = LaneDirection(lane, True) + start_params = MaliputRailcarParams() + start_params.r = 0 + start_params.h = 0 + railcar_params = { + "road": Any(road), + "initial_with_s": Any(True), + "lane_direction": Any(lane_direction), + "start_params": Any(start_params) + } + # Instantiates a Loadable Rail Car. + simulator.AddLoadableAgent("rail-car", + railcar_params, + str(robot_id), + maliput_car_state) diff --git a/python/examples/README.md b/python/examples/README.md index ddcd47b2e..7452abcb9 100644 --- a/python/examples/README.md +++ b/python/examples/README.md @@ -4,45 +4,44 @@ These examples are intended to demonstrate how to use the python bindings of the simulation runner. For all the examples below it's assumed that the Delphyne backend was successfully -built with CMake, as shown in the instructions -[here](https://github.com/ToyotaResearchInstitute/delphyne-gui/blob/master/README.md). -

road_loading

+built with CMake, as shown in the [Delphyne Guide](https://docs.google.com/document/d/1tQ9vDp084pMuHjYmtScLB3F1tdr4iP9w7_OTcoSM1zQ). +

all_cars_in_dragway

-This example shows how to run a simulation that includes a road. For the -time being three road examples are supported: dragway, onramp, monolane and -multilane. -This demo uses the subcommand style, where each road type can handle different -parameters (to list the available arguments just do -`$ road_loading -h`). Below are some examples of usage: +This demo consists of a suite of dynamically loaded cars, +running simultaneously on a dragway road. +For the time being, three cars are supported: + - A Prius Simple Car. + - A MOBIL Simple Car. + - A MaliputRailCar. +

keyboard_controlled_simulation

-A dragway that is 200 meters long and has a side-shoulder of 2.5 meters: + +This example shows how to use the keyboard events to control the advance of +a simulation. The simulation will open the usual simple car in the center of +the scene, which can be driven using the keyboard on the GUI's teleop widget. +However, by switching to the console, we can `play`/`pause`/`step`/`quit` the +simulation. ``` -$ road_loading.py dragway --length=200 --shoulder-width=2.5 +$ cd /install/bin +$ ./keyboard_controlled_simulation.py ``` -An on-ramp road: + The supported keys for the demo: -``` -$ road_loading.py onramp -``` +<`p`> will pause the simulation if running and vice-versa. -Load a monolane file: +<`s`> will step the simulation once if paused. -``` -$ road_loading.py monolane ---filename='./install/share/delphyne/road_samples/double_ring.yaml' -``` +<`q`> will stop the simulation and quit the demo. -Load a multilane file: +

railcar_in_multilane

-``` -$ road_loading.py multilane ---filename='./install/share/delphyne/road_samples/multilane_sample.yaml' -``` +An example of a couple of railcars running around in a closed-loop maliput +road.

realtime_rate_changer

@@ -62,27 +61,43 @@ in real-time). Once the scripts starts running it will cycle between a real-time rate of `0.6` to `1.6` to depict how dynamic real-time rate impacts on the simulation. -

keyboard_controlled_simulation

+

road_loading

-This example shows how to use the keyboard events to control the advance of -a simulation. The simulation will open the usual simple car in the center of -the scene, which can be driven using the keyboard on the GUI's teleop widget. -However, by switching to the console, we can `play`/`pause`/`step`/`quit` the -simulation. +This example shows how to run a simulation that includes a road. For the +time being three road examples are supported: dragway, onramp, monolane and +multilane. +This demo uses the subcommand style, where each road type can handle different +parameters (to list the available arguments just do +`$ road_loading -h`). Below are some examples of usage: + + +A dragway that is 200 meters long and has a side-shoulder of 2.5 meters: ``` -$ cd /install/bin -$ ./keyboard_controlled_simulation.py +$ road_loading.py dragway --length=200 --shoulder-width=2.5 ``` - The supported keys for the demo: +An on-ramp road: -<`p`> will pause the simulation if running and vice-versa. +``` +$ road_loading.py onramp +``` -<`s`> will step the simulation once if paused. +Load a monolane file: + +``` +$ road_loading.py monolane +--filename='./install/share/delphyne/road_samples/double_ring.yaml' +``` + +Load a multilane file: + +``` +$ road_loading.py multilane +--filename='./install/share/delphyne/road_samples/multilane_sample.yaml' +``` -<`q`> will stop the simulation and quit the demo.

simple_python_binding

@@ -123,36 +138,6 @@ $ ./ign service --service /world_control --reqtype ignition.msgs.WorldControl -- ``` -

loadable_agent_simulation

- - -This example shows how to run a simulation that dynamically loads a car agent. -For the time being two car types are supported: - - -- simple, which just places a `LoadablePriusSimpleCarDouble` in an empty world. -- mobil, which places a `LoadableMobilControlledSimpleCarDouble` at the start -of a 100 meters dragway. -- railcar, which places a `LoadableMaliputRailCar` in the center lane of a -three-lane dragway. - - -These examples can be executed by doing: - -``` -$ loadable_agent_simulation.py --type="simple" -``` - -``` -$ loadable_agent_simulation.py --type="mobil" - -``` -``` -$ loadable_agent_simulation.py --type="railcar" - -``` - -

time_bounded_simulation

@@ -168,9 +153,3 @@ seconds): $ time_bounded_simulation.py --realtime_rate=2.0 --duration=30.0 ``` -

railcar_in_multilane

- - -An example of a couple of railcars running around in a closed-loop maliput -road. - diff --git a/python/examples/all_cars_in_dragway.py b/python/examples/all_cars_in_dragway.py new file mode 100644 index 000000000..a3befc365 --- /dev/null +++ b/python/examples/all_cars_in_dragway.py @@ -0,0 +1,74 @@ +#!/usr/bin/env python2.7 +# +# Copyright 2017 Toyota Research Institute +# + +""" +This demo consists of a suite of dynamically loaded cars, +running simultaneously on a dragway road. +For the time being, three cars are supported: + - A Prius Simple Car. + - A MOBIL Simple Car. + - A MaliputRailCar. +""" + +from __future__ import print_function + +from delphyne.bindings import ( + AutomotiveSimulator, + RoadBuilder, + SimulatorRunner +) +from delphyne.simulation_utils import ( + add_simple_car, + add_maliput_railcar, + add_mobil_car, + launch_interactive_simulation +) + +SIMULATION_TIME_STEP_SECS = 0.001 + + +def main(): + """Excercises a simulator loaded with multiple different cars.""" + + simulator = AutomotiveSimulator() + builder = RoadBuilder(simulator) + + # Generates a dragway road. + num_dragway_lanes = 3 + dragway_length = 100.0 # meters + dragway_lane_width = 3.7 # meters + dragway_shoulder_width = 3.0 # meters + maximum_height = 5.0 # meters + dragway = builder.AddDragway("Automotive Demo Dragway", num_dragway_lanes, + dragway_length, dragway_lane_width, + dragway_shoulder_width, maximum_height) + + # Adds the different cars. + simple_car_position_x = 0.0 + simple_car_position_y = 3.7 + car_id = 0 + add_simple_car(simulator, car_id, simple_car_position_x, + simple_car_position_y) + + mobil_car_position_x = 0.0 + mobil_car_position_y = -3.7 + car_id += 1 + add_mobil_car(simulator, car_id, dragway, + mobil_car_position_x, mobil_car_position_y) + + railcar_s = 0.0 + railcar_speed = 3.0 + car_id += 1 + add_maliput_railcar(simulator, car_id, dragway, railcar_s, railcar_speed) + + runner = SimulatorRunner(simulator, SIMULATION_TIME_STEP_SECS) + + # Starts the simulation and runs it indefinitely. + with launch_interactive_simulation(runner): + runner.Start() + + +if __name__ == "__main__": + main() diff --git a/python/examples/demo_launcher.py b/python/examples/demo_launcher.py deleted file mode 100644 index aeb821406..000000000 --- a/python/examples/demo_launcher.py +++ /dev/null @@ -1,64 +0,0 @@ -#!/usr/bin/env python2.7 -# -# Copyright 2017 Toyota Research Institute -# - -"""Launches drake's automotive_demo and delphyne's visualizer. -""" - -from __future__ import print_function - -import argparse -import os -from delphyne.launcher import Launcher -from delphyne.simulation_utils import get_from_env_or_fail - - -def main(): - """Launches drake's automotive_demo and delphyne's visualizer. - Terminates all the processes if one of them is killed. - - Important: Many parts of this file are commented out as we are currently - migrating the demos and not all features are supported. We are leaving - these commented-out lines as a reference for the future. - """ - launcher = Launcher() - parser = argparse.ArgumentParser() - demo_arguments = { - "simple": ["--num_simple_car=1"] - } - - # Optional arguments - parser.add_argument("--demo", default="simple", dest="demo_name", - action="store", choices=demo_arguments.keys(), - help="the specific demo to launch") - - args = parser.parse_args() - - delphyne_resource_root = get_from_env_or_fail('DELPHYNE_RESOURCE_ROOT') - - # Delphyne binaries; these are found through the standard PATH, so - # they are relative - ign_visualizer = "visualizer" - automotive_demo = "automotive-demo" - - try: - if args.demo_name == "simple": - # Load custom layout with two TeleopWidgets - layout_key = "--layout=" - teleop_config = layout_key + os.path.join( - delphyne_resource_root, - "layoutWithTeleop.config") - launcher.launch([ign_visualizer, teleop_config]) - else: - launcher.launch([ign_visualizer]) - - launcher.launch([automotive_demo]) - launcher.wait(float("Inf")) - - finally: - launcher.kill() - - -if __name__ == "__main__": - main() diff --git a/python/examples/loadable_agent_simulation.py b/python/examples/loadable_agent_simulation.py deleted file mode 100644 index d2c6c3360..000000000 --- a/python/examples/loadable_agent_simulation.py +++ /dev/null @@ -1,157 +0,0 @@ -#!/usr/bin/env python2.7 -# -# Copyright 2017 Toyota Research Institute -# - -""" -This example shows how to run a simulation that dynamically loads a car agent. -For the time being two car types are supported: - - -- simple, which just places a `LoadablePriusSimpleCarDouble` in an empty world. -- mobil, which places a `LoadableMobilControlledSimpleCarDouble` at the start -of a 100 meters dragway. -- rail, which places a `LoadableMaliputRailCar` in the center lane of a -three-lane dragway. - - -These examples can be executed by doing: - -``` -$ loadable_agent_simulation.py --type="simple" -``` - -``` -$ loadable_agent_simulation.py --type="mobil" - -``` -``` -$ loadable_agent_simulation.py --type="rail" - -``` - -""" - -from __future__ import print_function - -import argparse - -from delphyne.bindings import ( - Any, - AutomotiveSimulator, - MaliputRailcarState, - MaliputRailcarParams, - RoadBuilder, - SimulatorRunner -) -from delphyne.simulation_utils import ( - launch_interactive_simulation -) -from pydrake.automotive import ( - LaneDirection, - SimpleCarState -) - -SIMULATION_TIME_STEP_SECS = 0.001 - - -def build_demo_dragway(simulator, name): - """Build a demo dragway that has 3 lanes. The dragway is 100 meters long, - each lane is 3.7 meters wide and the shoulder width is 3 meters. Finally, - the maximum allowed height is 5 meters. - """ - builder = RoadBuilder(simulator) - return builder.AddDragway(name, 3, 100.0, 3.7, 3.0, 5.0) - - -def main(): - """ - Parses the command line options and launches the loadable-agent demo based - on the provided configuration. - """ - - car_agent_types = ["simple", "mobil", "rail"] - - parser = argparse.ArgumentParser( - prog="loadable_agent_simulation", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument("-t", "--type", default=car_agent_types[0], - dest="type", - choices=car_agent_types, - help="The type of car agent to load") - - simulator = AutomotiveSimulator() - - args = parser.parse_args() - - if args.type == "simple": - state = SimpleCarState() - state.set_x(0.0) - state.set_y(1.0) - - # Instantiate a LoadablePriusSimpleCar with 0 id and originally - # placed in (0.0, 1.0) - simulator.AddLoadableAgent("simple-car", - {}, - args.type, - state) - - elif args.type == "mobil": - dragway = build_demo_dragway(simulator, "Mobil dragway") - - state = SimpleCarState() - state.set_x(0.0) - state.set_y(-3.7) - - mobil_params = { - "initial_with_s": Any(True), - "road": Any(dragway) - } - - # Instantiate a MobilControlledSimpleCar - # and originally placed in (0.0, -3.7). The road for the car to - # follow is the previously created dragway. - simulator.AddLoadableAgent("mobil-car", - mobil_params, - args.type, - state) - elif args.type == "rail": - dragway = build_demo_dragway(simulator, "Railcar dragway") - - lane = dragway.junction(0).segment(0).lane(1) - - state = MaliputRailcarState() - state.s = 0.0 - state.speed = 3.0 - - lane_direction = LaneDirection(lane, True) - - start_params = MaliputRailcarParams() - start_params.r = 0 - start_params.h = 0 - - railcar_params = { - "road": Any(dragway), - "initial_with_s": Any(True), - "lane_direction": Any(lane_direction), - "start_params": Any(start_params) - } - - # Instantiate a LoadableMaliputRailCar and - # originally placed at the start of the second lane of the dragway - # previously created. The car initial speed is 3 meters per sec. - simulator.AddLoadableAgent("rail-car", - railcar_params, - args.type, - state) - else: - raise RuntimeError("Option {} not recognized".format(args.type)) - - runner = SimulatorRunner(simulator, SIMULATION_TIME_STEP_SECS) - - with launch_interactive_simulation(runner): - runner.Start() - - -if __name__ == "__main__": - main() diff --git a/tools/generate_python_docs.sh b/tools/generate_python_docs.sh index bf4d42444..c89ebe18d 100755 --- a/tools/generate_python_docs.sh +++ b/tools/generate_python_docs.sh @@ -24,7 +24,7 @@ cat ${DELPHYNE_SOURCE_DIR}/tools/python_examples_md_template.in > $PATH_TO_READM cd ${DELPHYNE_SOURCE_DIR}/python/examples # Converts a python module docstring into markdown and appends it to the README. -find . -iname '*.py' -printf '%f\n' | while read file ; do +find . -iname '*.py' -printf '%f\n' | sort -n | while read file ; do module_name=$(echo $file | cut -f 1 -d '.') echo "Processing $module_name" pydocmd simple $module_name >> $PATH_TO_README diff --git a/tools/python_examples_md_template.in b/tools/python_examples_md_template.in index fab503679..1de1f85f7 100644 --- a/tools/python_examples_md_template.in +++ b/tools/python_examples_md_template.in @@ -4,5 +4,4 @@ These examples are intended to demonstrate how to use the python bindings of the simulation runner. For all the examples below it's assumed that the Delphyne backend was successfully -built with CMake, as shown in the instructions -[here](https://github.com/ToyotaResearchInstitute/delphyne-gui/blob/master/README.md). +built with CMake, as shown in the [Delphyne Guide](https://docs.google.com/document/d/1tQ9vDp084pMuHjYmtScLB3F1tdr4iP9w7_OTcoSM1zQ).