Unity-Technologies/Robotics-Nav2-SLAM-Example

Topic '/goal_pose; is not registered problem

howard1414 opened this issue · 8 comments

I'm trying to making a click to navigation function , already referenced the WaypointIntergrationTest.cs .
My code look like this:

The object setup are same as the testing script provide in the example.

//ROS Config
    ROSConnection ROS;
    const string k_RobotTag = "robot";
    const string k_RobotBaseName = "base_footprint/base_link";
    const string k_GoalPoseFrameId = "map";
    const string k_GoalPoseTopic = "/goal_pose";
    static readonly string k_GoalPoseMessageName = MessageRegistry.GetRosMessageName<RosMessageTypes.Geometry.PoseStampedMsg>();
    const float k_Nav2InitializeTime = 5.0f;
    const float k_SleepBetweenWaypointsTime = 2.0f;
    const float k_MinimumSpeedExpected = 0.15f;
    const float k_DistanceSuccessThreshold = 0.4f;

Here's the parameter setup.

void Start()
    {
        //Init ROS
        print("init ROS");
        ROS = ROSConnection.instance;
        ROS.ConnectOnStart = true;
        ConnectionCheck();
        ROS.RegisterPublisher(k_GoalPoseTopic, k_GoalPoseMessageName);   
      
        //Init button
        Button btn = GameObject.Find("Navi_Button").GetComponent<Button>();
        btn.onClick.AddListener(Onclick);
    }

Here's the update function , include the ROS message sending.

void Update()
    {
        if (Input.GetMouseButtonDown(0) && pass)
        {
            Plane plane = new Plane(Vector3.up, 0);
            float distance;
            Ray ray = Camera.main.ScreenPointToRay(Input.mousePosition);
            if (plane.Raycast(ray, out distance))
            {
                worldPosition = ray.GetPoint(distance);
            }
            pass = false;
            worldPosition.y = 0.0f;
            print(worldPosition);
            GoalObj.transform.position = worldPosition;     
            ROS.Send(k_GoalPoseTopic, ToRosMsg(GoalObj.transform));
        }
    }

Using the codes above , got the Topic '/goal_pose' is not registered! Known topics are: dict_keys(['cmd_vel', '/tf', 'clock', '/scan']) error , and the navigation to the point where I click only works randomly

Am I missing something?

Hi @howard1414, thanks for testing the navigation function. I have created an internal ticket AIRO-1215 and we will follow up to investigate the issue.

Hi @howard1414, I've tried your scripts and could replicate the issue. It seems that the variable k_GoalPoseMessageName will be reset to an empty string when you enter play mode in Unity Editor, which fails the ROS.RegisterPublisher(). You may want to move the string initialization to the Start() so that it could register the /goal_pose topic. Please let us know if it works for you?

Hi @howard1414, I've tried your scripts and could replicate the issue. It seems that the variable k_GoalPoseMessageName will be reset to an empty string when you enter play mode in Unity Editor, which fails the ROS.RegisterPublisher(). You may want to move the string initialization to the Start() so that it could register the /goal_pose topic. Please let us know if it works for you?

After moving the initialization to the Start(),the problem has solved.

And I'd like to ask , if I want to using the map server services to save the map(.pgm/.ppm) to local disk , is there any example for this ?
Currently I can only found the example for how to using the service to request a position and save it from the ROS2 , seems like there is non of the example for how to save the file without using the command line.

Thanks,

Hey @howard1414 -- have you found a command line example that works for your use case? If so, can you share it here? I may be able to help you translate it into something that can be invoked from within the program.

I'm trying to run these command in the Unity, already wrote a pgm/ppm file shader and can show the map file on the plane , and still finding a alternative method to stream the slam map to the Unity scene.

ros2 service call /map_server/load_map nav2_msgs/srv/LoadMap "{map_url: /ros/maps/map.yaml}"
ros2 service call /map_saver/save_map nav2_msgs/srv/SaveMap "{map_topic: map, map_url: my_map, image_format: pgm, map_mode: trinary, free_thresh: 0.25, occupied_thresh: 0.65}"

Thanks,

Ok so if we break down what these two lines are doing, they are both structured like this:
ros2 service call <service_topic> <message_type> <message_data>
In order to replicate this in Unity, you need to do a few things:

  1. Pull the appropriate message definitions into your project. It looks like those are here. It'll be easiest to drop the whole nav2_msgs folder into your Project, and Unity should handle generating the appropriate C# code for those files.
  2. Call RegisterRosService using the appropriate service topic and message type.
  3. Construct your messages with the fields populated the same way they are in those CLI calls you've posted and use SendServiceMessage to send the requests. I believe you can simply ignore the responses in this case.

It looks like you could also follow the same pattern to periodically call the GetCostmap service to get the costmap in Unity. Also note that for this example I'm not sure the nav2_bringup launch file we're hooking launches the map saver service named explicitly map_saver. If you do a ros2 service list inside the docker container after launching our example, you should see a list of services that might do what you want, though. There is a /slam_toolbox/save_map service, and a /global_costmap/get_costmap, for example.

It looks like you could also follow the same pattern to periodically call the GetCostmap service to get the costmap in Unity. Also note that for this example I'm not sure the nav2_bringup launch file we're hooking launches the map saver service named explicitly map_saver. If you do a ros2 service list inside the docker container after launching our example, you should see a list of services that might do what you want, though. There is a /slam_toolbox/save_map service, and a /global_costmap/get_costmap, for example.

I'll try it out to make the service available in my project.
Thanks for sharing the useful explanation !