Show EOL distros: 

nav2d: nav2d_exploration | nav2d_karto | nav2d_localizer | nav2d_msgs | nav2d_navigator | nav2d_operator | nav2d_remote | nav2d_tutorials

Package Summary

This package provides a lightweight, purely reactive obstacle-avoidance module for mobile robots moving in a planar environment. The operator node works by evaluating a set of predefined motion primitives based on a local costmap and a desired direction. The best evaluated motion command will be send to the mobile base.

nav2d: nav2d_exploration | nav2d_karto | nav2d_localizer | nav2d_msgs | nav2d_navigator | nav2d_operator | nav2d_remote | nav2d_tutorials

Package Summary

The operator is a lightweight, purely reactive obstacle-avoidance module for mobile robots moving in a planar environment. The operator node works by evaluating a set of predefined motion primitives based on a local costmap and a desired direction. The best evaluated motion command will be send to the mobile base.

  • Maintainer status: developed
  • Maintainer: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • Author: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • License: GPLv3
  • Source: git https://github.com/skasperski/navigation_2d.git (branch: hydro)
nav2d: nav2d_exploration | nav2d_karto | nav2d_localizer | nav2d_msgs | nav2d_navigator | nav2d_operator | nav2d_remote | nav2d_tutorials

Package Summary

The operator is a lightweight, purely reactive obstacle-avoidance module for mobile robots moving in a planar environment. The operator node works by evaluating a set of predefined motion primitives based on a local costmap and a desired direction. The best evaluated motion command will be send to the mobile base.

  • Maintainer status: maintained
  • Maintainer: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • Author: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • License: GPLv3
  • Source: git https://github.com/skasperski/navigation_2d.git (branch: indigo)
nav2d: nav2d_exploration | nav2d_karto | nav2d_localizer | nav2d_msgs | nav2d_navigator | nav2d_operator | nav2d_remote | nav2d_tutorials

Package Summary

The operator is a lightweight, purely reactive obstacle-avoidance module for mobile robots moving in a planar environment. The operator node works by evaluating a set of predefined motion primitives based on a local costmap and a desired direction. The best evaluated motion command will be send to the mobile base.

  • Maintainer status: maintained
  • Maintainer: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • Author: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • License: GPLv3
  • Source: git https://github.com/skasperski/navigation_2d.git (branch: jade)
nav2d: nav2d_exploration | nav2d_karto | nav2d_localizer | nav2d_msgs | nav2d_navigator | nav2d_operator | nav2d_remote | nav2d_tutorials

Package Summary

The operator is a lightweight, purely reactive obstacle-avoidance module for mobile robots moving in a planar environment. The operator node works by evaluating a set of predefined motion primitives based on a local costmap and a desired direction. The best evaluated motion command will be send to the mobile base.

  • Maintainer status: maintained
  • Maintainer: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • Author: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • License: GPLv3
  • Source: git https://github.com/skasperski/navigation_2d.git (branch: kinetic)
nav2d: nav2d_exploration | nav2d_karto | nav2d_localizer | nav2d_msgs | nav2d_navigator | nav2d_operator | nav2d_remote | nav2d_tutorials

Package Summary

The operator is a lightweight, purely reactive obstacle-avoidance module for mobile robots moving in a planar environment. The operator node works by evaluating a set of predefined motion primitives based on a local costmap and a desired direction. The best evaluated motion command will be send to the mobile base.

  • Maintainer status: maintained
  • Maintainer: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • Author: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • License: GPLv3
  • Source: git https://github.com/skasperski/navigation_2d.git (branch: lunar)
nav2d: nav2d_exploration | nav2d_karto | nav2d_localizer | nav2d_msgs | nav2d_navigator | nav2d_operator | nav2d_remote | nav2d_tutorials

Package Summary

The operator is a lightweight, purely reactive obstacle-avoidance module for mobile robots moving in a planar environment. The operator node works by evaluating a set of predefined motion primitives based on a local costmap and a desired direction. The best evaluated motion command will be send to the mobile base.

  • Maintainer status: maintained
  • Maintainer: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • Author: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • License: GPLv3
  • Source: git https://github.com/skasperski/navigation_2d.git (branch: melodic)
nav2d: nav2d_exploration | nav2d_karto | nav2d_localizer | nav2d_msgs | nav2d_navigator | nav2d_operator | nav2d_remote | nav2d_tutorials

Package Summary

The operator is a lightweight, purely reactive obstacle-avoidance module for mobile robots moving in a planar environment. The operator node works by evaluating a set of predefined motion primitives based on a local costmap and a desired direction. The best evaluated motion command will be send to the mobile base.

  • Maintainer status: maintained
  • Maintainer: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • Author: Sebastian Kasperski <sebastian.kasperski AT dfki DOT de>
  • License: GPLv3
  • Source: git https://github.com/skasperski/navigation_2d.git (branch: noetic)

Example

See the Operator Tutorial for an example how to setup the Operator in Stage and use a Joystick to simulate commands from a higher level node.

ROS Interface

operator

The operator takes motion commands from a path planner and outputs control commands to the robot hardware avoiding obstacles in front of the robot.

Subscribed Topics

scan (sensor_msgs/LaserScan)
  • Laser scans to update local costmap.
tf (tf/tfMessage)
  • Transforms.
cmd (nav2d_operator/cmd)
  • Motion command comming from a higher level node, e.g. a path planner. Velocity ranges from full speed backward (-1.0) over stop (0.0) to full speed forward (1.0). Turn ranges from maximum left (-1.0, turn in place ccw) over straight (0) to maximum right (1.0, turn in place cw). The parameter Mode defines how to handle obstacles, either by avoiding them (0) or stopping in front of them (1).

Published Topics

cmd_vel (geometry_msgs/Twist)
  • Control command to robot platform.
~desired (nav_msgs/GridCells)
  • Visualizes the received input command.
~route (nav_msgs/GridCells)
  • Visualizes the control command send to the robot.
~local_map/costmap (nav_msgs/OccupancyGrid)
  • Visualizes the internal Costmap2D.

Parameters

~max_free_space (double, default: 5.0)
  • Maximum considered trajectory length. All turn directions with longer trajectories will have an equal distance-value of 1.0.
~safety_decay (double, default: 0.95)
  • Obstacles will be discounted by this value for every cell distance in the costmap. A lower value (<1.0) causes the robot to avoid obstacles later and ignore obstacles that are far away.
~max_velocity (double, default: 1.0)
  • Maximum velocity command to be send to the robot when no obstacles present. A value of 1.0 means 100% of the platforms own max speed.
~safety_weight (int, default: 1)
  • Relative influence of a trajectories distance to obstacles.
~distance_weight (int, default: 1)
  • Relative influence of free space in front of the robot.
~conformance_weight (int, default: 1)
  • Relative influence of the conformance with the desired turn direction from path planner etc.
~continue_weight (int, default: 1)
  • Relative influence of the continuity of control commands.
~publish_route (bool, default: false)
  • Whether to publish the desired and route topics.

Wiki: nav2d_operator (last edited 2014-03-25 14:16:35 by SebastianKasperski)