Holonomic planer does not drive backwards

Hey,

when using the holonomic modules, the robot never reverses (in simulation).

Does someone has an idea why?

Thanks Markus

Hi Markus,

Would you provide more information please? Which Isaac SDK version are you using? Which app are you running? Which simulation, which scene, and which robot are you using?

Best,
Oguz

1 Like

Hi Oguz,

sorry for the lack of information in the first post.
I’m running the “navsim/navigate” app (changes to holonomic modules) in Isaac20.1 with the Unity (19.3) simulator.
My robot is a custom robot with a lidar on top.
Here are some screenshots of the movement:
Instead of driving straight backwards the robot wiggles it self backwards:






Best,
Markus

Hi Markus,

Did you change the minimum speed? I think the default value might be close to 0 (-0.05 or -0.1).

How is the path generated? Are you using the Global Planner or using your own planner? If you can try to have a codelet that outputs a simple path with 2 waypoints (current position + some position a little backward), it would help see if the issue come from the Global Planner or the Local Planner.

Regards,
Ben

1 Like

Hi Ben,

No, the min_speed is not set. But i cant find in the documentation what the default value for the HolonomicBaseLqrPlanner is.
I use the default HolonomicBaseLqrPlanner
I will try my luck writing a codelet for the path and report back
Best,
Markus

The default min_speed seems to be -0.05 in HolonomicBaseLqrPlanner, however it’s possible your config file override it.
I would start by changing this value.

You can either change it live in the config using sight. (the “Application Configuration” is on the right panel, you can use the input box on top to search for min_speed). Or you can change the JSON file of your app directly.

Regards,
Ben

1 Like

Hi Ben,
thanks for the advice! i changed it to -10 and it speed up the process (driving 2m straigt back) from 7min to 2 min.
It still takes a strange route…can you spot any wrong setting in my video?

While running i get a lot if errors in the terminal that the planner can’t find valid paths:


Best,
Markus

one more question:
how do i create a list of DifferentialStates?
I’m struggling to create the suggested codelet to publish a simple plan for testing.

if (active)
{
auto proto = tx_plan().initProto();
proto.setPlanFrame(“robot”);
proto.setStates();
tx_plan().publish();
LOG_INFO(“Plan send”);
set_active(false);
}

Thanks,
Markus

Hi Markus,

I notice a few things that can be potential issue:

  • Your speed seems much higher than what we have being testing so far (10m/s), this probably requiring some tuning. Make sure the speed is accurate, the map seems small to navigate that fast, but it’s hard for me.
  • Make sure your local_map around the robot is big enough to contain the path. At 10m/s for 5s (default) you would want your local_map to be 100m long… You can reduce the horizon window, and increase the size of the pixel of the local map (if you are indeed moving at 10m/s, then you probably don’t need 5cm accuracy for the obstacles as you probably want to keep a bigger distance).

I think the issue might be due to the high speed. Maybe limit the speed when moving backward to 1m/s to see if it improves or not. Then you might have to spend some time tuning unfortunately.

Regarding your second question:

  auto plans = tx_plan().initProto();
  plans.initStates(num_states);
  for (size_t idx = 0; idx < num_states; idx++) {
    auto state_builder = plans.getStates()[idx];
    const auto& state = states(idx);  // Whichever structure you use to store the different state.
    state_builder.setPositionX(state[kPosX]);
    state_builder.setPositionY(state[kPosY]);
    state_builder.setHeading(state[kAngle]);
    state_builder.setSpeedX(state[kSpeedX]);
    state_builder.setSpeedY(state[kSpeedY])
    state_builder.setAngularSpeed(state[kAngleDerivative]);
    state_builder.setTimestamp(start_time + static_cast<double>(idx) * delta_time);
  }
  plans.setPlanFrame("robot");
  tx_plan().publish(timestamp);

I hope this help.

Regards,
Ben

1 Like

Hi Ben,

sorry for the confusion with the 10m/s value.
originally it was -0.05 and needed 7 min to drive 2m backwards in a straight line.
i then changed it to ±1 m/s and the time improved to 2 minutes. To test it further it increased it to ±10 m/s but there was no improvement to the ±1 m/s value.
Normally the Robot would drive around 1.6 m/s top speed.
But your guess with the local map being to small for the robot (2m*5m) fixed the problem. I centered the map around the robot (offset [0.5, 0.5]) and changed the size to 512x512.

Thanks for your help @Ben_B and @OguzSaglam