Only released in EOL distros:  

Package Summary

riskrrt is a risk-based rapidly exploring random tree algorithm for human aware navigation

  • Maintainer status: maintained
  • Maintainer: Procopio Silveira <procopio.silveira-stein AT inria DOT fr>
  • Author: Gregoire Vignon <gregoire.vignon AT inria DOT fr>
  • License: BSD
  • Source: git https://github.com/spalanza/riskrrt_ros.git (branch: master)

Example scenarios

Some example scenarios can be run using:

roslaunch riskrrt scenario_name.launch

Available scenarios:

  • corridor
  • D_corridor
  • airport
  • empty_airport
  • back_forth
  • crossing
  • frontal
  • inria_hall
  • test

Nodes

controller

a path following node for differential drive robots

Subscribed Topics

traj (riskrrt/Trajectory)
  • robot trajectory
amcl_pose (geometry_msgs/PoseWithCovarianceStamped)
  • robot pose

Published Topics

controller_feedback (std_msgs/Bool)
  • controller feedback, true as long as robot is on trajectory
cmd_vel (geometry_msgs/Twist)
  • velocity commands

goal_pub

an automatic goal publisher

Published Topics

goal (geometry_msgs/PoseStamped)
  • robot final goal

og_builder*

some occupancy grid array publishers examples

Subscribed Topics

map (nav_msgs/OccupancyGrid)
  • static map
robot_*/base_pose_ground_truth (nav_msgs/Odometry)
  • mobile obstacles poses

Published Topics

robot_*/cmd_vel (geometry_msgs/Twist)
  • mobile obstacles velocities
ogarray (riskrrt/OccupancyGridArray)
  • occupancy grid array

planner

the riskrrt planner

Subscribed Topics

ogarray (riskrrt/OccupancyGridArray)
  • occupancy grid array
goal (geometry_msgs/PoseStamped)
  • robot final goal
controller_feedback (std_msgs/Bool)
  • controller feedback
amcl_pose (geometry_msgs/PoseWithCovarianceStamped)
  • robot pose
odom (nav_msgs/Odometry)
  • robot odometry

Published Topics

traj (riskrrt/Trajectory)
  • robot trajectory

Parameters

~timeStep (double)

  • time step between each node (s), should be used as the time gap between each grid if using a custom OccupancyGridArray publisher
~maxDepth (int)
  • maximum depth a node can have, should be used to set the occupancy grid array size if using a custom OccupancyGridArray publisher
~nv (int)
  • discretization of the robot's linear speed, used to create the set of possible controls from a node
~nphi (int)
  • discretization of the robot's angular speed, used to create the set of possible controls from a node
~threshold (double)
  • maximum risk value a node can have to be considered free
~socialWeight (double)
  • weight of the risk component in the computation of the node's score
~rotationWeight (double)
  • weight of the node's orientation toward the goal (compared to the distance)
~growTime (double)
  • time allocated to the tree growth between map updates (s)
~bias (double)
  • percentage of the time the final goal is chosen as random goal
~windowSize (double)
  • size of the window from which to pick a random goal (m)
~goalTh (double)
  • maximum distance the robot can be from the final goal to consider the goal reached (m)
~robotLength (double)
  • robot lenght (m)
~robotWidth (double)
  • robot width (m)
~vMin (double)
  • minimum robot linear speed (m/s), set it to 0 or a negative value to allow reverse
~vMax (double)
  • maximum robot linear speed (m/s)
~accMax (double)
  • maximum linear acceleration (m/s²)
~omegaMax (double)
  • maximum angular speed (rad/s)
~accOmegaMax (double)
  • maximum angular acceleration (rad/s²)

Wiki: riskrrt (last edited 2015-09-22 00:14:56 by GregoireVignon)