No node with name 'map' error when adding a python codelet to the navsim_navigate application

Hi,

I have been trying to add a python codelet to the default navsim_navigate example without much success.

I am receiving an error that says No node with name ‘map’
Error log:

2020-03-04 10:07:43.249 DEBUG engine/alice/backend/codelet_backend.cpp@287: Starting job for codelet 'navigation.control.control/isaac.planner.DifferentialBaseControl'
2020-03-04 10:07:43.249 DEBUG engine/alice/backend/node_backend.cpp@350: Stopping node 'backend'
2020-03-04 10:07:43.249 DEBUG engine/alice/backend/node_backend.cpp@325: Starting node 'goals.random_walk'
2020-03-04 10:07:43.249 PANIC engine/alice/application.cpp@153: No node with name 'map'
2020-03-04 10:07:43.252 INFO  packages/imu/ImuCorrector.cpp@116: Collecting IMU data to calibrate...
Ticking...
Ticking...
====================================================================================================
|                            Isaac application terminated unexpectedly                             |
====================================================================================================
#01 /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac/engine/pyalice/bindings.so(+0x1d081a) [0x7f8f6b90381a]
#02 google_breakpad::ExceptionHandler::GenerateDump(google_breakpad::ExceptionHandler::CrashContext*) /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac/engine/pyalice/bindings.so(_ZN15google_breakpad16ExceptionHandler12GenerateDumpEPNS0_12CrashContextE+0x3f0) [0x7f8f6b9f3c20]
#03 google_breakpad::ExceptionHandler::SignalHandler(int, siginfo_t*, void*) /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac/engine/pyalice/bindings.so(_ZN15google_breakpad16ExceptionHandler13SignalHandlerEiP9siginfo_tPv+0xc0) [0x7f8f6b9f3f90]
#04 /lib/x86_64-linux-gnu/libc.so.6(+0x3ef20) [0x7f8f6d508f20]
#05 /lib/x86_64-linux-gnu/libc.so.6(gsignal+0xc7) [0x7f8f6d508e97]
#06 /lib/x86_64-linux-gnu/libc.so.6(abort+0x141) [0x7f8f6d50a801]
#07 /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac//packages_x86_64/navigation/libnavigation_module.so(+0x28f31f) [0x7f8f277ff31f]
#08 isaac::navigation::RobotPoseGenerator::initializeLinks() /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac//packages_x86_64/navigation/libnavigation_module.so(_ZN5isaac10navigation18RobotPoseGenerator15initializeLinksEv+0xdd) [0x7f8f27791cbd]
#09 isaac::navigation::RobotPoseGenerator::start() /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac//packages_x86_64/navigation/libnavigation_module.so(_ZN5isaac10navigation18RobotPoseGenerator5startEv+0x3c) [0x7f8f277924ec]
#10 isaac::alice::NodeBackend::startComponents(isaac::alice::Node*) /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac/engine/pyalice/bindings.so(_ZN5isaac5alice11NodeBackend15startComponentsEPNS0_4NodeE+0xdf) [0x7f8f6b90edef]
#11 isaac::alice::NodeBackend::startImmediate(isaac::alice::Node*) /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac/engine/pyalice/bindings.so(_ZN5isaac5alice11NodeBackend14startImmediateEPNS0_4NodeE+0x182) [0x7f8f6b911362]
#12 isaac::alice::NodeBackend::processQueue() /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac/engine/pyalice/bindings.so(_ZN5isaac5alice11NodeBackend12processQueueEv+0xad) [0x7f8f6b91274d]
#13 isaac::alice::NodeBackend::queueMain() /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac/engine/pyalice/bindings.so(_ZN5isaac5alice11NodeBackend9queueMainEv+0x55) [0x7f8f6b912875]
#14 isaac::scheduler::Job::run() /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac/engine/pyalice/bindings.so(_ZN5isaac9scheduler3Job3runEv+0x36) [0x7f8f6b9ac8f6]
#15 isaac::scheduler::ExecutionGroup::BlockingWorker::main(isaac::scheduler::ExecutionGroup*, isaac::scheduler::Job*, bool) /home/user/.cache/bazel/_bazel_user/46c55f1d4122ba1196b277d38b290ad8/execroot/com_nvidia_isaac/bazel-out/k8-opt/bin/apps/navsim/camera_python.runfiles/com_nvidia_isaac/engine/pyalice/bindings.so(_ZN5isaac9scheduler14ExecutionGroup14BlockingWorker4mainEPS1_PNS0_3JobEb+0x19a) [0x7f8f6b878f9a]
#16 /usr/lib/x86_64-linux-gnu/libstdc++.so.6(+0xbd66f) [0x7f8f6977c66f]
#17 /lib/x86_64-linux-gnu/libpthread.so.0(+0x76db) [0x7f8f6d2b26db]
#18 /lib/x86_64-linux-gnu/libc.so.6(clone+0x3f) [0x7f8f6d5eb88f]
====================================================================================================
Minidump written to: /tmp/6bdd3527-b13c-4377-eb61739f-703b6927.dmp
Aborted (core dumped)

Here are my current files:

navsim_navigate.app.json:

{
  "name": "camera_python",
  "modules": [
    "map",
    "viewers",
    "navigation"
  ],
  "graph": {
    "nodes": [
      {
        "name": "camera_python",
        "components": [
          {
            "name": "message_ledger",
            "type": "isaac::alice::MessageLedger"
          },
          {
            "name": "isaac.alice.PyCodelet",
            "type": "isaac::alice::PyCodelet"
          }
        ]
      },
      {
        "name": "simulation",
        "subgraph": "packages/navsim/apps/navsim.subgraph.json"
      },
      {
        "name": "navigation",
        "subgraph": "packages/navigation/apps/differential_base_navigation.subgraph.json"
      },
      {
        "name": "goals",
        "subgraph": "packages/navigation/apps/goal_generators.subgraph.json"
      },
      {
        "name": "camera_viewer",
        "components": [
          {
            "name": "ledger",
            "type": "isaac::alice::MessageLedger"
          },
          {
            "name": "color_viewer",
            "type": "isaac::viewers::ColorCameraViewer"
          },
          {
            "name": "depth_viewer",
            "type": "isaac::viewers::DepthCameraViewer"
          }
        ]
      },
      {
        "name": "behavior_main",
        "components": [
          {
            "name": "NodeGroup",
            "type": "isaac::alice::behaviors::NodeGroup"
          },
          {
            "name": "MemorySequenceBehavior",
            "type": "isaac::alice::behaviors::MemorySequenceBehavior"
          }
        ]
      }
    ],
    "edges": [
      {
        "source": "simulation.interface/output/color",
        "target": "camera_python/isaac.alice.PyCodelet/color"
      },
      {
        "source": "navigation.subgraph/interface/feedback",
        "target": "goals.subgraph/interface/feedback"
      },
      {
        "source": "goals.subgraph/interface/goal",
        "target": "navigation.subgraph/interface/goal"
      },
      {
        "source": "simulation.interface/noisy/flatscan",
        "target": "navigation.subgraph/interface/flatscan_for_localization"
      },
      {
        "source": "simulation.interface/noisy/flatscan",
        "target": "navigation.subgraph/interface/flatscan_for_obstacles"
      },
      {
        "source": "simulation.interface/output/base_state",
        "target": "navigation.subgraph/interface/state"
      },
      {
        "source": "simulation.interface/output/imu_raw",
        "target": "navigation.subgraph/interface/imu_raw"
      },
      {
        "source": "navigation.subgraph/interface/command",
        "target": "simulation.interface/input/base_command"
      },
      {
        "source": "simulation.interface/output/color",
        "target": "camera_viewer/color_viewer/color_listener"
      },
      {
        "source": "simulation.interface/output/depth",
        "target": "camera_viewer/depth_viewer/depth_listener"
      },
      {
        "source": "navigation.planner.global_plan_smoother/smoother/smooth_plan",
        "target": "simulation.interface/sight/global_plan"
      },
      {
        "source": "navigation.control.lqr/isaac.planner.DifferentialBaseLqrPlanner/plan",
        "target": "simulation.interface/sight/local_plan"
      }
    ]
  },
  "config": {
    "behavior_main": {
      "MemorySequenceBehavior": {
        "tick_period": "10Hz"
      },
      "NodeGroup": {
        "node_names": [
          "simulation.scenario_manager",
          "navigation.localization.localize"
        ],
        "tick_period": "10Hz"
      }
    },
    "navigation.localization.localize": {
      "disable_automatic_start": true
    },
    "goals.goal_behavior": {
      "isaac.navigation.SelectorBehavior": {
        "desired_behavior": "random"
      }
    },
    "navigation.imu_odometry.odometry": {
      "DifferentialBaseWheelImuOdometry": {
        "use_imu": false
      }
    },
    "goals.pose_as_goal": {
      "pose_as_goal_frame": {
        "lhs_frame": "unity"
      }
    },
    "camera_viewer": {
      "color_viewer": {
        "target_fps": 20,
        "reduce_scale": 4
      },
      "depth_viewer": {
        "colormap": [
          [
            128,
            0,
            0
          ],
          [
            255,
            0,
            0
          ],
          [
            255,
            255,
            0
          ],
          [
            0,
            255,
            255
          ],
          [
            0,
            0,
            255
          ],
          [
            0,
            0,
            128
          ]
        ],
        "min_visualization_depth": 0,
        "max_visualization_depth": 20,
        "target_fps": 20,
        "reduce_scale": 4
      }
    }
  }
}

camera_python.py:

from engine.pyalice import *

# A Python codelet for proportional control
# For comparison, please see the same logic in C++ at "ProportionalControlCpp.cpp".
#
# We receive odometry information, from which we extract the x position.
# Then, using refence and gain parameters that are provided by the user,
# we compute and publish a linear speed command using `control = gain * (reference - position)`
class CameraPython(Codelet):
    def start(self):
        print("Please head to the Sight website at <IP>:<PORT> to see how I am doing.")
        print("<IP> is the Internet Protocol address where the app is running,")
        print("and <PORT> is set in the config file, typically to '3000'.")
        print("By default, local link is 'localhost:3000'.")

        self.tick_periodically(0.01)

    def tick(self):
        print("Ticking...")
        pass

def main():
    app = Application(app_filename = "apps/navsim/navsim_navigate.app.json")
    app.register({"camera_python": CameraPython})
    app.start_wait_stop()

if __name__ == '__main__':
    main()

BUILD:

load("//engine/build:isaac.bzl", "isaac_pkg")

py_binary(
    name = "camera_python",
    srcs = [
        "__init__.py",
        "camera_python.py",
    ],
    data = [
      "navsim_navigate.app.json",
      "//apps/navsim/multirobot/configs:navigate_config",

      "//apps:py_init",
      "//apps/tutorials:py_init",

      "//packages/navsim/apps:navsim_subgraph",
      "//packages/navigation/apps:differential_base_navigation_subgraph",
      "//packages/navigation/apps:goal_generators_subgraph",

      "//apps/assets/maps",
      "//packages/map:libmap_module.so",
      "//packages/viewers:libviewers_module.so",
      "//packages/navigation:libnavigation_module.so"
    ],
    deps = [
        "//engine/pyalice",
    ],

    visibility = ["//visibility:public"],
)

isaac_pkg(
    name = "camera_python-pkg",
    srcs = ["camera_python"],
)

I assume that my BUILD file is not importing everything that is required, but I failed to find the other requirements.

A related question but less urgent, is it possible to build a self-contained python binary and import that into an existing application (such as navsim_navigate)?

I greatly appreciate any help, thank you!

Hi iDekken,

The error: No node with name ‘map’ is due to missing map files that are used by the navsim_navigate app.

I can see in your BUILD file that you are referring to “//apps/assets/maps” instead it should be “//packages/navsim/maps”

Also, since you are using navsim_navigate.app.json, you would need to add the respective robot models to run the application. You can do that by adding the following in your BUILD file : “//packages/navsim/robots”

And when you run the application, you need to provide the following flag which link maps and robots to the application
–more packages/navsim/robots/<robot_name>.json,packages/navsim/maps/<map_name>.json

1 Like